$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-pr2_controllers/doc_stacks/2013-03-01_16-45-23.561928/pr2_controllers/robot_mechanism_controllers/msg/JTCartesianControllerState.msg */ 00002 #ifndef ROBOT_MECHANISM_CONTROLLERS_MESSAGE_JTCARTESIANCONTROLLERSTATE_H 00003 #define ROBOT_MECHANISM_CONTROLLERS_MESSAGE_JTCARTESIANCONTROLLERSTATE_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 "geometry_msgs/PoseStamped.h" 00019 #include "geometry_msgs/PoseStamped.h" 00020 #include "geometry_msgs/PoseStamped.h" 00021 #include "geometry_msgs/Twist.h" 00022 #include "geometry_msgs/Twist.h" 00023 #include "geometry_msgs/Twist.h" 00024 #include "geometry_msgs/Wrench.h" 00025 #include "std_msgs/Float64MultiArray.h" 00026 #include "std_msgs/Float64MultiArray.h" 00027 00028 namespace robot_mechanism_controllers 00029 { 00030 template <class ContainerAllocator> 00031 struct JTCartesianControllerState_ { 00032 typedef JTCartesianControllerState_<ContainerAllocator> Type; 00033 00034 JTCartesianControllerState_() 00035 : header() 00036 , x() 00037 , x_desi() 00038 , x_desi_filtered() 00039 , x_err() 00040 , xd() 00041 , xd_desi() 00042 , F() 00043 , tau_pose() 00044 , tau_posture() 00045 , tau() 00046 , J() 00047 , N() 00048 { 00049 } 00050 00051 JTCartesianControllerState_(const ContainerAllocator& _alloc) 00052 : header(_alloc) 00053 , x(_alloc) 00054 , x_desi(_alloc) 00055 , x_desi_filtered(_alloc) 00056 , x_err(_alloc) 00057 , xd(_alloc) 00058 , xd_desi(_alloc) 00059 , F(_alloc) 00060 , tau_pose(_alloc) 00061 , tau_posture(_alloc) 00062 , tau(_alloc) 00063 , J(_alloc) 00064 , N(_alloc) 00065 { 00066 } 00067 00068 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00069 ::std_msgs::Header_<ContainerAllocator> header; 00070 00071 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _x_type; 00072 ::geometry_msgs::PoseStamped_<ContainerAllocator> x; 00073 00074 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _x_desi_type; 00075 ::geometry_msgs::PoseStamped_<ContainerAllocator> x_desi; 00076 00077 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _x_desi_filtered_type; 00078 ::geometry_msgs::PoseStamped_<ContainerAllocator> x_desi_filtered; 00079 00080 typedef ::geometry_msgs::Twist_<ContainerAllocator> _x_err_type; 00081 ::geometry_msgs::Twist_<ContainerAllocator> x_err; 00082 00083 typedef ::geometry_msgs::Twist_<ContainerAllocator> _xd_type; 00084 ::geometry_msgs::Twist_<ContainerAllocator> xd; 00085 00086 typedef ::geometry_msgs::Twist_<ContainerAllocator> _xd_desi_type; 00087 ::geometry_msgs::Twist_<ContainerAllocator> xd_desi; 00088 00089 typedef ::geometry_msgs::Wrench_<ContainerAllocator> _F_type; 00090 ::geometry_msgs::Wrench_<ContainerAllocator> F; 00091 00092 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _tau_pose_type; 00093 std::vector<double, typename ContainerAllocator::template rebind<double>::other > tau_pose; 00094 00095 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _tau_posture_type; 00096 std::vector<double, typename ContainerAllocator::template rebind<double>::other > tau_posture; 00097 00098 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _tau_type; 00099 std::vector<double, typename ContainerAllocator::template rebind<double>::other > tau; 00100 00101 typedef ::std_msgs::Float64MultiArray_<ContainerAllocator> _J_type; 00102 ::std_msgs::Float64MultiArray_<ContainerAllocator> J; 00103 00104 typedef ::std_msgs::Float64MultiArray_<ContainerAllocator> _N_type; 00105 ::std_msgs::Float64MultiArray_<ContainerAllocator> N; 00106 00107 00108 ROS_DEPRECATED uint32_t get_tau_pose_size() const { return (uint32_t)tau_pose.size(); } 00109 ROS_DEPRECATED void set_tau_pose_size(uint32_t size) { tau_pose.resize((size_t)size); } 00110 ROS_DEPRECATED void get_tau_pose_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->tau_pose; } 00111 ROS_DEPRECATED void set_tau_pose_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->tau_pose = vec; } 00112 ROS_DEPRECATED uint32_t get_tau_posture_size() const { return (uint32_t)tau_posture.size(); } 00113 ROS_DEPRECATED void set_tau_posture_size(uint32_t size) { tau_posture.resize((size_t)size); } 00114 ROS_DEPRECATED void get_tau_posture_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->tau_posture; } 00115 ROS_DEPRECATED void set_tau_posture_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->tau_posture = vec; } 00116 ROS_DEPRECATED uint32_t get_tau_size() const { return (uint32_t)tau.size(); } 00117 ROS_DEPRECATED void set_tau_size(uint32_t size) { tau.resize((size_t)size); } 00118 ROS_DEPRECATED void get_tau_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->tau; } 00119 ROS_DEPRECATED void set_tau_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->tau = vec; } 00120 private: 00121 static const char* __s_getDataType_() { return "robot_mechanism_controllers/JTCartesianControllerState"; } 00122 public: 00123 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00124 00125 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00126 00127 private: 00128 static const char* __s_getMD5Sum_() { return "6ecdaa599ea0d27643819ae4cd4c43d0"; } 00129 public: 00130 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00131 00132 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00133 00134 private: 00135 static const char* __s_getMessageDefinition_() { return "Header header\n\ 00136 geometry_msgs/PoseStamped x\n\ 00137 geometry_msgs/PoseStamped x_desi\n\ 00138 geometry_msgs/PoseStamped x_desi_filtered\n\ 00139 geometry_msgs/Twist x_err\n\ 00140 geometry_msgs/Twist xd\n\ 00141 geometry_msgs/Twist xd_desi\n\ 00142 geometry_msgs/Wrench F\n\ 00143 float64[] tau_pose\n\ 00144 float64[] tau_posture\n\ 00145 float64[] tau\n\ 00146 std_msgs/Float64MultiArray J\n\ 00147 std_msgs/Float64MultiArray N\n\ 00148 \n\ 00149 ================================================================================\n\ 00150 MSG: std_msgs/Header\n\ 00151 # Standard metadata for higher-level stamped data types.\n\ 00152 # This is generally used to communicate timestamped data \n\ 00153 # in a particular coordinate frame.\n\ 00154 # \n\ 00155 # sequence ID: consecutively increasing ID \n\ 00156 uint32 seq\n\ 00157 #Two-integer timestamp that is expressed as:\n\ 00158 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00159 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00160 # time-handling sugar is provided by the client library\n\ 00161 time stamp\n\ 00162 #Frame this data is associated with\n\ 00163 # 0: no frame\n\ 00164 # 1: global frame\n\ 00165 string frame_id\n\ 00166 \n\ 00167 ================================================================================\n\ 00168 MSG: geometry_msgs/PoseStamped\n\ 00169 # A Pose with reference coordinate frame and timestamp\n\ 00170 Header header\n\ 00171 Pose pose\n\ 00172 \n\ 00173 ================================================================================\n\ 00174 MSG: geometry_msgs/Pose\n\ 00175 # A representation of pose in free space, composed of postion and orientation. \n\ 00176 Point position\n\ 00177 Quaternion orientation\n\ 00178 \n\ 00179 ================================================================================\n\ 00180 MSG: geometry_msgs/Point\n\ 00181 # This contains the position of a point in free space\n\ 00182 float64 x\n\ 00183 float64 y\n\ 00184 float64 z\n\ 00185 \n\ 00186 ================================================================================\n\ 00187 MSG: geometry_msgs/Quaternion\n\ 00188 # This represents an orientation in free space in quaternion form.\n\ 00189 \n\ 00190 float64 x\n\ 00191 float64 y\n\ 00192 float64 z\n\ 00193 float64 w\n\ 00194 \n\ 00195 ================================================================================\n\ 00196 MSG: geometry_msgs/Twist\n\ 00197 # This expresses velocity in free space broken into it's linear and angular parts. \n\ 00198 Vector3 linear\n\ 00199 Vector3 angular\n\ 00200 \n\ 00201 ================================================================================\n\ 00202 MSG: geometry_msgs/Vector3\n\ 00203 # This represents a vector in free space. \n\ 00204 \n\ 00205 float64 x\n\ 00206 float64 y\n\ 00207 float64 z\n\ 00208 ================================================================================\n\ 00209 MSG: geometry_msgs/Wrench\n\ 00210 # This represents force in free space, seperated into \n\ 00211 # it's linear and angular parts. \n\ 00212 Vector3 force\n\ 00213 Vector3 torque\n\ 00214 \n\ 00215 ================================================================================\n\ 00216 MSG: std_msgs/Float64MultiArray\n\ 00217 # Please look at the MultiArrayLayout message definition for\n\ 00218 # documentation on all multiarrays.\n\ 00219 \n\ 00220 MultiArrayLayout layout # specification of data layout\n\ 00221 float64[] data # array of data\n\ 00222 \n\ 00223 \n\ 00224 ================================================================================\n\ 00225 MSG: std_msgs/MultiArrayLayout\n\ 00226 # The multiarray declares a generic multi-dimensional array of a\n\ 00227 # particular data type. Dimensions are ordered from outer most\n\ 00228 # to inner most.\n\ 00229 \n\ 00230 MultiArrayDimension[] dim # Array of dimension properties\n\ 00231 uint32 data_offset # padding bytes at front of data\n\ 00232 \n\ 00233 # Accessors should ALWAYS be written in terms of dimension stride\n\ 00234 # and specified outer-most dimension first.\n\ 00235 # \n\ 00236 # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\ 00237 #\n\ 00238 # A standard, 3-channel 640x480 image with interleaved color channels\n\ 00239 # would be specified as:\n\ 00240 #\n\ 00241 # dim[0].label = \"height\"\n\ 00242 # dim[0].size = 480\n\ 00243 # dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\ 00244 # dim[1].label = \"width\"\n\ 00245 # dim[1].size = 640\n\ 00246 # dim[1].stride = 3*640 = 1920\n\ 00247 # dim[2].label = \"channel\"\n\ 00248 # dim[2].size = 3\n\ 00249 # dim[2].stride = 3\n\ 00250 #\n\ 00251 # multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\ 00252 ================================================================================\n\ 00253 MSG: std_msgs/MultiArrayDimension\n\ 00254 string label # label of given dimension\n\ 00255 uint32 size # size of given dimension (in type units)\n\ 00256 uint32 stride # stride of given dimension\n\ 00257 "; } 00258 public: 00259 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00260 00261 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00262 00263 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00264 { 00265 ros::serialization::OStream stream(write_ptr, 1000000000); 00266 ros::serialization::serialize(stream, header); 00267 ros::serialization::serialize(stream, x); 00268 ros::serialization::serialize(stream, x_desi); 00269 ros::serialization::serialize(stream, x_desi_filtered); 00270 ros::serialization::serialize(stream, x_err); 00271 ros::serialization::serialize(stream, xd); 00272 ros::serialization::serialize(stream, xd_desi); 00273 ros::serialization::serialize(stream, F); 00274 ros::serialization::serialize(stream, tau_pose); 00275 ros::serialization::serialize(stream, tau_posture); 00276 ros::serialization::serialize(stream, tau); 00277 ros::serialization::serialize(stream, J); 00278 ros::serialization::serialize(stream, N); 00279 return stream.getData(); 00280 } 00281 00282 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00283 { 00284 ros::serialization::IStream stream(read_ptr, 1000000000); 00285 ros::serialization::deserialize(stream, header); 00286 ros::serialization::deserialize(stream, x); 00287 ros::serialization::deserialize(stream, x_desi); 00288 ros::serialization::deserialize(stream, x_desi_filtered); 00289 ros::serialization::deserialize(stream, x_err); 00290 ros::serialization::deserialize(stream, xd); 00291 ros::serialization::deserialize(stream, xd_desi); 00292 ros::serialization::deserialize(stream, F); 00293 ros::serialization::deserialize(stream, tau_pose); 00294 ros::serialization::deserialize(stream, tau_posture); 00295 ros::serialization::deserialize(stream, tau); 00296 ros::serialization::deserialize(stream, J); 00297 ros::serialization::deserialize(stream, N); 00298 return stream.getData(); 00299 } 00300 00301 ROS_DEPRECATED virtual uint32_t serializationLength() const 00302 { 00303 uint32_t size = 0; 00304 size += ros::serialization::serializationLength(header); 00305 size += ros::serialization::serializationLength(x); 00306 size += ros::serialization::serializationLength(x_desi); 00307 size += ros::serialization::serializationLength(x_desi_filtered); 00308 size += ros::serialization::serializationLength(x_err); 00309 size += ros::serialization::serializationLength(xd); 00310 size += ros::serialization::serializationLength(xd_desi); 00311 size += ros::serialization::serializationLength(F); 00312 size += ros::serialization::serializationLength(tau_pose); 00313 size += ros::serialization::serializationLength(tau_posture); 00314 size += ros::serialization::serializationLength(tau); 00315 size += ros::serialization::serializationLength(J); 00316 size += ros::serialization::serializationLength(N); 00317 return size; 00318 } 00319 00320 typedef boost::shared_ptr< ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> > Ptr; 00321 typedef boost::shared_ptr< ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> const> ConstPtr; 00322 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00323 }; // struct JTCartesianControllerState 00324 typedef ::robot_mechanism_controllers::JTCartesianControllerState_<std::allocator<void> > JTCartesianControllerState; 00325 00326 typedef boost::shared_ptr< ::robot_mechanism_controllers::JTCartesianControllerState> JTCartesianControllerStatePtr; 00327 typedef boost::shared_ptr< ::robot_mechanism_controllers::JTCartesianControllerState const> JTCartesianControllerStateConstPtr; 00328 00329 00330 template<typename ContainerAllocator> 00331 std::ostream& operator<<(std::ostream& s, const ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> & v) 00332 { 00333 ros::message_operations::Printer< ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> >::stream(s, "", v); 00334 return s;} 00335 00336 } // namespace robot_mechanism_controllers 00337 00338 namespace ros 00339 { 00340 namespace message_traits 00341 { 00342 template<class ContainerAllocator> struct IsMessage< ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> > : public TrueType {}; 00343 template<class ContainerAllocator> struct IsMessage< ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> const> : public TrueType {}; 00344 template<class ContainerAllocator> 00345 struct MD5Sum< ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> > { 00346 static const char* value() 00347 { 00348 return "6ecdaa599ea0d27643819ae4cd4c43d0"; 00349 } 00350 00351 static const char* value(const ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> &) { return value(); } 00352 static const uint64_t static_value1 = 0x6ecdaa599ea0d276ULL; 00353 static const uint64_t static_value2 = 0x43819ae4cd4c43d0ULL; 00354 }; 00355 00356 template<class ContainerAllocator> 00357 struct DataType< ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> > { 00358 static const char* value() 00359 { 00360 return "robot_mechanism_controllers/JTCartesianControllerState"; 00361 } 00362 00363 static const char* value(const ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> &) { return value(); } 00364 }; 00365 00366 template<class ContainerAllocator> 00367 struct Definition< ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> > { 00368 static const char* value() 00369 { 00370 return "Header header\n\ 00371 geometry_msgs/PoseStamped x\n\ 00372 geometry_msgs/PoseStamped x_desi\n\ 00373 geometry_msgs/PoseStamped x_desi_filtered\n\ 00374 geometry_msgs/Twist x_err\n\ 00375 geometry_msgs/Twist xd\n\ 00376 geometry_msgs/Twist xd_desi\n\ 00377 geometry_msgs/Wrench F\n\ 00378 float64[] tau_pose\n\ 00379 float64[] tau_posture\n\ 00380 float64[] tau\n\ 00381 std_msgs/Float64MultiArray J\n\ 00382 std_msgs/Float64MultiArray N\n\ 00383 \n\ 00384 ================================================================================\n\ 00385 MSG: std_msgs/Header\n\ 00386 # Standard metadata for higher-level stamped data types.\n\ 00387 # This is generally used to communicate timestamped data \n\ 00388 # in a particular coordinate frame.\n\ 00389 # \n\ 00390 # sequence ID: consecutively increasing ID \n\ 00391 uint32 seq\n\ 00392 #Two-integer timestamp that is expressed as:\n\ 00393 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00394 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00395 # time-handling sugar is provided by the client library\n\ 00396 time stamp\n\ 00397 #Frame this data is associated with\n\ 00398 # 0: no frame\n\ 00399 # 1: global frame\n\ 00400 string frame_id\n\ 00401 \n\ 00402 ================================================================================\n\ 00403 MSG: geometry_msgs/PoseStamped\n\ 00404 # A Pose with reference coordinate frame and timestamp\n\ 00405 Header header\n\ 00406 Pose pose\n\ 00407 \n\ 00408 ================================================================================\n\ 00409 MSG: geometry_msgs/Pose\n\ 00410 # A representation of pose in free space, composed of postion and orientation. \n\ 00411 Point position\n\ 00412 Quaternion orientation\n\ 00413 \n\ 00414 ================================================================================\n\ 00415 MSG: geometry_msgs/Point\n\ 00416 # This contains the position of a point in free space\n\ 00417 float64 x\n\ 00418 float64 y\n\ 00419 float64 z\n\ 00420 \n\ 00421 ================================================================================\n\ 00422 MSG: geometry_msgs/Quaternion\n\ 00423 # This represents an orientation in free space in quaternion form.\n\ 00424 \n\ 00425 float64 x\n\ 00426 float64 y\n\ 00427 float64 z\n\ 00428 float64 w\n\ 00429 \n\ 00430 ================================================================================\n\ 00431 MSG: geometry_msgs/Twist\n\ 00432 # This expresses velocity in free space broken into it's linear and angular parts. \n\ 00433 Vector3 linear\n\ 00434 Vector3 angular\n\ 00435 \n\ 00436 ================================================================================\n\ 00437 MSG: geometry_msgs/Vector3\n\ 00438 # This represents a vector in free space. \n\ 00439 \n\ 00440 float64 x\n\ 00441 float64 y\n\ 00442 float64 z\n\ 00443 ================================================================================\n\ 00444 MSG: geometry_msgs/Wrench\n\ 00445 # This represents force in free space, seperated into \n\ 00446 # it's linear and angular parts. \n\ 00447 Vector3 force\n\ 00448 Vector3 torque\n\ 00449 \n\ 00450 ================================================================================\n\ 00451 MSG: std_msgs/Float64MultiArray\n\ 00452 # Please look at the MultiArrayLayout message definition for\n\ 00453 # documentation on all multiarrays.\n\ 00454 \n\ 00455 MultiArrayLayout layout # specification of data layout\n\ 00456 float64[] data # array of data\n\ 00457 \n\ 00458 \n\ 00459 ================================================================================\n\ 00460 MSG: std_msgs/MultiArrayLayout\n\ 00461 # The multiarray declares a generic multi-dimensional array of a\n\ 00462 # particular data type. Dimensions are ordered from outer most\n\ 00463 # to inner most.\n\ 00464 \n\ 00465 MultiArrayDimension[] dim # Array of dimension properties\n\ 00466 uint32 data_offset # padding bytes at front of data\n\ 00467 \n\ 00468 # Accessors should ALWAYS be written in terms of dimension stride\n\ 00469 # and specified outer-most dimension first.\n\ 00470 # \n\ 00471 # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\ 00472 #\n\ 00473 # A standard, 3-channel 640x480 image with interleaved color channels\n\ 00474 # would be specified as:\n\ 00475 #\n\ 00476 # dim[0].label = \"height\"\n\ 00477 # dim[0].size = 480\n\ 00478 # dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\ 00479 # dim[1].label = \"width\"\n\ 00480 # dim[1].size = 640\n\ 00481 # dim[1].stride = 3*640 = 1920\n\ 00482 # dim[2].label = \"channel\"\n\ 00483 # dim[2].size = 3\n\ 00484 # dim[2].stride = 3\n\ 00485 #\n\ 00486 # multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\ 00487 ================================================================================\n\ 00488 MSG: std_msgs/MultiArrayDimension\n\ 00489 string label # label of given dimension\n\ 00490 uint32 size # size of given dimension (in type units)\n\ 00491 uint32 stride # stride of given dimension\n\ 00492 "; 00493 } 00494 00495 static const char* value(const ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> &) { return value(); } 00496 }; 00497 00498 template<class ContainerAllocator> struct HasHeader< ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> > : public TrueType {}; 00499 template<class ContainerAllocator> struct HasHeader< const ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> > : public TrueType {}; 00500 } // namespace message_traits 00501 } // namespace ros 00502 00503 namespace ros 00504 { 00505 namespace serialization 00506 { 00507 00508 template<class ContainerAllocator> struct Serializer< ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> > 00509 { 00510 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00511 { 00512 stream.next(m.header); 00513 stream.next(m.x); 00514 stream.next(m.x_desi); 00515 stream.next(m.x_desi_filtered); 00516 stream.next(m.x_err); 00517 stream.next(m.xd); 00518 stream.next(m.xd_desi); 00519 stream.next(m.F); 00520 stream.next(m.tau_pose); 00521 stream.next(m.tau_posture); 00522 stream.next(m.tau); 00523 stream.next(m.J); 00524 stream.next(m.N); 00525 } 00526 00527 ROS_DECLARE_ALLINONE_SERIALIZER; 00528 }; // struct JTCartesianControllerState_ 00529 } // namespace serialization 00530 } // namespace ros 00531 00532 namespace ros 00533 { 00534 namespace message_operations 00535 { 00536 00537 template<class ContainerAllocator> 00538 struct Printer< ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> > 00539 { 00540 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::robot_mechanism_controllers::JTCartesianControllerState_<ContainerAllocator> & v) 00541 { 00542 s << indent << "header: "; 00543 s << std::endl; 00544 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00545 s << indent << "x: "; 00546 s << std::endl; 00547 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.x); 00548 s << indent << "x_desi: "; 00549 s << std::endl; 00550 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.x_desi); 00551 s << indent << "x_desi_filtered: "; 00552 s << std::endl; 00553 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.x_desi_filtered); 00554 s << indent << "x_err: "; 00555 s << std::endl; 00556 Printer< ::geometry_msgs::Twist_<ContainerAllocator> >::stream(s, indent + " ", v.x_err); 00557 s << indent << "xd: "; 00558 s << std::endl; 00559 Printer< ::geometry_msgs::Twist_<ContainerAllocator> >::stream(s, indent + " ", v.xd); 00560 s << indent << "xd_desi: "; 00561 s << std::endl; 00562 Printer< ::geometry_msgs::Twist_<ContainerAllocator> >::stream(s, indent + " ", v.xd_desi); 00563 s << indent << "F: "; 00564 s << std::endl; 00565 Printer< ::geometry_msgs::Wrench_<ContainerAllocator> >::stream(s, indent + " ", v.F); 00566 s << indent << "tau_pose[]" << std::endl; 00567 for (size_t i = 0; i < v.tau_pose.size(); ++i) 00568 { 00569 s << indent << " tau_pose[" << i << "]: "; 00570 Printer<double>::stream(s, indent + " ", v.tau_pose[i]); 00571 } 00572 s << indent << "tau_posture[]" << std::endl; 00573 for (size_t i = 0; i < v.tau_posture.size(); ++i) 00574 { 00575 s << indent << " tau_posture[" << i << "]: "; 00576 Printer<double>::stream(s, indent + " ", v.tau_posture[i]); 00577 } 00578 s << indent << "tau[]" << std::endl; 00579 for (size_t i = 0; i < v.tau.size(); ++i) 00580 { 00581 s << indent << " tau[" << i << "]: "; 00582 Printer<double>::stream(s, indent + " ", v.tau[i]); 00583 } 00584 s << indent << "J: "; 00585 s << std::endl; 00586 Printer< ::std_msgs::Float64MultiArray_<ContainerAllocator> >::stream(s, indent + " ", v.J); 00587 s << indent << "N: "; 00588 s << std::endl; 00589 Printer< ::std_msgs::Float64MultiArray_<ContainerAllocator> >::stream(s, indent + " ", v.N); 00590 } 00591 }; 00592 00593 00594 } // namespace message_operations 00595 } // namespace ros 00596 00597 #endif // ROBOT_MECHANISM_CONTROLLERS_MESSAGE_JTCARTESIANCONTROLLERSTATE_H 00598