|
Resurgence (PY2022)
Codebase for the Husky Robotics 2021-2022 rover Resurgence
|
Collection of functions for manipulating a motor. More...
Namespaces | |
| namespace | types |
| Types for use in the world interface. | |
Classes | |
| class | base_motor |
| An abstract motor class. More... | |
| class | can_motor |
| struct | encparams_t |
| struct | pidcoef_t |
| A struct containing a set of PID coefficients. More... | |
| struct | potparams_t |
| Represents parameters defining a potentiometer scale. More... | |
| class | sim_motor |
Typedefs | |
| using | callbackid_t = unsigned long long |
Enumerations | |
| enum class | WorldInterface { real , sim2d , sim3d , noop } |
| An enum which defines the possible types of world interfaces. More... | |
| enum class | motorid_t |
| The motors on the robot. | |
Functions | |
| DataPoint< Eigen::Quaterniond > | readIMU () |
| Read the rover orientation from the IMU. | |
| double | setCmdVel (double dtheta, double dx) |
| Request the robot to drive at the given velocities. | |
| double | setTankCmdVel (double left, double right) |
| Request the robot to drive in tank style, where each side is controlled individually. | |
| void | setJointPower (types::jointid_t joint, double power) |
| Set the power of the specified joint. | |
| void | setJointPos (types::jointid_t joint, int32_t targetPos) |
| Set the position of the specified joint. | |
| types::DataPoint< int32_t > | getJointPos (robot::types::jointid_t joint) |
| void | setScienceServoPos (uint8_t servoNum, int32_t angle) |
| DataPoint< double > | readIMUHeading () |
| Read the current heading in the global map frame based on an IMU measurement. | |
| DataPoint< point_t > | readGPS () |
| Get the current position in the global map frame based on a GPS measurement. | |
| std::optional< point_t > | gpsToMeters (const navtypes::gpscoords_t &coord) |
| Convert GPS coordinates into a coordinate on the map frame. | |
| bool | gpsHasFix () |
| Check if the GPS sensor has acquired a fix. | |
| const DiffDriveKinematics & | driveKinematics () |
| void | world_interface_init (std::optional< std::reference_wrapper< net::websocket::SingleClientWSServer > > wsServer, bool initOnlyMotors=false) |
| Initialize the world interface. | |
| std::shared_ptr< robot::base_motor > | getMotor (robot::types::motorid_t motor) |
| Get a pointer to the motor object associated with the motor id. | |
| void | emergencyStop () |
| Emergency stop all motors. | |
| bool | isEmergencyStopped () |
| Check if the robot has been emergency stopped. | |
| landmarks_t | readLandmarks () |
| Read measurement from the CV system. | |
| DataPoint< pose_t > | getTruePose () |
| Get the ground truth pose, if available. | |
| void | setMotorPower (robot::types::motorid_t motor, double power) |
| Set the PWM command of the given motor. | |
| void | setMotorPos (robot::types::motorid_t motor, int32_t targetPos) |
| Set the target position of the motor. | |
| types::DataPoint< int32_t > | getMotorPos (robot::types::motorid_t motor) |
| Get the last reported position of the specified motor. | |
| void | setMotorVel (robot::types::motorid_t motor, int32_t targetVel) |
| Sets the velocity of the given motor. | |
| void | setIndicator (types::indication_t signal) |
| Set the robot indicator to indicate the given signal. | |
| callbackid_t | addLimitSwitchCallback (robot::types::motorid_t motor, const std::function< void(robot::types::motorid_t motor, robot::types::DataPoint< LimitSwitchData > limitSwitchData)> &callback) |
| void | removeLimitSwitchCallback (callbackid_t id) |
| constexpr std::chrono::milliseconds | TELEM_PERIOD (50) |
| The default telemetry period for motors. | |
| std::shared_ptr< types::CameraHandle > | openCamera (types::CameraID camID) |
| Opens Camera with id camID. | |
| std::unordered_set< CameraID > | getCameras () |
| Get the IDs of the currently supported cameras. | |
| bool | hasNewCameraFrame (types::CameraID camera, uint32_t oldFrameNum) |
| Check if a new camera frame from the specified camera is available. | |
| DataPoint< CameraFrame > | readCamera (types::CameraID camera) |
| Read the latest frame from the given camera. | |
| std::optional< cam::CameraParams > | getCameraIntrinsicParams (types::CameraID camera) |
| Get the intrinsic params of the specified camera, if it exists. | |
| std::optional< cv::Mat > | getCameraExtrinsicParams (types::CameraID camera) |
| Get the extrinsic params of the specified camera, if it exists. | |
| template<typename T> | |
| int | getIndex (const std::vector< T > &vec, const T &val) |
| void | setServoPos (robot::types::servoid_t servo, int32_t position) |
| void | setRequestedStepperTurnAngle (robot::types::stepperid_t stepper, int16_t angle) |
| void | setActuator (uint8_t value) |
| callbackid_t | addLimitSwitchCallback (robot::types::motorid_t motor, const std::function< void(robot::types::motorid_t motor, robot::types::DataPoint< robot::types::LimitSwitchData > limitSwitchData)> &callback) |
| template<unsigned long int N> | |
| types::DataPoint< navtypes::Vectord< N > > | getMotorPositionsRad (const std::array< types::motorid_t, N > &motors) |
| Get the positions in radians of multiple motors at the same time. | |
Variables | |
| const WorldInterface | WORLD_INTERFACE = WorldInterface::noop |
| The current world interface being used. | |
| constexpr auto | encMotors |
| constexpr double | FOURBAR_GEAR_RATIO = 71.71875 |
| constexpr auto | potMotors |
| constexpr auto | motorSerialIDMap |
| A mapping of motorids to their corresponding serial number. | |
| constexpr auto | motorGroupMap |
| constexpr auto | motorPIDMap |
| A mapping of PID controlled motors to their pid coefficients. | |
| constexpr auto | positive_pwm_scales |
| A mapping of motorids to power scale factors when commanded with positive power. | |
| constexpr auto | negative_pwm_scales |
| A mapping of motorids to power scale factors when commanded with negative power. | |
| std::unordered_map< robot::types::motorid_t, std::shared_ptr< robot::base_motor > > | motor_ptrs |
| constexpr double | WHEEL_BASE = 0.66 |
| constexpr double | EFF_WHEEL_BASE = 1.40 |
| constexpr double | WHEEL_RADIUS = 0.15 |
| constexpr double | PWM_FOR_1RAD_PER_SEC = 5000 |
| constexpr double | MAX_PWM = 20000 |
Collection of functions for manipulating a motor.
Collection of functions that allows interfacing with the hardware and the world.
|
strong |
An enum which defines the possible types of world interfaces.
| void robot::emergencyStop | ( | ) |
Emergency stop all motors.
After emergency stopping, all motors must be reinitialized.
| std::optional< cv::Mat > robot::getCameraExtrinsicParams | ( | types::CameraID | camera | ) |
Get the extrinsic params of the specified camera, if it exists.
| camera | The ID of the camera for which to get the extrinsic params. |
| std::optional< cam::CameraParams > robot::getCameraIntrinsicParams | ( | types::CameraID | camera | ) |
Get the intrinsic params of the specified camera, if it exists.
| camera | The ID of the camera for which to get the intrinsic params. |
| std::unordered_set< types::CameraID > robot::getCameras | ( | ) |
Get the IDs of the currently supported cameras.
| types::DataPoint< int32_t > robot::getJointPos | ( | types::jointid_t | joint | ) |
| joint | the jointid_t of the joint to get the position of. |
| std::shared_ptr< robot::base_motor > robot::getMotor | ( | robot::types::motorid_t | motor | ) |
Get a pointer to the motor object associated with the motor id.
| motor | The motor id to manipulate. |
| types::DataPoint< int32_t > robot::getMotorPos | ( | robot::types::motorid_t | motor | ) |
Get the last reported position of the specified motor.
| motor | The motor to get the position from. |
| types::DataPoint< navtypes::Vectord< N > > robot::getMotorPositionsRad | ( | const std::array< types::motorid_t, N > & | motors | ) |
Get the positions in radians of multiple motors at the same time.
This is useful for kinematics classes which expect motor positions as a vector.
| N | Number of motors. |
| motors | The motors to get the positions of. |
| types::DataPoint< navtypes::pose_t > robot::getTruePose | ( | ) |
Get the ground truth pose, if available.
This is only available in simulation.
| bool robot::gpsHasFix | ( | ) |
Check if the GPS sensor has acquired a fix.
| std::optional< navtypes::point_t > robot::gpsToMeters | ( | const navtypes::gpscoords_t & | coord | ) |
Convert GPS coordinates into a coordinate on the map frame.
| coord | The coord to transform into map space. |
| bool robot::hasNewCameraFrame | ( | types::CameraID | camera, |
| uint32_t | oldFrameNum ) |
Check if a new camera frame from the specified camera is available.
| camera | The ID of the camera to check |
| oldFrameNum | The frame number of the old frame. A camera frame is "new" if its id is different than this. |
| bool robot::isEmergencyStopped | ( | ) |
Check if the robot has been emergency stopped.
| std::shared_ptr< types::CameraHandle > robot::openCamera | ( | types::CameraID | camID | ) |
Opens Camera with id camID.
| camID | The camera id to open. |
| types::DataPoint< types::CameraFrame > robot::readCamera | ( | types::CameraID | camera | ) |
Read the latest frame from the given camera.
This is not guaranteed to change between calls, so use hasNewCameraFrame() to check if a new frame is available.
| camera | The ID of the camera to read from. |
| types::DataPoint< navtypes::point_t > robot::readGPS | ( | ) |
Get the current position in the global map frame based on a GPS measurement.
Note that these values are NOT lat/long. Note that for the map frame, +x=+lat,+y=-lon.
| types::DataPoint< Eigen::Quaterniond > robot::readIMU | ( | ) |
Read the rover orientation from the IMU.
| types::DataPoint< double > robot::readIMUHeading | ( | ) |
Read the current heading in the global map frame based on an IMU measurement.
Note that the heading is in radians, CCW, and 0=North.
| types::landmarks_t robot::readLandmarks | ( | ) |
Read measurement from the CV system.
As of now, returns a vector of fixed length, one for each post in the competition.
| double robot::setCmdVel | ( | double | dtheta, |
| double | dx ) |
Request the robot to drive at the given velocities.
| dtheta | The heading velocity. |
| dx | The forward velocity. |
| void robot::setIndicator | ( | types::indication_t | signal | ) |
Set the robot indicator to indicate the given signal.
| signal | The signal to display on the indicator. |
| void robot::setJointPos | ( | types::jointid_t | joint, |
| int32_t | targetPos ) |
Set the position of the specified joint.
| joint | the jointid_t of the joint to set the position of. |
| targetPos | the position to set the joint to, in millidegrees. |
| void robot::setJointPower | ( | types::jointid_t | joint, |
| double | power ) |
Set the power of the specified joint.
| joint | The joint to set the power of. |
| power | The power value to set, in the range [-1,1]. |
| void robot::setMotorPos | ( | robot::types::motorid_t | motor, |
| int32_t | targetPos ) |
Set the target position of the motor.
This will have no effect if the motor does not support PID.
| motor | The motor to set the target position of. |
| targetPos | The target position, in millidegrees. Refer to the specific motor for more information. |
| void robot::setMotorPower | ( | robot::types::motorid_t | motor, |
| double | power ) |
Set the PWM command of the given motor.
| motor | The motor to set the PWM of. |
| power | The power command, in the range [-1, 1] |
| void robot::setMotorVel | ( | robot::types::motorid_t | motor, |
| int32_t | targetVel ) |
Sets the velocity of the given motor.
| motor | The motor to set the target position of. |
| targetVel | The target velocity, in millidegrees per second. |
| double robot::setTankCmdVel | ( | double | left, |
| double | right ) |
Request the robot to drive in tank style, where each side is controlled individually.
| left | The left velocity. |
| right | The right velocity. |
| void robot::world_interface_init | ( | std::optional< std::reference_wrapper< net::websocket::SingleClientWSServer > > | wsServer, |
| bool | initOnlyMotors = false ) |
Initialize the world interface.
This method should only be called once, and must be called before any other world interface methods.
| wsServer | A reference to the websocket server to use for communication. If empty, components that require it will not be initialized. |
| initOnlyMotors | If true, only initialize the motors and not the rest of the world interface. |
|
constexpr |
|
constexpr |
|
constexpr |
A mapping of PID controlled motors to their pid coefficients.
|
constexpr |
A mapping of motorids to their corresponding serial number.
|
constexpr |
A mapping of motorids to power scale factors when commanded with negative power.
Negative values mean that the motor is inverted.
|
constexpr |
A mapping of motorids to power scale factors when commanded with positive power.
Negative values mean that the motor is inverted.
|
constexpr |