Classes | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
roch_base::rochHardware Class Reference

#include <roch_hardware.h>

Inheritance diagram for roch_base::rochHardware:
Inheritance graph
[legend]

List of all members.

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 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 &center, const double &right)
void publishSensorState ()
void publishUltEvent (const double &left, const double &center, const double &right)
void publishWheelEvent (const float &leftOffset, const float &rightOffset)
void registerControlInterfaces ()
void resetTravelOffset ()

Private Attributes

PSDEvent centerpsdevent
UltEvent centerultevent
ros::Publisher cliff_event_publisher_
double cliff_height_
std::vector< double > cliffbottom
ros::Publisher diagnostic_publisher_
diagnostic_updater::Updater diagnostic_updater_
std::string gyro_link_frame_
struct
roch_base::rochHardware::ThreeAxisGyro 
gyroData
hardware_interface::ImuSensorInterface imu_sensor_interface_
hardware_interface::JointStateInterface joint_state_interface_
struct
roch_base::rochHardware::Joint 
joints_ [2]
CliffEvent leftcliffevent
PSDEvent leftpsdevent
UltEvent leftultevent
double max_accel_
double max_speed_
ros::NodeHandle nh_
double polling_timeout_
rochHardwareDiagnosticTask
< sawyer::DataPowerSystem
power_status_task_
ros::NodeHandle private_nh_
ros::Publisher psd_event_publisher_
double PSD_length_
std::vector< double > psdbottom
ros::Publisher raw_data_command_publisher_
CliffEvent rightcliffevent
PSDEvent rightpsdevent
UltEvent rightultevent
roch_msgs::RochStatus roch_status_msg_
rochHardwareDiagnosticTask
< sawyer::DataSafetySystemStatus
safety_status_task_
ros::Publisher sensor_state_publisher_
struct
roch_base::rochHardware::SixAxisGyro 
sixGyro
rochSoftwareDiagnosticTask software_status_task_
rochHardwareDiagnosticTask
< sawyer::DataSystemStatus
system_status_task_
ros::Publisher ult_event_publisher_
double ult_length_
std::vector< double > ultbottom
hardware_interface::VelocityJointInterface velocity_joint_interface_
double wheel_diameter_

Detailed Description

Class representing roch hardware, allows for ros_control to modify internal state via joint interfaces

Definition at line 63 of file roch_hardware.h.


Constructor & Destructor Documentation

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.


Member Function Documentation

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.

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.

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]

Register interfaces with the RobotHW interface manager, allowing ros_control operation

Definition at line 233 of file roch_hardware.cpp.

Update diagnostics with control loop timing information

Definition at line 642 of file roch_hardware.cpp.

Get current encoder travel offsets from MCU and bias future encoder readings against them

Definition at line 78 of file roch_hardware.cpp.

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.


Member Data Documentation

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.

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.

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.

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.

Definition at line 145 of file roch_hardware.h.

Definition at line 145 of file roch_hardware.h.

Definition at line 125 of file roch_hardware.h.

Definition at line 95 of file roch_hardware.h.

Definition at line 96 of file roch_hardware.h.

Definition at line 147 of file roch_hardware.h.

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.

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.

Definition at line 141 of file roch_hardware.h.

Definition at line 136 of file roch_hardware.h.

Definition at line 142 of file roch_hardware.h.

Definition at line 139 of file roch_hardware.h.

Definition at line 135 of file roch_hardware.h.

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.

Definition at line 129 of file roch_hardware.h.

Definition at line 145 of file roch_hardware.h.


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


roch_base
Author(s): Mike Purvis , Paul Bovbel , Carl
autogenerated on Sat Jun 8 2019 20:32:33