Classes | Public Member Functions | Public Attributes | 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

void clearCommands ()
 
bool getEstopState (void)
 
 MotorHardware (ros::NodeHandle nh, CommsParams serial_params, FirmwareParams firmware_params)
 
void readInputs ()
 
void requestFirmwareDate ()
 
void requestFirmwareVersion ()
 
void sendParams ()
 
void setDeadmanTimer (int32_t deadman)
 
void setDeadzoneEnable (int32_t deadzone_enable)
 
void setDebugLeds (bool led1, bool led2)
 
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 setParams (FirmwareParams firmware_params)
 
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 ControllerInfo &) const
 
virtual SwitchState switchResult () 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 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
 
- Public Attributes inherited from hardware_interface::RobotHW
 DONE
 
 ERROR
 
 ONGOING
 

Private Member Functions

void _addOdometryRequest (std::vector< MotorMessage > &commands) const
 
void _addVelocityRequest (std::vector< MotorMessage > &commands) const
 
double calculateRadiansFromTicks (int16_t ticks) const
 
int16_t calculateSpeedFromRadians (double radians) const
 
 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
 
FirmwareParams fw_params
 
hardware_interface::JointStateInterface joint_state_interface_
 
struct MotorHardware::Joint joints_ [2]
 
ros::Publisher leftError
 
MotorDiagnostics motor_diag_
 
ros::Publisher motor_power_active
 
MotorSerialmotor_serial_
 
FirmwareParams prev_fw_params
 
ros::Publisher rightError
 
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
 
- 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 98 of file motor_hardware.h.

Constructor & Destructor Documentation

◆ MotorHardware()

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

Definition at line 56 of file motor_hardware.cc.

◆ ~MotorHardware()

MotorHardware::~MotorHardware ( )
virtual

Definition at line 124 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

◆ calculateRadiansFromTicks()

double MotorHardware::calculateRadiansFromTicks ( int16_t  ticks) const
private

Definition at line 574 of file motor_hardware.cc.

◆ calculateSpeedFromRadians()

int16_t MotorHardware::calculateSpeedFromRadians ( double  radians) const
private

Definition at line 559 of file motor_hardware.cc.

◆ clearCommands()

void MotorHardware::clearCommands ( )

Definition at line 126 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

◆ getEstopState()

bool MotorHardware::getEstopState ( void  )

Definition at line 382 of file motor_hardware.cc.

◆ readInputs()

void MotorHardware::readInputs ( )

Definition at line 137 of file motor_hardware.cc.

◆ requestFirmwareDate()

void MotorHardware::requestFirmwareDate ( )

Definition at line 340 of file motor_hardware.cc.

◆ requestFirmwareVersion()

void MotorHardware::requestFirmwareVersion ( )

Definition at line 331 of file motor_hardware.cc.

◆ sendParams()

void MotorHardware::sendParams ( )

Definition at line 445 of file motor_hardware.cc.

◆ setDeadmanTimer()

void MotorHardware::setDeadmanTimer ( int32_t  deadman)

Definition at line 416 of file motor_hardware.cc.

◆ setDeadzoneEnable()

void MotorHardware::setDeadzoneEnable ( int32_t  deadzone_enable)

Definition at line 425 of file motor_hardware.cc.

◆ setDebugLeds()

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

Definition at line 530 of file motor_hardware.cc.

◆ setEstopDetection()

void MotorHardware::setEstopDetection ( int32_t  estop_detection)

Definition at line 372 of file motor_hardware.cc.

◆ setEstopPidThreshold()

void MotorHardware::setEstopPidThreshold ( int32_t  estop_pid_threshold)

Definition at line 362 of file motor_hardware.cc.

◆ setHardwareVersion()

void MotorHardware::setHardwareVersion ( int32_t  hardware_version)

Definition at line 352 of file motor_hardware.cc.

◆ setMaxFwdSpeed()

void MotorHardware::setMaxFwdSpeed ( int32_t  max_speed_fwd)

Definition at line 387 of file motor_hardware.cc.

◆ setMaxPwm()

void MotorHardware::setMaxPwm ( int32_t  max_pwm)

Definition at line 407 of file motor_hardware.cc.

◆ setMaxRevSpeed()

void MotorHardware::setMaxRevSpeed ( int32_t  max_speed_rev)

Definition at line 397 of file motor_hardware.cc.

◆ setParams()

void MotorHardware::setParams ( FirmwareParams  firmware_params)

Definition at line 434 of file motor_hardware.cc.

◆ writeSpeeds()

void MotorHardware::writeSpeeds ( )

Definition at line 322 of file motor_hardware.cc.

◆ writeSpeedsInRadians()

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

Definition at line 296 of file motor_hardware.cc.

Member Data Documentation

◆ battery_state

ros::Publisher MotorHardware::battery_state
private

Definition at line 165 of file motor_hardware.h.

◆ deadman_enable

int MotorHardware::deadman_enable

Definition at line 129 of file motor_hardware.h.

◆ deadman_timer

int32_t MotorHardware::deadman_timer
private

Definition at line 145 of file motor_hardware.h.

◆ diag_updater

diagnostic_updater::Updater MotorHardware::diag_updater

Definition at line 131 of file motor_hardware.h.

◆ estop_motor_power_off

bool MotorHardware::estop_motor_power_off
private

Definition at line 151 of file motor_hardware.h.

◆ estop_pid_threshold

int MotorHardware::estop_pid_threshold

Definition at line 125 of file motor_hardware.h.

◆ firmware_date

int MotorHardware::firmware_date

Definition at line 122 of file motor_hardware.h.

◆ firmware_options

int MotorHardware::firmware_options

Definition at line 123 of file motor_hardware.h.

◆ firmware_version

int MotorHardware::firmware_version

Definition at line 121 of file motor_hardware.h.

◆ fw_params

FirmwareParams MotorHardware::fw_params
private

Definition at line 142 of file motor_hardware.h.

◆ hardware_version

int MotorHardware::hardware_version

Definition at line 124 of file motor_hardware.h.

◆ joint_state_interface_

hardware_interface::JointStateInterface MotorHardware::joint_state_interface_
private

Definition at line 139 of file motor_hardware.h.

◆ joints_

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

◆ leftError

ros::Publisher MotorHardware::leftError
private

Definition at line 162 of file motor_hardware.h.

◆ max_pwm

int MotorHardware::max_pwm

Definition at line 128 of file motor_hardware.h.

◆ max_speed_fwd

int MotorHardware::max_speed_fwd

Definition at line 126 of file motor_hardware.h.

◆ max_speed_rev

int MotorHardware::max_speed_rev

Definition at line 127 of file motor_hardware.h.

◆ motor_diag_

MotorDiagnostics MotorHardware::motor_diag_
private

Definition at line 170 of file motor_hardware.h.

◆ motor_power_active

ros::Publisher MotorHardware::motor_power_active
private

Definition at line 166 of file motor_hardware.h.

◆ motor_serial_

MotorSerial* MotorHardware::motor_serial_
private

Definition at line 168 of file motor_hardware.h.

◆ prev_fw_params

FirmwareParams MotorHardware::prev_fw_params
private

Definition at line 143 of file motor_hardware.h.

◆ rightError

ros::Publisher MotorHardware::rightError
private

Definition at line 163 of file motor_hardware.h.

◆ sendPid_count

int32_t MotorHardware::sendPid_count
private

Definition at line 149 of file motor_hardware.h.

◆ ticks_per_radian

double MotorHardware::ticks_per_radian
private

Definition at line 147 of file motor_hardware.h.

◆ velocity_joint_interface_

hardware_interface::VelocityJointInterface MotorHardware::velocity_joint_interface_
private

Definition at line 140 of file motor_hardware.h.


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


ubiquity_motor
Author(s):
autogenerated on Mon Feb 28 2022 23:57:06