#include <roch_hardware.h>
Classes | |
struct | CliffEvent |
struct | Joint |
struct | PSDEvent |
struct | SixAxisGyro |
struct | ThreeAxisGyro |
struct | UltEvent |
Public Member Functions | |
void | getDifferentControlConstantData () |
void | getPlatAccData () |
void | getPlatformName () |
void | getRangefinderData () |
void | publishRawData () |
void | reportLoopDuration (const ros::Duration &duration) |
rochHardware (ros::NodeHandle nh, ros::NodeHandle private_nh, double target_control_freq) | |
void | showRawData () |
void | updateDiagnostics () |
void | updateJointsFromHardware () |
void | writeCommandsToHardware () |
void | writeOverallSpeedCommandsToHardware () |
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 void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
virtual bool | init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) |
virtual bool | prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list) |
virtual bool | prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list) |
virtual void | read (const ros::Time &time, const ros::Duration &period) |
virtual void | read (const ros::Time &time, const ros::Duration &period) |
RobotHW () | |
virtual void | write (const ros::Time &time, const ros::Duration &period) |
virtual void | write (const ros::Time &time, const ros::Duration &period) |
virtual | ~RobotHW () |
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 | |
double | angular_velocity [3] |
double | angular_velocity_covariance [9] |
hardware_interface::ImuSensorHandle::Data | imuMsgData |
double | linear_acceleration [3] |
double | linear_acceleration_covariance [9] |
double | orientation [4] |
double | orientation_covariance [9] |
Private Member Functions | |
double | angularToLinear (const double &angle) const |
void | initializeDiagnostics () |
void | limitDifferentialSpeed (double &travel_speed_left, double &travel_speed_right) |
double | linearToAngular (const double &travel) const |
void | publishCliffEvent (const double &left, const double &right) |
void | publishPSDEvent (const double &left, const double ¢er, const double &right) |
void | publishSensorState () |
void | publishUltEvent (const double &left, const double ¢er, const double &right) |
void | publishWheelEvent (const float &leftOffset, const float &rightOffset) |
void | registerControlInterfaces () |
void | resetTravelOffset () |
Additional Inherited Members | |
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 | |
boost::ptr_vector< ResourceManagerBase > | interface_destruction_list_ |
InterfaceManagerVector | interface_managers_ |
InterfaceMap | interfaces_ |
InterfaceMap | interfaces_combo_ |
SizeMap | num_ifaces_registered_ |
ResourceMap | resources_ |
Class representing roch hardware, allows for ros_control to modify internal state via joint interfaces
Definition at line 63 of file roch_hardware.h.
roch_base::rochHardware::rochHardware | ( | ros::NodeHandle | nh, |
ros::NodeHandle | private_nh, | ||
double | target_control_freq | ||
) |
Initialize roch hardware
Definition at line 47 of file roch_hardware.cpp.
|
private |
RobotHW provides velocity command in rad/s, roch needs m/s,
Definition at line 672 of file roch_hardware.cpp.
void roch_base::rochHardware::getDifferentControlConstantData | ( | ) |
Definition at line 188 of file roch_hardware.cpp.
void roch_base::rochHardware::getPlatAccData | ( | ) |
Definition at line 154 of file roch_hardware.cpp.
void roch_base::rochHardware::getPlatformName | ( | ) |
Definition at line 176 of file roch_hardware.cpp.
void roch_base::rochHardware::getRangefinderData | ( | ) |
Definition at line 128 of file roch_hardware.cpp.
|
private |
Register diagnostic tasks with updater class
Definition at line 206 of file roch_hardware.cpp.
|
private |
Scale left and right speed outputs to maintain ros_control's desired trajectory without saturating the outputs
Definition at line 650 of file roch_hardware.cpp.
|
private |
roch reports travel in metres, need radians for ros_control RobotHW
Definition at line 664 of file roch_hardware.cpp.
|
private |
Definition at line 461 of file roch_hardware.cpp.
|
private |
Definition at line 587 of file roch_hardware.cpp.
void roch_base::rochHardware::publishRawData | ( | ) |
Definition at line 442 of file roch_hardware.cpp.
|
private |
Definition at line 553 of file roch_hardware.cpp.
|
private |
Definition at line 498 of file roch_hardware.cpp.
|
private |
|
private |
Register interfaces with the RobotHW interface manager, allowing ros_control operation
Definition at line 233 of file roch_hardware.cpp.
void roch_base::rochHardware::reportLoopDuration | ( | const ros::Duration & | duration | ) |
Update diagnostics with control loop timing information
Definition at line 642 of file roch_hardware.cpp.
|
private |
Get current encoder travel offsets from MCU and bias future encoder readings against them
Definition at line 78 of file roch_hardware.cpp.
void roch_base::rochHardware::showRawData | ( | ) |
void roch_base::rochHardware::updateDiagnostics | ( | ) |
External hook to trigger diagnostic update
Definition at line 313 of file roch_hardware.cpp.
void roch_base::rochHardware::updateJointsFromHardware | ( | ) |
Pull latest speed and travel measurements from MCU, and store in joint structure for ros_control
Definition at line 324 of file roch_hardware.cpp.
void roch_base::rochHardware::writeCommandsToHardware | ( | ) |
Get latest velocity commands from ros_control via joint structure, and send to MCU
Definition at line 414 of file roch_hardware.cpp.
void roch_base::rochHardware::writeOverallSpeedCommandsToHardware | ( | ) |
Get latest velocity commands from ros_control via joint structure, and send overall speed to MCU
Definition at line 432 of file roch_hardware.cpp.
double roch_base::rochHardware::angular_velocity[3] |
Definition at line 99 of file roch_hardware.h.
double roch_base::rochHardware::angular_velocity_covariance[9] |
Definition at line 97 of file roch_hardware.h.
|
private |
Definition at line 247 of file roch_hardware.h.
|
private |
Definition at line 245 of file roch_hardware.h.
|
private |
Definition at line 135 of file roch_hardware.h.
|
private |
Definition at line 149 of file roch_hardware.h.
|
private |
Definition at line 156 of file roch_hardware.h.
|
private |
Definition at line 133 of file roch_hardware.h.
|
private |
Definition at line 138 of file roch_hardware.h.
|
private |
Definition at line 155 of file roch_hardware.h.
|
private |
|
private |
Definition at line 130 of file roch_hardware.h.
hardware_interface::ImuSensorHandle::Data roch_base::rochHardware::imuMsgData |
Definition at line 94 of file roch_hardware.h.
|
private |
Definition at line 128 of file roch_hardware.h.
|
private |
|
private |
Definition at line 243 of file roch_hardware.h.
|
private |
Definition at line 247 of file roch_hardware.h.
|
private |
Definition at line 245 of file roch_hardware.h.
double roch_base::rochHardware::linear_acceleration[3] |
Definition at line 100 of file roch_hardware.h.
double roch_base::rochHardware::linear_acceleration_covariance[9] |
Definition at line 98 of file roch_hardware.h.
|
private |
Definition at line 145 of file roch_hardware.h.
|
private |
Definition at line 145 of file roch_hardware.h.
|
private |
Definition at line 125 of file roch_hardware.h.
double roch_base::rochHardware::orientation[4] |
Definition at line 95 of file roch_hardware.h.
double roch_base::rochHardware::orientation_covariance[9] |
Definition at line 96 of file roch_hardware.h.
|
private |
Definition at line 147 of file roch_hardware.h.
|
private |
Definition at line 140 of file roch_hardware.h.
|
private |
Definition at line 125 of file roch_hardware.h.
|
private |
Definition at line 135 of file roch_hardware.h.
|
private |
Definition at line 154 of file roch_hardware.h.
|
private |
Definition at line 158 of file roch_hardware.h.
|
private |
Definition at line 134 of file roch_hardware.h.
|
private |
Definition at line 243 of file roch_hardware.h.
|
private |
Definition at line 247 of file roch_hardware.h.
|
private |
Definition at line 245 of file roch_hardware.h.
|
private |
Definition at line 137 of file roch_hardware.h.
|
private |
Definition at line 141 of file roch_hardware.h.
|
private |
Definition at line 136 of file roch_hardware.h.
|
private |
|
private |
Definition at line 142 of file roch_hardware.h.
|
private |
Definition at line 139 of file roch_hardware.h.
|
private |
Definition at line 135 of file roch_hardware.h.
|
private |
Definition at line 152 of file roch_hardware.h.
|
private |
Definition at line 157 of file roch_hardware.h.
|
private |
Definition at line 129 of file roch_hardware.h.
|
private |
Definition at line 145 of file roch_hardware.h.