Classes | Public Member Functions | Public Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
MotorHardware Class Reference

#include <motor_hardware.h>

Inheritance diagram for MotorHardware:
Inheritance graph
[legend]

Classes

struct  Joint
 

Public Member Functions

int areWheelSpeedsLower (double wheelSpeedRadPerSec)
 
float calculateBatteryPercentage (float voltage, int cells, const float *type)
 
void clearCommands ()
 
void closePort ()
 
void forcePidParamUpdates ()
 
float getBatteryVoltage (void)
 
bool getEstopState (void)
 
void getMotorCurrents (double &currentLeft, double &currentRight)
 
int getOptionSwitch (void)
 
int getPidControlWord (void)
 
double getWheelGearRatio (void)
 
void getWheelJointPositions (double &leftWheelPosition, double &rightWheelPosition)
 
double getWheelTicksPerRadian (void)
 
 MotorHardware (ros::NodeHandle nh, NodeParams node_params, CommsParams serial_params, FirmwareParams firmware_params)
 
void nullWheelErrors (void)
 
bool openPort ()
 
void publishFirmwareInfo ()
 
void publishMotorState (void)
 
void readInputs (uint32_t index)
 
void requestFirmwareDate ()
 
void requestFirmwareVersion ()
 
void requestSystemEvents ()
 
void sendParams ()
 
void setDeadmanTimer (int32_t deadman)
 
void setDeadzoneEnable (int32_t deadzone_enable)
 
void setDebugLeds (bool led1, bool led2)
 
void setDriveType (int32_t drive_type)
 
void setEstopDetection (int32_t estop_detection)
 
void setEstopPidThreshold (int32_t estop_pid_threshold)
 
void setHardwareVersion (int32_t hardware_version)
 
void setMaxFwdSpeed (int32_t max_speed_fwd)
 
void setMaxPwm (int32_t max_pwm)
 
void setMaxRevSpeed (int32_t max_speed_rev)
 
void setOptionSwitchReg (int32_t option_switch)
 
void setParams (FirmwareParams firmware_params)
 
void setPidControl (int32_t pid_control)
 
void setSystemEvents (int32_t system_events)
 
void setWheelDirection (int32_t wheel_direction)
 
void setWheelGearRatio (double wheel_gear_ratio)
 
void setWheelJointVelocities (double leftWheelVelocity, double rightWheelVelocity)
 
void setWheelType (int32_t wheel_type)
 
void writeSpeeds ()
 
void writeSpeedsInRadians (double left_radians, double right_radians)
 
virtual ~MotorHardware ()
 
- Public Member Functions inherited from hardware_interface::RobotHW
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual bool init (ros::NodeHandle &, ros::NodeHandle &)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual void read (const ros::Time &, const ros::Duration &)
 
virtual void read (const ros::Time &, const ros::Duration &)
 
virtual SwitchState switchResult () const
 
virtual SwitchState switchResult (const ControllerInfo &) const
 
virtual void write (const ros::Time &, const ros::Duration &)
 
virtual void write (const ros::Time &, const ros::Duration &)
 
virtual ~RobotHW ()=default
 
- Public Member Functions inherited from hardware_interface::InterfaceManager
T * get ()
 
std::vector< std::string > getInterfaceResources (std::string iface_type) const
 
std::vector< std::string > getNames () const
 
void registerInterface (T *iface)
 
void registerInterfaceManager (InterfaceManager *iface_man)
 

Public Attributes

int deadman_enable
 
diagnostic_updater::Updater diag_updater
 
int drive_type
 
int estop_pid_threshold
 
int firmware_date
 
int firmware_options
 
int firmware_version
 
int hardware_version
 
int max_pwm
 
int max_speed_fwd
 
int max_speed_rev
 
int num_fw_params
 
int pid_control
 
int system_events
 
double wheel_gear_ratio
 
int wheel_type
 

Private Types

enum  MotorOrWheelNumber { Motor_M1 = 1, Motor_M2 = 2 }
 
enum  WheelJointLocation { Left = 0, Right = 1 }
 

Private Member Functions

void _addOdometryRequest (std::vector< MotorMessage > &commands) const
 
void _addVelocityRequest (std::vector< MotorMessage > &commands) const
 
double calculateRadiansFromTicks (int16_t ticks)
 
int16_t calculateSpeedFromRadians (double radians)
 
 FRIEND_TEST (MotorHardwareTests, nonZeroWriteSpeedsOutputs)
 
 FRIEND_TEST (MotorHardwareTests, odomUpdatesPosition)
 
 FRIEND_TEST (MotorHardwareTests, odomUpdatesPositionMax)
 

Private Attributes

ros::Publisher battery_state
 
int32_t deadman_timer
 
bool estop_motor_power_off
 
ros::Publisher firmware_state
 
FirmwareParams fw_params
 
hardware_interface::JointStateInterface joint_state_interface_
 
struct MotorHardware::Joint joints_ [2]
 
ros::Publisher leftCurrent
 
ros::Publisher leftError
 
ros::Publisher leftTickInterval
 
MotorDiagnostics motor_diag_
 
ros::Publisher motor_power_active
 
MotorSerialmotor_serial_
 
ros::Publisher motor_state
 
FirmwareParams prev_fw_params
 
ros::Publisher rightCurrent
 
ros::Publisher rightError
 
ros::Publisher rightTickInterval
 
int32_t sendPid_count
 
double ticks_per_radian
 
hardware_interface::VelocityJointInterface velocity_joint_interface_
 

Additional Inherited Members

- Public Types inherited from hardware_interface::RobotHW
enum  SwitchState { SwitchState::DONE, SwitchState::ONGOING, SwitchState::ERROR }
 
- Protected Types inherited from hardware_interface::InterfaceManager
typedef std::vector< InterfaceManager * > InterfaceManagerVector
 
typedef std::map< std::string, void * > InterfaceMap
 
typedef std::map< std::string, std::vector< std::string > > ResourceMap
 
typedef std::map< std::string, size_t > SizeMap
 
- Protected Attributes inherited from hardware_interface::InterfaceManager
std::vector< ResourceManagerBase * > interface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Detailed Description

Definition at line 133 of file motor_hardware.h.

Member Enumeration Documentation

◆ MotorOrWheelNumber

Enumerator
Motor_M1 
Motor_M2 

Definition at line 229 of file motor_hardware.h.

◆ WheelJointLocation

Enumerator
Left 
Right 

Definition at line 235 of file motor_hardware.h.

Constructor & Destructor Documentation

◆ MotorHardware()

MotorHardware::MotorHardware ( ros::NodeHandle  nh,
NodeParams  node_params,
CommsParams  serial_params,
FirmwareParams  firmware_params 
)

Definition at line 116 of file motor_hardware.cc.

◆ ~MotorHardware()

MotorHardware::~MotorHardware ( )
virtual

Definition at line 210 of file motor_hardware.cc.

Member Function Documentation

◆ _addOdometryRequest()

void MotorHardware::_addOdometryRequest ( std::vector< MotorMessage > &  commands) const
private

◆ _addVelocityRequest()

void MotorHardware::_addVelocityRequest ( std::vector< MotorMessage > &  commands) const
private

◆ areWheelSpeedsLower()

int MotorHardware::areWheelSpeedsLower ( double  wheelSpeedRadPerSec)

Definition at line 664 of file motor_hardware.cc.

◆ calculateBatteryPercentage()

float MotorHardware::calculateBatteryPercentage ( float  voltage,
int  cells,
const float *  type 
)

Definition at line 584 of file motor_hardware.cc.

◆ calculateRadiansFromTicks()

double MotorHardware::calculateRadiansFromTicks ( int16_t  ticks)
private

Definition at line 1133 of file motor_hardware.cc.

◆ calculateSpeedFromRadians()

int16_t MotorHardware::calculateSpeedFromRadians ( double  radians)
private

Definition at line 1116 of file motor_hardware.cc.

◆ clearCommands()

void MotorHardware::clearCommands ( )

Definition at line 223 of file motor_hardware.cc.

◆ closePort()

void MotorHardware::closePort ( )

Definition at line 214 of file motor_hardware.cc.

◆ forcePidParamUpdates()

void MotorHardware::forcePidParamUpdates ( )

Definition at line 954 of file motor_hardware.cc.

◆ FRIEND_TEST() [1/3]

MotorHardware::FRIEND_TEST ( MotorHardwareTests  ,
nonZeroWriteSpeedsOutputs   
)
private

◆ FRIEND_TEST() [2/3]

MotorHardware::FRIEND_TEST ( MotorHardwareTests  ,
odomUpdatesPosition   
)
private

◆ FRIEND_TEST() [3/3]

MotorHardware::FRIEND_TEST ( MotorHardwareTests  ,
odomUpdatesPositionMax   
)
private

◆ getBatteryVoltage()

float MotorHardware::getBatteryVoltage ( void  )

Definition at line 1083 of file motor_hardware.cc.

◆ getEstopState()

bool MotorHardware::getEstopState ( void  )

Definition at line 748 of file motor_hardware.cc.

◆ getMotorCurrents()

void MotorHardware::getMotorCurrents ( double &  currentLeft,
double &  currentRight 
)

Definition at line 707 of file motor_hardware.cc.

◆ getOptionSwitch()

int MotorHardware::getOptionSwitch ( void  )

Definition at line 862 of file motor_hardware.cc.

◆ getPidControlWord()

int MotorHardware::getPidControlWord ( void  )

Definition at line 853 of file motor_hardware.cc.

◆ getWheelGearRatio()

double MotorHardware::getWheelGearRatio ( void  )

Definition at line 783 of file motor_hardware.cc.

◆ getWheelJointPositions()

void MotorHardware::getWheelJointPositions ( double &  leftWheelPosition,
double &  rightWheelPosition 
)

Definition at line 230 of file motor_hardware.cc.

◆ getWheelTicksPerRadian()

double MotorHardware::getWheelTicksPerRadian ( void  )

Definition at line 788 of file motor_hardware.cc.

◆ nullWheelErrors()

void MotorHardware::nullWheelErrors ( void  )

Definition at line 832 of file motor_hardware.cc.

◆ openPort()

bool MotorHardware::openPort ( )

Definition at line 219 of file motor_hardware.cc.

◆ publishFirmwareInfo()

void MotorHardware::publishFirmwareInfo ( )

Definition at line 560 of file motor_hardware.cc.

◆ publishMotorState()

void MotorHardware::publishMotorState ( void  )

Definition at line 245 of file motor_hardware.cc.

◆ readInputs()

void MotorHardware::readInputs ( uint32_t  index)

Definition at line 268 of file motor_hardware.cc.

◆ requestFirmwareDate()

void MotorHardware::requestFirmwareDate ( )

Definition at line 689 of file motor_hardware.cc.

◆ requestFirmwareVersion()

void MotorHardware::requestFirmwareVersion ( )

Definition at line 680 of file motor_hardware.cc.

◆ requestSystemEvents()

void MotorHardware::requestSystemEvents ( )

Definition at line 698 of file motor_hardware.cc.

◆ sendParams()

void MotorHardware::sendParams ( )

Definition at line 967 of file motor_hardware.cc.

◆ setDeadmanTimer()

void MotorHardware::setDeadmanTimer ( int32_t  deadman)

Definition at line 921 of file motor_hardware.cc.

◆ setDeadzoneEnable()

void MotorHardware::setDeadzoneEnable ( int32_t  deadzone_enable)

Definition at line 930 of file motor_hardware.cc.

◆ setDebugLeds()

void MotorHardware::setDebugLeds ( bool  led1,
bool  led2 
)

Definition at line 1087 of file motor_hardware.cc.

◆ setDriveType()

void MotorHardware::setDriveType ( int32_t  drive_type)

Definition at line 811 of file motor_hardware.cc.

◆ setEstopDetection()

void MotorHardware::setEstopDetection ( int32_t  estop_detection)

Definition at line 738 of file motor_hardware.cc.

◆ setEstopPidThreshold()

void MotorHardware::setEstopPidThreshold ( int32_t  estop_pid_threshold)

Definition at line 728 of file motor_hardware.cc.

◆ setHardwareVersion()

void MotorHardware::setHardwareVersion ( int32_t  hardware_version)

Definition at line 717 of file motor_hardware.cc.

◆ setMaxFwdSpeed()

void MotorHardware::setMaxFwdSpeed ( int32_t  max_speed_fwd)

Definition at line 753 of file motor_hardware.cc.

◆ setMaxPwm()

void MotorHardware::setMaxPwm ( int32_t  max_pwm)

Definition at line 912 of file motor_hardware.cc.

◆ setMaxRevSpeed()

void MotorHardware::setMaxRevSpeed ( int32_t  max_speed_rev)

Definition at line 902 of file motor_hardware.cc.

◆ setOptionSwitchReg()

void MotorHardware::setOptionSwitchReg ( int32_t  option_switch)

Definition at line 882 of file motor_hardware.cc.

◆ setParams()

void MotorHardware::setParams ( FirmwareParams  firmware_params)

Definition at line 939 of file motor_hardware.cc.

◆ setPidControl()

void MotorHardware::setPidControl ( int32_t  pid_control)

Definition at line 821 of file motor_hardware.cc.

◆ setSystemEvents()

void MotorHardware::setSystemEvents ( int32_t  system_events)

Definition at line 892 of file motor_hardware.cc.

◆ setWheelDirection()

void MotorHardware::setWheelDirection ( int32_t  wheel_direction)

Definition at line 843 of file motor_hardware.cc.

◆ setWheelGearRatio()

void MotorHardware::setWheelGearRatio ( double  wheel_gear_ratio)

Definition at line 796 of file motor_hardware.cc.

◆ setWheelJointVelocities()

void MotorHardware::setWheelJointVelocities ( double  leftWheelVelocity,
double  rightWheelVelocity 
)

Definition at line 238 of file motor_hardware.cc.

◆ setWheelType()

void MotorHardware::setWheelType ( int32_t  wheel_type)

Definition at line 764 of file motor_hardware.cc.

◆ writeSpeeds()

void MotorHardware::writeSpeeds ( )

Definition at line 653 of file motor_hardware.cc.

◆ writeSpeedsInRadians()

void MotorHardware::writeSpeedsInRadians ( double  left_radians,
double  right_radians 
)

Definition at line 616 of file motor_hardware.cc.

Member Data Documentation

◆ battery_state

ros::Publisher MotorHardware::battery_state
private

Definition at line 250 of file motor_hardware.h.

◆ deadman_enable

int MotorHardware::deadman_enable

Definition at line 190 of file motor_hardware.h.

◆ deadman_timer

int32_t MotorHardware::deadman_timer
private

Definition at line 211 of file motor_hardware.h.

◆ diag_updater

diagnostic_updater::Updater MotorHardware::diag_updater

Definition at line 197 of file motor_hardware.h.

◆ drive_type

int MotorHardware::drive_type

Definition at line 194 of file motor_hardware.h.

◆ estop_motor_power_off

bool MotorHardware::estop_motor_power_off
private

Definition at line 217 of file motor_hardware.h.

◆ estop_pid_threshold

int MotorHardware::estop_pid_threshold

Definition at line 185 of file motor_hardware.h.

◆ firmware_date

int MotorHardware::firmware_date

Definition at line 181 of file motor_hardware.h.

◆ firmware_options

int MotorHardware::firmware_options

Definition at line 182 of file motor_hardware.h.

◆ firmware_state

ros::Publisher MotorHardware::firmware_state
private

Definition at line 249 of file motor_hardware.h.

◆ firmware_version

int MotorHardware::firmware_version

Definition at line 180 of file motor_hardware.h.

◆ fw_params

FirmwareParams MotorHardware::fw_params
private

Definition at line 208 of file motor_hardware.h.

◆ hardware_version

int MotorHardware::hardware_version

Definition at line 184 of file motor_hardware.h.

◆ joint_state_interface_

hardware_interface::JointStateInterface MotorHardware::joint_state_interface_
private

Definition at line 205 of file motor_hardware.h.

◆ joints_

struct MotorHardware::Joint MotorHardware::joints_[2]
private

◆ leftCurrent

ros::Publisher MotorHardware::leftCurrent
private

Definition at line 243 of file motor_hardware.h.

◆ leftError

ros::Publisher MotorHardware::leftError
private

Definition at line 240 of file motor_hardware.h.

◆ leftTickInterval

ros::Publisher MotorHardware::leftTickInterval
private

Definition at line 246 of file motor_hardware.h.

◆ max_pwm

int MotorHardware::max_pwm

Definition at line 188 of file motor_hardware.h.

◆ max_speed_fwd

int MotorHardware::max_speed_fwd

Definition at line 186 of file motor_hardware.h.

◆ max_speed_rev

int MotorHardware::max_speed_rev

Definition at line 187 of file motor_hardware.h.

◆ motor_diag_

MotorDiagnostics MotorHardware::motor_diag_
private

Definition at line 256 of file motor_hardware.h.

◆ motor_power_active

ros::Publisher MotorHardware::motor_power_active
private

Definition at line 251 of file motor_hardware.h.

◆ motor_serial_

MotorSerial* MotorHardware::motor_serial_
private

Definition at line 254 of file motor_hardware.h.

◆ motor_state

ros::Publisher MotorHardware::motor_state
private

Definition at line 252 of file motor_hardware.h.

◆ num_fw_params

int MotorHardware::num_fw_params

Definition at line 183 of file motor_hardware.h.

◆ pid_control

int MotorHardware::pid_control

Definition at line 189 of file motor_hardware.h.

◆ prev_fw_params

FirmwareParams MotorHardware::prev_fw_params
private

Definition at line 209 of file motor_hardware.h.

◆ rightCurrent

ros::Publisher MotorHardware::rightCurrent
private

Definition at line 244 of file motor_hardware.h.

◆ rightError

ros::Publisher MotorHardware::rightError
private

Definition at line 241 of file motor_hardware.h.

◆ rightTickInterval

ros::Publisher MotorHardware::rightTickInterval
private

Definition at line 247 of file motor_hardware.h.

◆ sendPid_count

int32_t MotorHardware::sendPid_count
private

Definition at line 215 of file motor_hardware.h.

◆ system_events

int MotorHardware::system_events

Definition at line 191 of file motor_hardware.h.

◆ ticks_per_radian

double MotorHardware::ticks_per_radian
private

Definition at line 213 of file motor_hardware.h.

◆ velocity_joint_interface_

hardware_interface::VelocityJointInterface MotorHardware::velocity_joint_interface_
private

Definition at line 206 of file motor_hardware.h.

◆ wheel_gear_ratio

double MotorHardware::wheel_gear_ratio

Definition at line 193 of file motor_hardware.h.

◆ wheel_type

int MotorHardware::wheel_type

Definition at line 192 of file motor_hardware.h.


The documentation for this class was generated from the following files:


ubiquity_motor
Author(s):
autogenerated on Thu Nov 16 2023 03:30:56