Classes | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
roch_base::rochHardware Class Reference

#include <roch_hardware.h>

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

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::stringgetInterfaceResources (std::string iface_type) const
 
std::vector< std::stringgetNames () 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 &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::DataPowerSystempower_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::DataSafetySystemStatussafety_status_task_
 
ros::Publisher sensor_state_publisher_
 
struct roch_base::rochHardware::SixAxisGyro sixGyro
 
rochSoftwareDiagnosticTask software_status_task_
 
rochHardwareDiagnosticTask< sawyer::DataSystemStatussystem_status_task_
 
ros::Publisher ult_event_publisher_
 
double ult_length_
 
std::vector< double > ultbottom
 
hardware_interface::VelocityJointInterface velocity_joint_interface_
 
double wheel_diameter_
 

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< ResourceManagerBaseinterface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

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.

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.

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.

void roch_base::rochHardware::publishRawData ( )

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 ( )
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.

Member Data Documentation

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.

PSDEvent roch_base::rochHardware::centerpsdevent
private

Definition at line 247 of file roch_hardware.h.

UltEvent roch_base::rochHardware::centerultevent
private

Definition at line 245 of file roch_hardware.h.

ros::Publisher roch_base::rochHardware::cliff_event_publisher_
private

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.

ros::Publisher roch_base::rochHardware::diagnostic_publisher_
private

Definition at line 133 of file roch_hardware.h.

diagnostic_updater::Updater roch_base::rochHardware::diagnostic_updater_
private

Definition at line 138 of file roch_hardware.h.

std::string roch_base::rochHardware::gyro_link_frame_
private

Definition at line 155 of file roch_hardware.h.

struct roch_base::rochHardware::ThreeAxisGyro roch_base::rochHardware::gyroData
private
hardware_interface::ImuSensorInterface roch_base::rochHardware::imu_sensor_interface_
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.

hardware_interface::JointStateInterface roch_base::rochHardware::joint_state_interface_
private

Definition at line 128 of file roch_hardware.h.

struct roch_base::rochHardware::Joint roch_base::rochHardware::joints_[2]
private
CliffEvent roch_base::rochHardware::leftcliffevent
private

Definition at line 243 of file roch_hardware.h.

PSDEvent roch_base::rochHardware::leftpsdevent
private

Definition at line 247 of file roch_hardware.h.

UltEvent roch_base::rochHardware::leftultevent
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.

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.

double roch_base::rochHardware::orientation_covariance[9]

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.

ros::NodeHandle roch_base::rochHardware::private_nh_
private

Definition at line 125 of file roch_hardware.h.

ros::Publisher roch_base::rochHardware::psd_event_publisher_
private

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.

ros::Publisher roch_base::rochHardware::raw_data_command_publisher_
private

Definition at line 134 of file roch_hardware.h.

CliffEvent roch_base::rochHardware::rightcliffevent
private

Definition at line 243 of file roch_hardware.h.

PSDEvent roch_base::rochHardware::rightpsdevent
private

Definition at line 247 of file roch_hardware.h.

UltEvent roch_base::rochHardware::rightultevent
private

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.

ros::Publisher roch_base::rochHardware::sensor_state_publisher_
private

Definition at line 136 of file roch_hardware.h.

struct roch_base::rochHardware::SixAxisGyro roch_base::rochHardware::sixGyro
private
rochSoftwareDiagnosticTask roch_base::rochHardware::software_status_task_
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.

ros::Publisher roch_base::rochHardware::ult_event_publisher_
private

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.


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


roch_base
Author(s): Mike Purvis , Paul Bovbel , Chen
autogenerated on Mon Jun 10 2019 14:41:14