#include <sr_articulated_robot.h>
Public Attributes | |
| double | current |
| current value More... | |
| std::map< std::string, int > | debug_values |
| the debug values More... | |
| std::string | flags |
| a string containing flags: FORCE, TEMPERATURE, ... indicating the different cutouts / warning sent by the hand. More... | |
| double | force |
| force value More... | |
| std::string | joint_name |
| the name of the joint More... | |
| int16_t | level |
| the level of alert: 0 = OK, 1 = WARNING, 2 = ERROR More... | |
| uint64_t | num_sensor_msgs_received |
| values read from the debug node. More... | |
| double | position |
| the actual value of the position More... | |
| int | position_sensor_num |
| the channel number of the position sensor More... | |
| double | target |
| the actual value of the target More... | |
| int | target_sensor_num |
| the channel number of the target sensor More... | |
| double | temperature |
| temperature value More... | |
The information being published by the Diagnostic publisher
Definition at line 217 of file sr_articulated_robot.h.
| double shadowrobot::DiagnosticData::current |
current value
Definition at line 242 of file sr_articulated_robot.h.
| std::map<std::string, int> shadowrobot::DiagnosticData::debug_values |
the debug values
Definition at line 235 of file sr_articulated_robot.h.
| std::string shadowrobot::DiagnosticData::flags |
a string containing flags: FORCE, TEMPERATURE, ... indicating the different cutouts / warning sent by the hand.
Definition at line 225 of file sr_articulated_robot.h.
| double shadowrobot::DiagnosticData::force |
force value
Definition at line 244 of file sr_articulated_robot.h.
| std::string shadowrobot::DiagnosticData::joint_name |
the name of the joint
Definition at line 220 of file sr_articulated_robot.h.
| int16_t shadowrobot::DiagnosticData::level |
the level of alert: 0 = OK, 1 = WARNING, 2 = ERROR
Definition at line 222 of file sr_articulated_robot.h.
| uint64_t shadowrobot::DiagnosticData::num_sensor_msgs_received |
values read from the debug node.
Definition at line 247 of file sr_articulated_robot.h.
| double shadowrobot::DiagnosticData::position |
the actual value of the position
Definition at line 237 of file sr_articulated_robot.h.
| int shadowrobot::DiagnosticData::position_sensor_num |
the channel number of the position sensor
Definition at line 230 of file sr_articulated_robot.h.
| double shadowrobot::DiagnosticData::target |
the actual value of the target
Definition at line 232 of file sr_articulated_robot.h.
| int shadowrobot::DiagnosticData::target_sensor_num |
the channel number of the target sensor
Definition at line 228 of file sr_articulated_robot.h.
| double shadowrobot::DiagnosticData::temperature |
temperature value
Definition at line 240 of file sr_articulated_robot.h.