#include <sr_articulated_robot.h>
Public Attributes | |
double | current |
current value | |
std::map< std::string, int > | debug_values |
the debug values | |
std::string | flags |
a string containing flags: FORCE, TEMPERATURE, ... indicating the different cutouts / warning sent by the hand. | |
double | force |
force value | |
std::string | joint_name |
the name of the joint | |
short | level |
the level of alert: 0 = OK, 1 = WARNING, 2 = ERROR | |
uint64_t | num_sensor_msgs_received |
double | position |
the actual value of the position | |
int | position_sensor_num |
the channel number of the position sensor | |
double | target |
the actual value of the target | |
int | target_sensor_num |
the channel number of the target sensor | |
double | temperature |
temperature value |
The information being published by the Diagnostic publisher
Definition at line 214 of file sr_articulated_robot.h.
current value
Definition at line 239 of file sr_articulated_robot.h.
std::map<std::string, int> shadowrobot::DiagnosticData::debug_values |
the debug values
Definition at line 232 of file sr_articulated_robot.h.
a string containing flags: FORCE, TEMPERATURE, ... indicating the different cutouts / warning sent by the hand.
Definition at line 222 of file sr_articulated_robot.h.
force value
Definition at line 241 of file sr_articulated_robot.h.
the name of the joint
Definition at line 217 of file sr_articulated_robot.h.
the level of alert: 0 = OK, 1 = WARNING, 2 = ERROR
Definition at line 219 of file sr_articulated_robot.h.
Definition at line 244 of file sr_articulated_robot.h.
the actual value of the position
Definition at line 234 of file sr_articulated_robot.h.
the channel number of the position sensor
Definition at line 227 of file sr_articulated_robot.h.
the actual value of the target
Definition at line 229 of file sr_articulated_robot.h.
the channel number of the target sensor
Definition at line 225 of file sr_articulated_robot.h.
temperature value
Definition at line 237 of file sr_articulated_robot.h.