Resurgence (PY2022)
Codebase for the Husky Robotics 2021-2022 rover Resurgence
Loading...
Searching...
No Matches
robot Namespace Reference

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::QuaterniondreadIMU ()
 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_tgetJointPos (robot::types::jointid_t joint)
 
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 DiffDriveKinematicsdriveKinematics ()
 
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_motorgetMotor (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_tgetMotorPos (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::unordered_set< CameraIDgetCameras ()
 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< CameraFramereadCamera (types::CameraID camera)
 Read the latest frame from the given camera.
 
std::optional< cam::CameraParamsgetCameraIntrinsicParams (types::CameraID camera)
 Get the intrinsic params of the specified camera, if it exists.
 
std::optional< cv::MatgetCameraExtrinsicParams (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)
 
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 auto potMotors
 
constexpr auto motorSerialIDMap
 A mapping of motorids to their corresponding serial number.
 
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
 

Detailed Description

Collection of functions for manipulating a motor.

Collection of functions that allows interfacing with the hardware and the world.

Enumeration Type Documentation

◆ WorldInterface

enum class robot::WorldInterface
strong

An enum which defines the possible types of world interfaces.

See also
WORLD_INTERFACE

Function Documentation

◆ emergencyStop()

void robot::emergencyStop ( )

Emergency stop all motors.

After emergency stopping, all motors must be reinitialized.

◆ getCameraExtrinsicParams()

std::optional< cv::Mat > robot::getCameraExtrinsicParams ( types::CameraID camera)

Get the extrinsic params of the specified camera, if it exists.

Parameters
cameraThe ID of the camera for which to get the extrinsic params.
Returns
The extrinsic params if it exists, else an empty optional object.

◆ getCameraIntrinsicParams()

std::optional< cam::CameraParams > robot::getCameraIntrinsicParams ( types::CameraID camera)

Get the intrinsic params of the specified camera, if it exists.

Parameters
cameraThe ID of the camera for which to get the intrinsic params.
Returns
The intrinsic params if it exists, else an empty optional object.

◆ getCameras()

std::unordered_set< types::CameraID > robot::getCameras ( )

Get the IDs of the currently supported cameras.

Returns
The IDs of all cameras currently supported by the world interface, as a std::unordered_set.

◆ getJointPos()

types::DataPoint< int32_t > robot::getJointPos ( types::jointid_t joint)
Parameters
jointthe jointid_t of the joint to get the position of.
Returns
the position of the joint specified by the jointid_t argument joint, in millidegrees.

◆ getMotor()

Get a pointer to the motor object associated with the motor id.

Parameters
motorThe motor id to manipulate.
Returns
A shared pointer to the motor object

◆ getMotorPos()

types::DataPoint< int32_t > robot::getMotorPos ( robot::types::motorid_t motor)

Get the last reported position of the specified motor.

Parameters
motorThe motor to get the position from.
Returns
types::DataPoint<int32_t> The last reported position of the motor in millidegrees, if it exists. If the motor has not reported a position (because it hasn't been received yet or if it doesn't have an encoder) then an empty data point is returned.

◆ getMotorPositionsRad()

template<unsigned long int N>
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.

Template Parameters
NNumber of motors.
Parameters
motorsThe motors to get the positions of.
Returns
types::DataPoint<navtypes::Vectord<N>> The joint positions. This will be an empty data point if any of the requested motors do not have any associated data. The timestamp of this data point is the oldest timestamp of the requested motors.

◆ getTruePose()

types::DataPoint< navtypes::pose_t > robot::getTruePose ( )

Get the ground truth pose, if available.

This is only available in simulation.

Returns
DataPoint<pose_t> The ground truth pose, or an empty datapoint if unavailable.

◆ gpsHasFix()

bool robot::gpsHasFix ( )

Check if the GPS sensor has acquired a fix.

Returns
true iff the GPS has a fix

◆ gpsToMeters()

std::optional< navtypes::point_t > robot::gpsToMeters ( const navtypes::gpscoords_t & coord)

Convert GPS coordinates into a coordinate on the map frame.

Parameters
coordThe coord to transform into map space.
Returns
std::optional<point_t> The transformed point, or an empty datapoint if the GPS does not have a fix.

◆ hasNewCameraFrame()

bool robot::hasNewCameraFrame ( types::CameraID camera,
uint32_t oldFrameNum )

Check if a new camera frame from the specified camera is available.

Parameters
cameraThe ID of the camera to check
oldFrameNumThe frame number of the old frame. A camera frame is "new" if its id is different than this.
Returns
true iff a new camera frame is available.

◆ isEmergencyStopped()

bool robot::isEmergencyStopped ( )

Check if the robot has been emergency stopped.

Returns
If emergencyStop() has been called previously.

◆ readCamera()

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.

Parameters
cameraThe ID of the camera to read from.
Returns
DataPoint<CameraFrame> A datapoint containing the latest frame. If an error occurs or the ID is invalid, returns an invalid datapoint.

◆ readGPS()

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.

Returns
DataPoint<point_t> The last GPS reading, in the map space.

◆ readIMU()

types::DataPoint< Eigen::Quaterniond > robot::readIMU ( )

Read the rover orientation from the IMU.

Returns
types::DataPoint<Eigen::Quaterniond>

◆ readIMUHeading()

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.

Returns
DataPoint<double> The last heading reading, or none if measurement not available.

◆ readLandmarks()

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.

Returns
DataPoint<points_t> A vector of fixed lengths. Non-visible markers are denoted with {0,0,0}, while all nonzero points are visible marker. The index of a landmark in this vector is its id.

◆ setCmdVel()

double robot::setCmdVel ( double dtheta,
double dx )

Request the robot to drive at the given velocities.

Parameters
dthetaThe heading velocity.
dxThe forward velocity.
Returns
double If the requested velocities are too high, they will be scaled down. The returned value is the scale divisor. If no scaling was performed, 1 is returned.

◆ setIndicator()

void robot::setIndicator ( types::indication_t signal)

Set the robot indicator to indicate the given signal.

Parameters
signalThe signal to display on the indicator.

◆ setJointPos()

void robot::setJointPos ( types::jointid_t joint,
int32_t targetPos )

Set the position of the specified joint.

Parameters
jointthe jointid_t of the joint to set the position of.
targetPosthe position to set the joint to, in millidegrees.

◆ setJointPower()

void robot::setJointPower ( types::jointid_t joint,
double power )

Set the power of the specified joint.

Parameters
jointThe joint to set the power of.
powerThe power value to set, in the range [-1,1].

◆ setMotorPos()

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.

Parameters
motorThe motor to set the target position of.
targetPosThe target position, in millidegrees. Refer to the specific motor for more information.

◆ setMotorPower()

void robot::setMotorPower ( robot::types::motorid_t motor,
double power )

Set the PWM command of the given motor.

Parameters
motorThe motor to set the PWM of.
powerThe power command, in the range [-1, 1]

◆ setMotorVel()

void robot::setMotorVel ( robot::types::motorid_t motor,
int32_t targetVel )

Sets the velocity of the given motor.

Parameters
motorThe motor to set the target position of.
targetVelThe target velocity, in millidegrees per second.

◆ setTankCmdVel()

double robot::setTankCmdVel ( double left,
double right )

Request the robot to drive in tank style, where each side is controlled individually.

Parameters
leftThe left velocity.
rightThe right velocity.
Returns
double If the requested velocities are too high, they will be scaled down. The returned value is the scale divisor. If no scaling was performed, 1 is returned.

◆ world_interface_init()

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.

Parameters
wsServerA reference to the websocket server to use for communication. If empty, components that require it will not be initialized.
initOnlyMotorsIf true, only initialize the motors and not the rest of the world interface.

Variable Documentation

◆ encMotors

auto robot::encMotors
constexpr
Initial value:
= frozen::make_unordered_map<motorid_t, encparams_t>({
{motorid_t::shoulder,
{.isInverted = true,
.ppjr = 4590 * 1024 * 4,
.limitSwitchLow = Constants::arm::JOINT_LIMITS.at(robot::types::motorid_t::shoulder).first,
.limitSwitchHigh = Constants::arm::JOINT_LIMITS.at(robot::types::motorid_t::shoulder).second,
.zeroCalibrationPower = 0.4}}
})

◆ motorPIDMap

auto robot::motorPIDMap
constexpr
Initial value:
= frozen::make_unordered_map<motorid_t, pidcoef_t>(
{{motorid_t::shoulder, {70, 0, 0}},
{motorid_t::frontLeftSwerve, {2, 0, 0}},
{motorid_t::frontRightSwerve, {2, 0, 0}},
{motorid_t::rearLeftSwerve, {2, 0, 0}},
{motorid_t::rearRightSwerve, {2, 0, 0}}})

A mapping of PID controlled motors to their pid coefficients.

◆ motorSerialIDMap

auto robot::motorSerialIDMap
constexpr
Initial value:
= frozen::make_unordered_map<motorid_t, can::deviceserial_t>(
{{motorid_t::frontLeftWheel, DEVICE_SERIAL_MOTOR_CHASSIS_FL},
{motorid_t::frontRightWheel, DEVICE_SERIAL_MOTOR_CHASSIS_FR},
{motorid_t::rearLeftWheel, DEVICE_SERIAL_MOTOR_CHASSIS_BL},
{motorid_t::rearRightWheel, DEVICE_SERIAL_MOTOR_CHASSIS_BR},
{motorid_t::frontLeftSwerve, DEVICE_SERIAL_MOTOR_CHASSIS_FL_SW},
{motorid_t::frontRightSwerve, DEVICE_SERIAL_MOTOR_CHASSIS_FR_SW},
{motorid_t::rearLeftSwerve, DEVICE_SERIAL_MOTOR_CHASSIS_BL_SW},
{motorid_t::rearRightSwerve, DEVICE_SERIAL_MOTOR_CHASSIS_BR_SW},
{motorid_t::armBase, DEVICE_SERIAL_MOTOR_BASE},
{motorid_t::shoulder, DEVICE_SERIAL_MOTOR_SHOULDER},
{motorid_t::elbow, DEVICE_SERIAL_MOTOR_ELBOW},
{motorid_t::forearm, DEVICE_SERIAL_MOTOR_FOREARM},
{motorid_t::wristDiffLeft, DEVICE_SERIAL_MOTOR_WRIST_DIFF_LEFT},
{motorid_t::wristDiffRight, DEVICE_SERIAL_MOTOR_WRIST_DIFF_RIGHT},
{motorid_t::hand, DEVICE_SERIAL_MOTOR_HAND},
{motorid_t::activeSuspension, DEVICE_SERIAL_LINEAR_ACTUATOR},
{motorid_t::drillActuator, DEVICE_SERIAL_DRILL_ARM_MOTOR},
{motorid_t::drillMotor, DEVICE_SERIAL_DRILL_MOTOR}})

A mapping of motorids to their corresponding serial number.

◆ negative_pwm_scales

auto robot::negative_pwm_scales
constexpr
Initial value:
=
frozen::make_unordered_map<motorid_t, double>({{motorid_t::armBase, -0.25},
{motorid_t::shoulder, -1},
{motorid_t::elbow, -1},
{motorid_t::forearm, -0.2},
{motorid_t::wristDiffLeft, -0.1},
{motorid_t::wristDiffRight, 0.1},
{motorid_t::frontLeftWheel, 0.7},
{motorid_t::frontRightWheel, 0.7},
{motorid_t::rearLeftWheel, 0.7},
{motorid_t::rearRightWheel, 0.7},
{motorid_t::frontLeftSwerve, 1.0},
{motorid_t::frontRightSwerve, 1.0},
{motorid_t::rearLeftSwerve, 1.0},
{motorid_t::rearRightSwerve, 1.0},
{motorid_t::hand, -0.75},
{motorid_t::activeSuspension, -0.5},
{motorid_t::drillActuator, -0.5},
{motorid_t::drillMotor, 1.0}})

A mapping of motorids to power scale factors when commanded with negative power.

Negative values mean that the motor is inverted.

◆ positive_pwm_scales

auto robot::positive_pwm_scales
constexpr
Initial value:
=
frozen::make_unordered_map<motorid_t, double>({{motorid_t::armBase, -0.25},
{motorid_t::shoulder, -1},
{motorid_t::elbow, -1},
{motorid_t::forearm, -0.2},
{motorid_t::wristDiffLeft, -0.1},
{motorid_t::wristDiffRight, 0.1},
{motorid_t::frontLeftWheel, 0.7},
{motorid_t::frontRightWheel, 0.7},
{motorid_t::rearLeftWheel, 0.7},
{motorid_t::rearRightWheel, 0.7},
{motorid_t::frontLeftSwerve, 1.0},
{motorid_t::frontRightSwerve, 1.0},
{motorid_t::rearLeftSwerve, 1.0},
{motorid_t::rearRightSwerve, 1.0},
{motorid_t::hand, -0.75},
{motorid_t::activeSuspension, -0.5},
{motorid_t::drillActuator, -0.5},
{motorid_t::drillMotor, 1.0}})

A mapping of motorids to power scale factors when commanded with positive power.

Negative values mean that the motor is inverted.

◆ potMotors

auto robot::potMotors
constexpr
Initial value:
= frozen::make_unordered_map<motorid_t, potparams_t>({
{motorid_t::forearm,
{.adc_lo = 1208, .mdeg_lo = -180 * 1000, .adc_hi = 841, .mdeg_hi = 180 * 1000}},
{motorid_t::wristDiffLeft,
{.adc_lo = 0, .mdeg_lo = -100 * 0, .adc_hi = 0, .mdeg_hi = 100 * 0}},
{motorid_t::wristDiffRight,
{.adc_lo = 0, .mdeg_lo = -100 * 0, .adc_hi = 0, .mdeg_hi = 100 * 0}},
{motorid_t::frontLeftSwerve,
{.adc_lo = 1422, .mdeg_lo = -180 * 1000, .adc_hi = 656, .mdeg_hi = 180 * 1000}},
{motorid_t::frontRightSwerve,
{.adc_lo = 644, .mdeg_lo = -180 * 1000, .adc_hi = 1404, .mdeg_hi = 180 * 1000}},
{motorid_t::rearLeftSwerve,
{.adc_lo = 1260, .mdeg_lo = -180 * 1000, .adc_hi = 476, .mdeg_hi = 180 * 1000}},
{motorid_t::rearRightSwerve,
{.adc_lo = 1538, .mdeg_lo = -180 * 1000, .adc_hi = 767, .mdeg_hi = 180 * 1000}},
})