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