$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-pr2_mechanism/doc_stacks/2013-03-01_16-59-32.624252/pr2_mechanism/pr2_mechanism_msgs/msg/MechanismStatistics.msg */ 00002 #ifndef PR2_MECHANISM_MSGS_MESSAGE_MECHANISMSTATISTICS_H 00003 #define PR2_MECHANISM_MSGS_MESSAGE_MECHANISMSTATISTICS_H 00004 #include <string> 00005 #include <vector> 00006 #include <map> 00007 #include <ostream> 00008 #include "ros/serialization.h" 00009 #include "ros/builtin_message_traits.h" 00010 #include "ros/message_operations.h" 00011 #include "ros/time.h" 00012 00013 #include "ros/macros.h" 00014 00015 #include "ros/assert.h" 00016 00017 #include "std_msgs/Header.h" 00018 #include "pr2_mechanism_msgs/ActuatorStatistics.h" 00019 #include "pr2_mechanism_msgs/JointStatistics.h" 00020 #include "pr2_mechanism_msgs/ControllerStatistics.h" 00021 00022 namespace pr2_mechanism_msgs 00023 { 00024 template <class ContainerAllocator> 00025 struct MechanismStatistics_ { 00026 typedef MechanismStatistics_<ContainerAllocator> Type; 00027 00028 MechanismStatistics_() 00029 : header() 00030 , actuator_statistics() 00031 , joint_statistics() 00032 , controller_statistics() 00033 { 00034 } 00035 00036 MechanismStatistics_(const ContainerAllocator& _alloc) 00037 : header(_alloc) 00038 , actuator_statistics(_alloc) 00039 , joint_statistics(_alloc) 00040 , controller_statistics(_alloc) 00041 { 00042 } 00043 00044 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00045 ::std_msgs::Header_<ContainerAllocator> header; 00046 00047 typedef std::vector< ::pr2_mechanism_msgs::ActuatorStatistics_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_mechanism_msgs::ActuatorStatistics_<ContainerAllocator> >::other > _actuator_statistics_type; 00048 std::vector< ::pr2_mechanism_msgs::ActuatorStatistics_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_mechanism_msgs::ActuatorStatistics_<ContainerAllocator> >::other > actuator_statistics; 00049 00050 typedef std::vector< ::pr2_mechanism_msgs::JointStatistics_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_mechanism_msgs::JointStatistics_<ContainerAllocator> >::other > _joint_statistics_type; 00051 std::vector< ::pr2_mechanism_msgs::JointStatistics_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_mechanism_msgs::JointStatistics_<ContainerAllocator> >::other > joint_statistics; 00052 00053 typedef std::vector< ::pr2_mechanism_msgs::ControllerStatistics_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_mechanism_msgs::ControllerStatistics_<ContainerAllocator> >::other > _controller_statistics_type; 00054 std::vector< ::pr2_mechanism_msgs::ControllerStatistics_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_mechanism_msgs::ControllerStatistics_<ContainerAllocator> >::other > controller_statistics; 00055 00056 00057 ROS_DEPRECATED uint32_t get_actuator_statistics_size() const { return (uint32_t)actuator_statistics.size(); } 00058 ROS_DEPRECATED void set_actuator_statistics_size(uint32_t size) { actuator_statistics.resize((size_t)size); } 00059 ROS_DEPRECATED void get_actuator_statistics_vec(std::vector< ::pr2_mechanism_msgs::ActuatorStatistics_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_mechanism_msgs::ActuatorStatistics_<ContainerAllocator> >::other > & vec) const { vec = this->actuator_statistics; } 00060 ROS_DEPRECATED void set_actuator_statistics_vec(const std::vector< ::pr2_mechanism_msgs::ActuatorStatistics_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_mechanism_msgs::ActuatorStatistics_<ContainerAllocator> >::other > & vec) { this->actuator_statistics = vec; } 00061 ROS_DEPRECATED uint32_t get_joint_statistics_size() const { return (uint32_t)joint_statistics.size(); } 00062 ROS_DEPRECATED void set_joint_statistics_size(uint32_t size) { joint_statistics.resize((size_t)size); } 00063 ROS_DEPRECATED void get_joint_statistics_vec(std::vector< ::pr2_mechanism_msgs::JointStatistics_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_mechanism_msgs::JointStatistics_<ContainerAllocator> >::other > & vec) const { vec = this->joint_statistics; } 00064 ROS_DEPRECATED void set_joint_statistics_vec(const std::vector< ::pr2_mechanism_msgs::JointStatistics_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_mechanism_msgs::JointStatistics_<ContainerAllocator> >::other > & vec) { this->joint_statistics = vec; } 00065 ROS_DEPRECATED uint32_t get_controller_statistics_size() const { return (uint32_t)controller_statistics.size(); } 00066 ROS_DEPRECATED void set_controller_statistics_size(uint32_t size) { controller_statistics.resize((size_t)size); } 00067 ROS_DEPRECATED void get_controller_statistics_vec(std::vector< ::pr2_mechanism_msgs::ControllerStatistics_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_mechanism_msgs::ControllerStatistics_<ContainerAllocator> >::other > & vec) const { vec = this->controller_statistics; } 00068 ROS_DEPRECATED void set_controller_statistics_vec(const std::vector< ::pr2_mechanism_msgs::ControllerStatistics_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_mechanism_msgs::ControllerStatistics_<ContainerAllocator> >::other > & vec) { this->controller_statistics = vec; } 00069 private: 00070 static const char* __s_getDataType_() { return "pr2_mechanism_msgs/MechanismStatistics"; } 00071 public: 00072 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00073 00074 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00075 00076 private: 00077 static const char* __s_getMD5Sum_() { return "b4a99069393681672c01f8c823458e04"; } 00078 public: 00079 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00080 00081 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00082 00083 private: 00084 static const char* __s_getMessageDefinition_() { return "# This message describes the state of the pr2 mechanism. It contains the state of\n\ 00085 # each actuator, each joint, and each controller that is spawned in pr2_mechanism_control.\n\ 00086 \n\ 00087 Header header\n\ 00088 ActuatorStatistics[] actuator_statistics\n\ 00089 JointStatistics[] joint_statistics\n\ 00090 ControllerStatistics[] controller_statistics\n\ 00091 \n\ 00092 ================================================================================\n\ 00093 MSG: std_msgs/Header\n\ 00094 # Standard metadata for higher-level stamped data types.\n\ 00095 # This is generally used to communicate timestamped data \n\ 00096 # in a particular coordinate frame.\n\ 00097 # \n\ 00098 # sequence ID: consecutively increasing ID \n\ 00099 uint32 seq\n\ 00100 #Two-integer timestamp that is expressed as:\n\ 00101 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00102 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00103 # time-handling sugar is provided by the client library\n\ 00104 time stamp\n\ 00105 #Frame this data is associated with\n\ 00106 # 0: no frame\n\ 00107 # 1: global frame\n\ 00108 string frame_id\n\ 00109 \n\ 00110 ================================================================================\n\ 00111 MSG: pr2_mechanism_msgs/ActuatorStatistics\n\ 00112 # This message contains the state of an actuator on the pr2 robot.\n\ 00113 # An actuator contains a motor and an encoder, and is connected\n\ 00114 # to a joint by a transmission\n\ 00115 \n\ 00116 # the name of the actuator\n\ 00117 string name\n\ 00118 \n\ 00119 # the sequence number of the MCB in the ethercat chain. \n\ 00120 # the first device in the chain gets deviced_id zero\n\ 00121 int32 device_id\n\ 00122 \n\ 00123 # the time at which this actuator state was measured\n\ 00124 time timestamp\n\ 00125 \n\ 00126 # the encoder position, represented by the number of encoder ticks\n\ 00127 int32 encoder_count\n\ 00128 \n\ 00129 # The angular offset (in radians) that is added to the encoder reading, \n\ 00130 # to get to the position of the actuator. This number is computed when the referece\n\ 00131 # sensor is triggered during the calibration phase\n\ 00132 float64 encoder_offset\n\ 00133 \n\ 00134 # the encoder position in radians\n\ 00135 float64 position\n\ 00136 \n\ 00137 # the encoder velocity in encoder ticks per second\n\ 00138 float64 encoder_velocity\n\ 00139 \n\ 00140 # the encoder velocity in radians per second\n\ 00141 float64 velocity\n\ 00142 \n\ 00143 # the value of the calibration reading: low (false) or high (true)\n\ 00144 bool calibration_reading\n\ 00145 \n\ 00146 # bool to indicate if the joint already triggered the rising/falling edge of the reference sensor\n\ 00147 bool calibration_rising_edge_valid\n\ 00148 bool calibration_falling_edge_valid\n\ 00149 \n\ 00150 # the encoder position when the last rising/falling edge was observed. \n\ 00151 # only read this value when the calibration_rising/falling_edge_valid is true\n\ 00152 float64 last_calibration_rising_edge\n\ 00153 float64 last_calibration_falling_edge\n\ 00154 \n\ 00155 # flag to indicate if this actuator is enabled or not. \n\ 00156 # An actuator can only be commanded when it is enabled.\n\ 00157 bool is_enabled\n\ 00158 \n\ 00159 # indicates if the motor is halted. A motor can be halted because of a voltage or communication problem\n\ 00160 bool halted\n\ 00161 \n\ 00162 # the last current/effort command that was requested\n\ 00163 float64 last_commanded_current\n\ 00164 float64 last_commanded_effort\n\ 00165 \n\ 00166 # the last current/effort command that was executed by the actuator\n\ 00167 float64 last_executed_current\n\ 00168 float64 last_executed_effort\n\ 00169 \n\ 00170 # the last current/effort that was measured by the actuator\n\ 00171 float64 last_measured_current\n\ 00172 float64 last_measured_effort\n\ 00173 \n\ 00174 # the motor voltate\n\ 00175 float64 motor_voltage\n\ 00176 \n\ 00177 # the number of detected encoder problems \n\ 00178 int32 num_encoder_errors\n\ 00179 \n\ 00180 \n\ 00181 ================================================================================\n\ 00182 MSG: pr2_mechanism_msgs/JointStatistics\n\ 00183 # This message contains the state of one joint of the pr2 robot.\n\ 00184 # This message is specificly designed for the pr2 robot. \n\ 00185 # A generic joint state message can be found in sensor_msgs::JointState\n\ 00186 \n\ 00187 # the name of the joint\n\ 00188 string name\n\ 00189 \n\ 00190 # the time at which these joint statistics were measured\n\ 00191 time timestamp\n\ 00192 \n\ 00193 # the position of the joint in radians\n\ 00194 float64 position\n\ 00195 \n\ 00196 # the velocity of the joint in radians per second\n\ 00197 float64 velocity\n\ 00198 \n\ 00199 # the measured joint effort \n\ 00200 float64 measured_effort\n\ 00201 \n\ 00202 # the effort that was commanded to the joint.\n\ 00203 # the actual applied effort might be different\n\ 00204 # because the safety code can limit the effort\n\ 00205 # a joint can apply\n\ 00206 float64 commanded_effort\n\ 00207 \n\ 00208 # a flag indicating if the joint is calibrated or not\n\ 00209 bool is_calibrated\n\ 00210 \n\ 00211 # a flag inidcating if the joint violated one of its position/velocity/effort limits\n\ 00212 # in the last publish cycle\n\ 00213 bool violated_limits\n\ 00214 \n\ 00215 # the total distance travelled by the joint, measured in radians.\n\ 00216 float64 odometer\n\ 00217 \n\ 00218 # the lowest position reached by the joint in the last publish cycle\n\ 00219 float64 min_position\n\ 00220 \n\ 00221 # the highest position reached by the joint in the last publish cycle\n\ 00222 float64 max_position\n\ 00223 \n\ 00224 # the maximum absolute velocity reached by the joint in the last publish cycle\n\ 00225 float64 max_abs_velocity\n\ 00226 \n\ 00227 # the maximum absolute effort applied by the joint in the last publish cycle\n\ 00228 float64 max_abs_effort\n\ 00229 \n\ 00230 ================================================================================\n\ 00231 MSG: pr2_mechanism_msgs/ControllerStatistics\n\ 00232 # This message contains the state of one realtime controller\n\ 00233 # that was spawned in pr2_mechanism_control\n\ 00234 \n\ 00235 # the name of the controller\n\ 00236 string name\n\ 00237 \n\ 00238 # the time at which these controller statistics were measured\n\ 00239 time timestamp\n\ 00240 \n\ 00241 # bool that indicates if the controller is currently\n\ 00242 # in a running or a stopped state\n\ 00243 bool running\n\ 00244 \n\ 00245 # the maximum time the update loop of the controller ever needed to complete\n\ 00246 duration max_time\n\ 00247 \n\ 00248 # the average time the update loop of the controller needs to complete. \n\ 00249 # the average is computed in a sliding time window.\n\ 00250 duration mean_time\n\ 00251 \n\ 00252 # the variance on the time the update loop of the controller needs to complete.\n\ 00253 # the variance applies to a sliding time window.\n\ 00254 duration variance_time\n\ 00255 \n\ 00256 # the number of times this controller broke the realtime loop\n\ 00257 int32 num_control_loop_overruns\n\ 00258 \n\ 00259 # the timestamp of the last time this controller broke the realtime loop\n\ 00260 time time_last_control_loop_overrun\n\ 00261 "; } 00262 public: 00263 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00264 00265 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00266 00267 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00268 { 00269 ros::serialization::OStream stream(write_ptr, 1000000000); 00270 ros::serialization::serialize(stream, header); 00271 ros::serialization::serialize(stream, actuator_statistics); 00272 ros::serialization::serialize(stream, joint_statistics); 00273 ros::serialization::serialize(stream, controller_statistics); 00274 return stream.getData(); 00275 } 00276 00277 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00278 { 00279 ros::serialization::IStream stream(read_ptr, 1000000000); 00280 ros::serialization::deserialize(stream, header); 00281 ros::serialization::deserialize(stream, actuator_statistics); 00282 ros::serialization::deserialize(stream, joint_statistics); 00283 ros::serialization::deserialize(stream, controller_statistics); 00284 return stream.getData(); 00285 } 00286 00287 ROS_DEPRECATED virtual uint32_t serializationLength() const 00288 { 00289 uint32_t size = 0; 00290 size += ros::serialization::serializationLength(header); 00291 size += ros::serialization::serializationLength(actuator_statistics); 00292 size += ros::serialization::serializationLength(joint_statistics); 00293 size += ros::serialization::serializationLength(controller_statistics); 00294 return size; 00295 } 00296 00297 typedef boost::shared_ptr< ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> > Ptr; 00298 typedef boost::shared_ptr< ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> const> ConstPtr; 00299 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00300 }; // struct MechanismStatistics 00301 typedef ::pr2_mechanism_msgs::MechanismStatistics_<std::allocator<void> > MechanismStatistics; 00302 00303 typedef boost::shared_ptr< ::pr2_mechanism_msgs::MechanismStatistics> MechanismStatisticsPtr; 00304 typedef boost::shared_ptr< ::pr2_mechanism_msgs::MechanismStatistics const> MechanismStatisticsConstPtr; 00305 00306 00307 template<typename ContainerAllocator> 00308 std::ostream& operator<<(std::ostream& s, const ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> & v) 00309 { 00310 ros::message_operations::Printer< ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> >::stream(s, "", v); 00311 return s;} 00312 00313 } // namespace pr2_mechanism_msgs 00314 00315 namespace ros 00316 { 00317 namespace message_traits 00318 { 00319 template<class ContainerAllocator> struct IsMessage< ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> > : public TrueType {}; 00320 template<class ContainerAllocator> struct IsMessage< ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> const> : public TrueType {}; 00321 template<class ContainerAllocator> 00322 struct MD5Sum< ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> > { 00323 static const char* value() 00324 { 00325 return "b4a99069393681672c01f8c823458e04"; 00326 } 00327 00328 static const char* value(const ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> &) { return value(); } 00329 static const uint64_t static_value1 = 0xb4a9906939368167ULL; 00330 static const uint64_t static_value2 = 0x2c01f8c823458e04ULL; 00331 }; 00332 00333 template<class ContainerAllocator> 00334 struct DataType< ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> > { 00335 static const char* value() 00336 { 00337 return "pr2_mechanism_msgs/MechanismStatistics"; 00338 } 00339 00340 static const char* value(const ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> &) { return value(); } 00341 }; 00342 00343 template<class ContainerAllocator> 00344 struct Definition< ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> > { 00345 static const char* value() 00346 { 00347 return "# This message describes the state of the pr2 mechanism. It contains the state of\n\ 00348 # each actuator, each joint, and each controller that is spawned in pr2_mechanism_control.\n\ 00349 \n\ 00350 Header header\n\ 00351 ActuatorStatistics[] actuator_statistics\n\ 00352 JointStatistics[] joint_statistics\n\ 00353 ControllerStatistics[] controller_statistics\n\ 00354 \n\ 00355 ================================================================================\n\ 00356 MSG: std_msgs/Header\n\ 00357 # Standard metadata for higher-level stamped data types.\n\ 00358 # This is generally used to communicate timestamped data \n\ 00359 # in a particular coordinate frame.\n\ 00360 # \n\ 00361 # sequence ID: consecutively increasing ID \n\ 00362 uint32 seq\n\ 00363 #Two-integer timestamp that is expressed as:\n\ 00364 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00365 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00366 # time-handling sugar is provided by the client library\n\ 00367 time stamp\n\ 00368 #Frame this data is associated with\n\ 00369 # 0: no frame\n\ 00370 # 1: global frame\n\ 00371 string frame_id\n\ 00372 \n\ 00373 ================================================================================\n\ 00374 MSG: pr2_mechanism_msgs/ActuatorStatistics\n\ 00375 # This message contains the state of an actuator on the pr2 robot.\n\ 00376 # An actuator contains a motor and an encoder, and is connected\n\ 00377 # to a joint by a transmission\n\ 00378 \n\ 00379 # the name of the actuator\n\ 00380 string name\n\ 00381 \n\ 00382 # the sequence number of the MCB in the ethercat chain. \n\ 00383 # the first device in the chain gets deviced_id zero\n\ 00384 int32 device_id\n\ 00385 \n\ 00386 # the time at which this actuator state was measured\n\ 00387 time timestamp\n\ 00388 \n\ 00389 # the encoder position, represented by the number of encoder ticks\n\ 00390 int32 encoder_count\n\ 00391 \n\ 00392 # The angular offset (in radians) that is added to the encoder reading, \n\ 00393 # to get to the position of the actuator. This number is computed when the referece\n\ 00394 # sensor is triggered during the calibration phase\n\ 00395 float64 encoder_offset\n\ 00396 \n\ 00397 # the encoder position in radians\n\ 00398 float64 position\n\ 00399 \n\ 00400 # the encoder velocity in encoder ticks per second\n\ 00401 float64 encoder_velocity\n\ 00402 \n\ 00403 # the encoder velocity in radians per second\n\ 00404 float64 velocity\n\ 00405 \n\ 00406 # the value of the calibration reading: low (false) or high (true)\n\ 00407 bool calibration_reading\n\ 00408 \n\ 00409 # bool to indicate if the joint already triggered the rising/falling edge of the reference sensor\n\ 00410 bool calibration_rising_edge_valid\n\ 00411 bool calibration_falling_edge_valid\n\ 00412 \n\ 00413 # the encoder position when the last rising/falling edge was observed. \n\ 00414 # only read this value when the calibration_rising/falling_edge_valid is true\n\ 00415 float64 last_calibration_rising_edge\n\ 00416 float64 last_calibration_falling_edge\n\ 00417 \n\ 00418 # flag to indicate if this actuator is enabled or not. \n\ 00419 # An actuator can only be commanded when it is enabled.\n\ 00420 bool is_enabled\n\ 00421 \n\ 00422 # indicates if the motor is halted. A motor can be halted because of a voltage or communication problem\n\ 00423 bool halted\n\ 00424 \n\ 00425 # the last current/effort command that was requested\n\ 00426 float64 last_commanded_current\n\ 00427 float64 last_commanded_effort\n\ 00428 \n\ 00429 # the last current/effort command that was executed by the actuator\n\ 00430 float64 last_executed_current\n\ 00431 float64 last_executed_effort\n\ 00432 \n\ 00433 # the last current/effort that was measured by the actuator\n\ 00434 float64 last_measured_current\n\ 00435 float64 last_measured_effort\n\ 00436 \n\ 00437 # the motor voltate\n\ 00438 float64 motor_voltage\n\ 00439 \n\ 00440 # the number of detected encoder problems \n\ 00441 int32 num_encoder_errors\n\ 00442 \n\ 00443 \n\ 00444 ================================================================================\n\ 00445 MSG: pr2_mechanism_msgs/JointStatistics\n\ 00446 # This message contains the state of one joint of the pr2 robot.\n\ 00447 # This message is specificly designed for the pr2 robot. \n\ 00448 # A generic joint state message can be found in sensor_msgs::JointState\n\ 00449 \n\ 00450 # the name of the joint\n\ 00451 string name\n\ 00452 \n\ 00453 # the time at which these joint statistics were measured\n\ 00454 time timestamp\n\ 00455 \n\ 00456 # the position of the joint in radians\n\ 00457 float64 position\n\ 00458 \n\ 00459 # the velocity of the joint in radians per second\n\ 00460 float64 velocity\n\ 00461 \n\ 00462 # the measured joint effort \n\ 00463 float64 measured_effort\n\ 00464 \n\ 00465 # the effort that was commanded to the joint.\n\ 00466 # the actual applied effort might be different\n\ 00467 # because the safety code can limit the effort\n\ 00468 # a joint can apply\n\ 00469 float64 commanded_effort\n\ 00470 \n\ 00471 # a flag indicating if the joint is calibrated or not\n\ 00472 bool is_calibrated\n\ 00473 \n\ 00474 # a flag inidcating if the joint violated one of its position/velocity/effort limits\n\ 00475 # in the last publish cycle\n\ 00476 bool violated_limits\n\ 00477 \n\ 00478 # the total distance travelled by the joint, measured in radians.\n\ 00479 float64 odometer\n\ 00480 \n\ 00481 # the lowest position reached by the joint in the last publish cycle\n\ 00482 float64 min_position\n\ 00483 \n\ 00484 # the highest position reached by the joint in the last publish cycle\n\ 00485 float64 max_position\n\ 00486 \n\ 00487 # the maximum absolute velocity reached by the joint in the last publish cycle\n\ 00488 float64 max_abs_velocity\n\ 00489 \n\ 00490 # the maximum absolute effort applied by the joint in the last publish cycle\n\ 00491 float64 max_abs_effort\n\ 00492 \n\ 00493 ================================================================================\n\ 00494 MSG: pr2_mechanism_msgs/ControllerStatistics\n\ 00495 # This message contains the state of one realtime controller\n\ 00496 # that was spawned in pr2_mechanism_control\n\ 00497 \n\ 00498 # the name of the controller\n\ 00499 string name\n\ 00500 \n\ 00501 # the time at which these controller statistics were measured\n\ 00502 time timestamp\n\ 00503 \n\ 00504 # bool that indicates if the controller is currently\n\ 00505 # in a running or a stopped state\n\ 00506 bool running\n\ 00507 \n\ 00508 # the maximum time the update loop of the controller ever needed to complete\n\ 00509 duration max_time\n\ 00510 \n\ 00511 # the average time the update loop of the controller needs to complete. \n\ 00512 # the average is computed in a sliding time window.\n\ 00513 duration mean_time\n\ 00514 \n\ 00515 # the variance on the time the update loop of the controller needs to complete.\n\ 00516 # the variance applies to a sliding time window.\n\ 00517 duration variance_time\n\ 00518 \n\ 00519 # the number of times this controller broke the realtime loop\n\ 00520 int32 num_control_loop_overruns\n\ 00521 \n\ 00522 # the timestamp of the last time this controller broke the realtime loop\n\ 00523 time time_last_control_loop_overrun\n\ 00524 "; 00525 } 00526 00527 static const char* value(const ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> &) { return value(); } 00528 }; 00529 00530 template<class ContainerAllocator> struct HasHeader< ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> > : public TrueType {}; 00531 template<class ContainerAllocator> struct HasHeader< const ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> > : public TrueType {}; 00532 } // namespace message_traits 00533 } // namespace ros 00534 00535 namespace ros 00536 { 00537 namespace serialization 00538 { 00539 00540 template<class ContainerAllocator> struct Serializer< ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> > 00541 { 00542 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00543 { 00544 stream.next(m.header); 00545 stream.next(m.actuator_statistics); 00546 stream.next(m.joint_statistics); 00547 stream.next(m.controller_statistics); 00548 } 00549 00550 ROS_DECLARE_ALLINONE_SERIALIZER; 00551 }; // struct MechanismStatistics_ 00552 } // namespace serialization 00553 } // namespace ros 00554 00555 namespace ros 00556 { 00557 namespace message_operations 00558 { 00559 00560 template<class ContainerAllocator> 00561 struct Printer< ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> > 00562 { 00563 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_mechanism_msgs::MechanismStatistics_<ContainerAllocator> & v) 00564 { 00565 s << indent << "header: "; 00566 s << std::endl; 00567 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00568 s << indent << "actuator_statistics[]" << std::endl; 00569 for (size_t i = 0; i < v.actuator_statistics.size(); ++i) 00570 { 00571 s << indent << " actuator_statistics[" << i << "]: "; 00572 s << std::endl; 00573 s << indent; 00574 Printer< ::pr2_mechanism_msgs::ActuatorStatistics_<ContainerAllocator> >::stream(s, indent + " ", v.actuator_statistics[i]); 00575 } 00576 s << indent << "joint_statistics[]" << std::endl; 00577 for (size_t i = 0; i < v.joint_statistics.size(); ++i) 00578 { 00579 s << indent << " joint_statistics[" << i << "]: "; 00580 s << std::endl; 00581 s << indent; 00582 Printer< ::pr2_mechanism_msgs::JointStatistics_<ContainerAllocator> >::stream(s, indent + " ", v.joint_statistics[i]); 00583 } 00584 s << indent << "controller_statistics[]" << std::endl; 00585 for (size_t i = 0; i < v.controller_statistics.size(); ++i) 00586 { 00587 s << indent << " controller_statistics[" << i << "]: "; 00588 s << std::endl; 00589 s << indent; 00590 Printer< ::pr2_mechanism_msgs::ControllerStatistics_<ContainerAllocator> >::stream(s, indent + " ", v.controller_statistics[i]); 00591 } 00592 } 00593 }; 00594 00595 00596 } // namespace message_operations 00597 } // namespace ros 00598 00599 #endif // PR2_MECHANISM_MSGS_MESSAGE_MECHANISMSTATISTICS_H 00600