$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-shadow_robot/doc_stacks/2013-03-02_13-32-28.994675/shadow_robot/sr_robot_msgs/msg/EthercatDebug.msg */ 00002 #ifndef SR_ROBOT_MSGS_MESSAGE_ETHERCATDEBUG_H 00003 #define SR_ROBOT_MSGS_MESSAGE_ETHERCATDEBUG_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 "sr_robot_msgs/FromMotorDataType.h" 00019 00020 namespace sr_robot_msgs 00021 { 00022 template <class ContainerAllocator> 00023 struct EthercatDebug_ { 00024 typedef EthercatDebug_<ContainerAllocator> Type; 00025 00026 EthercatDebug_() 00027 : header() 00028 , sensors() 00029 , motor_data_type() 00030 , which_motors(0) 00031 , which_motor_data_arrived(0) 00032 , which_motor_data_had_errors(0) 00033 , motor_data_packet_torque() 00034 , motor_data_packet_misc() 00035 , tactile_data_type(0) 00036 , tactile_data_valid(0) 00037 , tactile() 00038 , idle_time_us(0) 00039 { 00040 } 00041 00042 EthercatDebug_(const ContainerAllocator& _alloc) 00043 : header(_alloc) 00044 , sensors(_alloc) 00045 , motor_data_type(_alloc) 00046 , which_motors(0) 00047 , which_motor_data_arrived(0) 00048 , which_motor_data_had_errors(0) 00049 , motor_data_packet_torque(_alloc) 00050 , motor_data_packet_misc(_alloc) 00051 , tactile_data_type(0) 00052 , tactile_data_valid(0) 00053 , tactile(_alloc) 00054 , idle_time_us(0) 00055 { 00056 } 00057 00058 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00059 ::std_msgs::Header_<ContainerAllocator> header; 00060 00061 typedef std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > _sensors_type; 00062 std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > sensors; 00063 00064 typedef ::sr_robot_msgs::FromMotorDataType_<ContainerAllocator> _motor_data_type_type; 00065 ::sr_robot_msgs::FromMotorDataType_<ContainerAllocator> motor_data_type; 00066 00067 typedef int16_t _which_motors_type; 00068 int16_t which_motors; 00069 00070 typedef int32_t _which_motor_data_arrived_type; 00071 int32_t which_motor_data_arrived; 00072 00073 typedef int32_t _which_motor_data_had_errors_type; 00074 int32_t which_motor_data_had_errors; 00075 00076 typedef std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > _motor_data_packet_torque_type; 00077 std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > motor_data_packet_torque; 00078 00079 typedef std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > _motor_data_packet_misc_type; 00080 std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > motor_data_packet_misc; 00081 00082 typedef int32_t _tactile_data_type_type; 00083 int32_t tactile_data_type; 00084 00085 typedef int16_t _tactile_data_valid_type; 00086 int16_t tactile_data_valid; 00087 00088 typedef std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > _tactile_type; 00089 std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > tactile; 00090 00091 typedef int16_t _idle_time_us_type; 00092 int16_t idle_time_us; 00093 00094 00095 ROS_DEPRECATED uint32_t get_sensors_size() const { return (uint32_t)sensors.size(); } 00096 ROS_DEPRECATED void set_sensors_size(uint32_t size) { sensors.resize((size_t)size); } 00097 ROS_DEPRECATED void get_sensors_vec(std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > & vec) const { vec = this->sensors; } 00098 ROS_DEPRECATED void set_sensors_vec(const std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > & vec) { this->sensors = vec; } 00099 ROS_DEPRECATED uint32_t get_motor_data_packet_torque_size() const { return (uint32_t)motor_data_packet_torque.size(); } 00100 ROS_DEPRECATED void set_motor_data_packet_torque_size(uint32_t size) { motor_data_packet_torque.resize((size_t)size); } 00101 ROS_DEPRECATED void get_motor_data_packet_torque_vec(std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > & vec) const { vec = this->motor_data_packet_torque; } 00102 ROS_DEPRECATED void set_motor_data_packet_torque_vec(const std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > & vec) { this->motor_data_packet_torque = vec; } 00103 ROS_DEPRECATED uint32_t get_motor_data_packet_misc_size() const { return (uint32_t)motor_data_packet_misc.size(); } 00104 ROS_DEPRECATED void set_motor_data_packet_misc_size(uint32_t size) { motor_data_packet_misc.resize((size_t)size); } 00105 ROS_DEPRECATED void get_motor_data_packet_misc_vec(std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > & vec) const { vec = this->motor_data_packet_misc; } 00106 ROS_DEPRECATED void set_motor_data_packet_misc_vec(const std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > & vec) { this->motor_data_packet_misc = vec; } 00107 ROS_DEPRECATED uint32_t get_tactile_size() const { return (uint32_t)tactile.size(); } 00108 ROS_DEPRECATED void set_tactile_size(uint32_t size) { tactile.resize((size_t)size); } 00109 ROS_DEPRECATED void get_tactile_vec(std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > & vec) const { vec = this->tactile; } 00110 ROS_DEPRECATED void set_tactile_vec(const std::vector<int16_t, typename ContainerAllocator::template rebind<int16_t>::other > & vec) { this->tactile = vec; } 00111 private: 00112 static const char* __s_getDataType_() { return "sr_robot_msgs/EthercatDebug"; } 00113 public: 00114 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00115 00116 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00117 00118 private: 00119 static const char* __s_getMD5Sum_() { return "ed9e30784a7d4571ecf4d526e7ff529f"; } 00120 public: 00121 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00122 00123 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00124 00125 private: 00126 static const char* __s_getMessageDefinition_() { return "Header header\n\ 00127 \n\ 00128 int16[] sensors\n\ 00129 FromMotorDataType motor_data_type\n\ 00130 int16 which_motors\n\ 00131 int32 which_motor_data_arrived\n\ 00132 int32 which_motor_data_had_errors\n\ 00133 int16[] motor_data_packet_torque\n\ 00134 int16[] motor_data_packet_misc\n\ 00135 int32 tactile_data_type\n\ 00136 int16 tactile_data_valid\n\ 00137 int16[] tactile\n\ 00138 int16 idle_time_us\n\ 00139 \n\ 00140 ================================================================================\n\ 00141 MSG: std_msgs/Header\n\ 00142 # Standard metadata for higher-level stamped data types.\n\ 00143 # This is generally used to communicate timestamped data \n\ 00144 # in a particular coordinate frame.\n\ 00145 # \n\ 00146 # sequence ID: consecutively increasing ID \n\ 00147 uint32 seq\n\ 00148 #Two-integer timestamp that is expressed as:\n\ 00149 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00150 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00151 # time-handling sugar is provided by the client library\n\ 00152 time stamp\n\ 00153 #Frame this data is associated with\n\ 00154 # 0: no frame\n\ 00155 # 1: global frame\n\ 00156 string frame_id\n\ 00157 \n\ 00158 ================================================================================\n\ 00159 MSG: sr_robot_msgs/FromMotorDataType\n\ 00160 int16 data\n\ 00161 "; } 00162 public: 00163 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00164 00165 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00166 00167 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00168 { 00169 ros::serialization::OStream stream(write_ptr, 1000000000); 00170 ros::serialization::serialize(stream, header); 00171 ros::serialization::serialize(stream, sensors); 00172 ros::serialization::serialize(stream, motor_data_type); 00173 ros::serialization::serialize(stream, which_motors); 00174 ros::serialization::serialize(stream, which_motor_data_arrived); 00175 ros::serialization::serialize(stream, which_motor_data_had_errors); 00176 ros::serialization::serialize(stream, motor_data_packet_torque); 00177 ros::serialization::serialize(stream, motor_data_packet_misc); 00178 ros::serialization::serialize(stream, tactile_data_type); 00179 ros::serialization::serialize(stream, tactile_data_valid); 00180 ros::serialization::serialize(stream, tactile); 00181 ros::serialization::serialize(stream, idle_time_us); 00182 return stream.getData(); 00183 } 00184 00185 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00186 { 00187 ros::serialization::IStream stream(read_ptr, 1000000000); 00188 ros::serialization::deserialize(stream, header); 00189 ros::serialization::deserialize(stream, sensors); 00190 ros::serialization::deserialize(stream, motor_data_type); 00191 ros::serialization::deserialize(stream, which_motors); 00192 ros::serialization::deserialize(stream, which_motor_data_arrived); 00193 ros::serialization::deserialize(stream, which_motor_data_had_errors); 00194 ros::serialization::deserialize(stream, motor_data_packet_torque); 00195 ros::serialization::deserialize(stream, motor_data_packet_misc); 00196 ros::serialization::deserialize(stream, tactile_data_type); 00197 ros::serialization::deserialize(stream, tactile_data_valid); 00198 ros::serialization::deserialize(stream, tactile); 00199 ros::serialization::deserialize(stream, idle_time_us); 00200 return stream.getData(); 00201 } 00202 00203 ROS_DEPRECATED virtual uint32_t serializationLength() const 00204 { 00205 uint32_t size = 0; 00206 size += ros::serialization::serializationLength(header); 00207 size += ros::serialization::serializationLength(sensors); 00208 size += ros::serialization::serializationLength(motor_data_type); 00209 size += ros::serialization::serializationLength(which_motors); 00210 size += ros::serialization::serializationLength(which_motor_data_arrived); 00211 size += ros::serialization::serializationLength(which_motor_data_had_errors); 00212 size += ros::serialization::serializationLength(motor_data_packet_torque); 00213 size += ros::serialization::serializationLength(motor_data_packet_misc); 00214 size += ros::serialization::serializationLength(tactile_data_type); 00215 size += ros::serialization::serializationLength(tactile_data_valid); 00216 size += ros::serialization::serializationLength(tactile); 00217 size += ros::serialization::serializationLength(idle_time_us); 00218 return size; 00219 } 00220 00221 typedef boost::shared_ptr< ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> > Ptr; 00222 typedef boost::shared_ptr< ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> const> ConstPtr; 00223 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00224 }; // struct EthercatDebug 00225 typedef ::sr_robot_msgs::EthercatDebug_<std::allocator<void> > EthercatDebug; 00226 00227 typedef boost::shared_ptr< ::sr_robot_msgs::EthercatDebug> EthercatDebugPtr; 00228 typedef boost::shared_ptr< ::sr_robot_msgs::EthercatDebug const> EthercatDebugConstPtr; 00229 00230 00231 template<typename ContainerAllocator> 00232 std::ostream& operator<<(std::ostream& s, const ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> & v) 00233 { 00234 ros::message_operations::Printer< ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> >::stream(s, "", v); 00235 return s;} 00236 00237 } // namespace sr_robot_msgs 00238 00239 namespace ros 00240 { 00241 namespace message_traits 00242 { 00243 template<class ContainerAllocator> struct IsMessage< ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> > : public TrueType {}; 00244 template<class ContainerAllocator> struct IsMessage< ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> const> : public TrueType {}; 00245 template<class ContainerAllocator> 00246 struct MD5Sum< ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> > { 00247 static const char* value() 00248 { 00249 return "ed9e30784a7d4571ecf4d526e7ff529f"; 00250 } 00251 00252 static const char* value(const ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> &) { return value(); } 00253 static const uint64_t static_value1 = 0xed9e30784a7d4571ULL; 00254 static const uint64_t static_value2 = 0xecf4d526e7ff529fULL; 00255 }; 00256 00257 template<class ContainerAllocator> 00258 struct DataType< ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> > { 00259 static const char* value() 00260 { 00261 return "sr_robot_msgs/EthercatDebug"; 00262 } 00263 00264 static const char* value(const ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> &) { return value(); } 00265 }; 00266 00267 template<class ContainerAllocator> 00268 struct Definition< ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> > { 00269 static const char* value() 00270 { 00271 return "Header header\n\ 00272 \n\ 00273 int16[] sensors\n\ 00274 FromMotorDataType motor_data_type\n\ 00275 int16 which_motors\n\ 00276 int32 which_motor_data_arrived\n\ 00277 int32 which_motor_data_had_errors\n\ 00278 int16[] motor_data_packet_torque\n\ 00279 int16[] motor_data_packet_misc\n\ 00280 int32 tactile_data_type\n\ 00281 int16 tactile_data_valid\n\ 00282 int16[] tactile\n\ 00283 int16 idle_time_us\n\ 00284 \n\ 00285 ================================================================================\n\ 00286 MSG: std_msgs/Header\n\ 00287 # Standard metadata for higher-level stamped data types.\n\ 00288 # This is generally used to communicate timestamped data \n\ 00289 # in a particular coordinate frame.\n\ 00290 # \n\ 00291 # sequence ID: consecutively increasing ID \n\ 00292 uint32 seq\n\ 00293 #Two-integer timestamp that is expressed as:\n\ 00294 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00295 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00296 # time-handling sugar is provided by the client library\n\ 00297 time stamp\n\ 00298 #Frame this data is associated with\n\ 00299 # 0: no frame\n\ 00300 # 1: global frame\n\ 00301 string frame_id\n\ 00302 \n\ 00303 ================================================================================\n\ 00304 MSG: sr_robot_msgs/FromMotorDataType\n\ 00305 int16 data\n\ 00306 "; 00307 } 00308 00309 static const char* value(const ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> &) { return value(); } 00310 }; 00311 00312 template<class ContainerAllocator> struct HasHeader< ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> > : public TrueType {}; 00313 template<class ContainerAllocator> struct HasHeader< const ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> > : public TrueType {}; 00314 } // namespace message_traits 00315 } // namespace ros 00316 00317 namespace ros 00318 { 00319 namespace serialization 00320 { 00321 00322 template<class ContainerAllocator> struct Serializer< ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> > 00323 { 00324 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00325 { 00326 stream.next(m.header); 00327 stream.next(m.sensors); 00328 stream.next(m.motor_data_type); 00329 stream.next(m.which_motors); 00330 stream.next(m.which_motor_data_arrived); 00331 stream.next(m.which_motor_data_had_errors); 00332 stream.next(m.motor_data_packet_torque); 00333 stream.next(m.motor_data_packet_misc); 00334 stream.next(m.tactile_data_type); 00335 stream.next(m.tactile_data_valid); 00336 stream.next(m.tactile); 00337 stream.next(m.idle_time_us); 00338 } 00339 00340 ROS_DECLARE_ALLINONE_SERIALIZER; 00341 }; // struct EthercatDebug_ 00342 } // namespace serialization 00343 } // namespace ros 00344 00345 namespace ros 00346 { 00347 namespace message_operations 00348 { 00349 00350 template<class ContainerAllocator> 00351 struct Printer< ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> > 00352 { 00353 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sr_robot_msgs::EthercatDebug_<ContainerAllocator> & v) 00354 { 00355 s << indent << "header: "; 00356 s << std::endl; 00357 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00358 s << indent << "sensors[]" << std::endl; 00359 for (size_t i = 0; i < v.sensors.size(); ++i) 00360 { 00361 s << indent << " sensors[" << i << "]: "; 00362 Printer<int16_t>::stream(s, indent + " ", v.sensors[i]); 00363 } 00364 s << indent << "motor_data_type: "; 00365 s << std::endl; 00366 Printer< ::sr_robot_msgs::FromMotorDataType_<ContainerAllocator> >::stream(s, indent + " ", v.motor_data_type); 00367 s << indent << "which_motors: "; 00368 Printer<int16_t>::stream(s, indent + " ", v.which_motors); 00369 s << indent << "which_motor_data_arrived: "; 00370 Printer<int32_t>::stream(s, indent + " ", v.which_motor_data_arrived); 00371 s << indent << "which_motor_data_had_errors: "; 00372 Printer<int32_t>::stream(s, indent + " ", v.which_motor_data_had_errors); 00373 s << indent << "motor_data_packet_torque[]" << std::endl; 00374 for (size_t i = 0; i < v.motor_data_packet_torque.size(); ++i) 00375 { 00376 s << indent << " motor_data_packet_torque[" << i << "]: "; 00377 Printer<int16_t>::stream(s, indent + " ", v.motor_data_packet_torque[i]); 00378 } 00379 s << indent << "motor_data_packet_misc[]" << std::endl; 00380 for (size_t i = 0; i < v.motor_data_packet_misc.size(); ++i) 00381 { 00382 s << indent << " motor_data_packet_misc[" << i << "]: "; 00383 Printer<int16_t>::stream(s, indent + " ", v.motor_data_packet_misc[i]); 00384 } 00385 s << indent << "tactile_data_type: "; 00386 Printer<int32_t>::stream(s, indent + " ", v.tactile_data_type); 00387 s << indent << "tactile_data_valid: "; 00388 Printer<int16_t>::stream(s, indent + " ", v.tactile_data_valid); 00389 s << indent << "tactile[]" << std::endl; 00390 for (size_t i = 0; i < v.tactile.size(); ++i) 00391 { 00392 s << indent << " tactile[" << i << "]: "; 00393 Printer<int16_t>::stream(s, indent + " ", v.tactile[i]); 00394 } 00395 s << indent << "idle_time_us: "; 00396 Printer<int16_t>::stream(s, indent + " ", v.idle_time_us); 00397 } 00398 }; 00399 00400 00401 } // namespace message_operations 00402 } // namespace ros 00403 00404 #endif // SR_ROBOT_MSGS_MESSAGE_ETHERCATDEBUG_H 00405