#include <roch_hardware.h>
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.
double roch_base::rochHardware::angularToLinear | ( | const double & | angle | ) | const [private] |
RobotHW provides velocity command in rad/s, roch needs m/s,
Definition at line 672 of file roch_hardware.cpp.
Definition at line 188 of file roch_hardware.cpp.
Definition at line 154 of file roch_hardware.cpp.
Definition at line 176 of file roch_hardware.cpp.
Definition at line 128 of file roch_hardware.cpp.
void roch_base::rochHardware::initializeDiagnostics | ( | ) | [private] |
Register diagnostic tasks with updater class
Definition at line 206 of file roch_hardware.cpp.
void roch_base::rochHardware::limitDifferentialSpeed | ( | double & | diff_speed_left, |
double & | diff_speed_right | ||
) | [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.
double roch_base::rochHardware::linearToAngular | ( | const double & | travel | ) | const [private] |
roch reports travel in metres, need radians for ros_control RobotHW
Definition at line 664 of file roch_hardware.cpp.
void roch_base::rochHardware::publishCliffEvent | ( | const double & | left, |
const double & | right | ||
) | [private] |
Definition at line 461 of file roch_hardware.cpp.
void roch_base::rochHardware::publishPSDEvent | ( | const double & | left, |
const double & | center, | ||
const double & | right | ||
) | [private] |
Definition at line 587 of file roch_hardware.cpp.
Definition at line 442 of file roch_hardware.cpp.
void roch_base::rochHardware::publishSensorState | ( | ) | [private] |
Definition at line 553 of file roch_hardware.cpp.
void roch_base::rochHardware::publishUltEvent | ( | const double & | left, |
const double & | center, | ||
const double & | right | ||
) | [private] |
Definition at line 498 of file roch_hardware.cpp.
void roch_base::rochHardware::publishWheelEvent | ( | const float & | leftOffset, |
const float & | rightOffset | ||
) | [private] |
void roch_base::rochHardware::registerControlInterfaces | ( | ) | [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.
void roch_base::rochHardware::resetTravelOffset | ( | ) | [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 | ( | ) |
External hook to trigger diagnostic update
Definition at line 313 of file roch_hardware.cpp.
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.
Get latest velocity commands from ros_control via joint structure, and send to MCU
Definition at line 414 of file roch_hardware.cpp.
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.
Definition at line 99 of file roch_hardware.h.
Definition at line 97 of file roch_hardware.h.
Definition at line 247 of file roch_hardware.h.
Definition at line 245 of file roch_hardware.h.
Definition at line 135 of file roch_hardware.h.
double roch_base::rochHardware::cliff_height_ [private] |
Definition at line 149 of file roch_hardware.h.
std::vector<double> roch_base::rochHardware::cliffbottom [private] |
Definition at line 156 of file roch_hardware.h.
Definition at line 133 of file roch_hardware.h.
Definition at line 138 of file roch_hardware.h.
Definition at line 155 of file roch_hardware.h.
struct roch_base::rochHardware::ThreeAxisGyro roch_base::rochHardware::gyroData [private] |
Definition at line 130 of file roch_hardware.h.
Definition at line 94 of file roch_hardware.h.
Definition at line 128 of file roch_hardware.h.
struct roch_base::rochHardware::Joint roch_base::rochHardware::joints_[2] [private] |
Definition at line 243 of file roch_hardware.h.
Definition at line 247 of file roch_hardware.h.
Definition at line 245 of file roch_hardware.h.
Definition at line 100 of file roch_hardware.h.
Definition at line 98 of file roch_hardware.h.
double roch_base::rochHardware::max_accel_ [private] |
Definition at line 145 of file roch_hardware.h.
double roch_base::rochHardware::max_speed_ [private] |
Definition at line 145 of file roch_hardware.h.
ros::NodeHandle roch_base::rochHardware::nh_ [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.
Definition at line 96 of file roch_hardware.h.
double roch_base::rochHardware::polling_timeout_ [private] |
Definition at line 147 of file roch_hardware.h.
rochHardwareDiagnosticTask<sawyer::DataPowerSystem> roch_base::rochHardware::power_status_task_ [private] |
Definition at line 140 of file roch_hardware.h.
Definition at line 125 of file roch_hardware.h.
Definition at line 135 of file roch_hardware.h.
double roch_base::rochHardware::PSD_length_ [private] |
Definition at line 154 of file roch_hardware.h.
std::vector<double> roch_base::rochHardware::psdbottom [private] |
Definition at line 158 of file roch_hardware.h.
Definition at line 134 of file roch_hardware.h.
Definition at line 243 of file roch_hardware.h.
Definition at line 247 of file roch_hardware.h.
Definition at line 245 of file roch_hardware.h.
roch_msgs::RochStatus roch_base::rochHardware::roch_status_msg_ [private] |
Definition at line 137 of file roch_hardware.h.
rochHardwareDiagnosticTask<sawyer::DataSafetySystemStatus> roch_base::rochHardware::safety_status_task_ [private] |
Definition at line 141 of file roch_hardware.h.
Definition at line 136 of file roch_hardware.h.
struct roch_base::rochHardware::SixAxisGyro roch_base::rochHardware::sixGyro [private] |
Definition at line 142 of file roch_hardware.h.
rochHardwareDiagnosticTask<sawyer::DataSystemStatus> roch_base::rochHardware::system_status_task_ [private] |
Definition at line 139 of file roch_hardware.h.
Definition at line 135 of file roch_hardware.h.
double roch_base::rochHardware::ult_length_ [private] |
Definition at line 152 of file roch_hardware.h.
std::vector<double> roch_base::rochHardware::ultbottom [private] |
Definition at line 157 of file roch_hardware.h.
hardware_interface::VelocityJointInterface roch_base::rochHardware::velocity_joint_interface_ [private] |
Definition at line 129 of file roch_hardware.h.
double roch_base::rochHardware::wheel_diameter_ [private] |
Definition at line 145 of file roch_hardware.h.