$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/srv/MoveToPose.srv */ 00002 #ifndef PR2_MANIPULATION_CONTROLLERS_SERVICE_MOVETOPOSE_H 00003 #define PR2_MANIPULATION_CONTROLLERS_SERVICE_MOVETOPOSE_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 "ros/service_traits.h" 00018 00019 #include "geometry_msgs/PoseStamped.h" 00020 #include "geometry_msgs/Twist.h" 00021 00022 00023 00024 namespace pr2_manipulation_controllers 00025 { 00026 template <class ContainerAllocator> 00027 struct MoveToPoseRequest_ { 00028 typedef MoveToPoseRequest_<ContainerAllocator> Type; 00029 00030 MoveToPoseRequest_() 00031 : pose() 00032 , tolerance() 00033 { 00034 } 00035 00036 MoveToPoseRequest_(const ContainerAllocator& _alloc) 00037 : pose(_alloc) 00038 , tolerance(_alloc) 00039 { 00040 } 00041 00042 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _pose_type; 00043 ::geometry_msgs::PoseStamped_<ContainerAllocator> pose; 00044 00045 typedef ::geometry_msgs::Twist_<ContainerAllocator> _tolerance_type; 00046 ::geometry_msgs::Twist_<ContainerAllocator> tolerance; 00047 00048 00049 private: 00050 static const char* __s_getDataType_() { return "pr2_manipulation_controllers/MoveToPoseRequest"; } 00051 public: 00052 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00053 00054 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00055 00056 private: 00057 static const char* __s_getMD5Sum_() { return "82f6cf7cdf73d640535ee9f29d47dc63"; } 00058 public: 00059 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00060 00061 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00062 00063 private: 00064 static const char* __s_getServerMD5Sum_() { return "82f6cf7cdf73d640535ee9f29d47dc63"; } 00065 public: 00066 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00067 00068 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00069 00070 private: 00071 static const char* __s_getMessageDefinition_() { return "geometry_msgs/PoseStamped pose\n\ 00072 geometry_msgs/Twist tolerance\n\ 00073 \n\ 00074 ================================================================================\n\ 00075 MSG: geometry_msgs/PoseStamped\n\ 00076 # A Pose with reference coordinate frame and timestamp\n\ 00077 Header header\n\ 00078 Pose pose\n\ 00079 \n\ 00080 ================================================================================\n\ 00081 MSG: std_msgs/Header\n\ 00082 # Standard metadata for higher-level stamped data types.\n\ 00083 # This is generally used to communicate timestamped data \n\ 00084 # in a particular coordinate frame.\n\ 00085 # \n\ 00086 # sequence ID: consecutively increasing ID \n\ 00087 uint32 seq\n\ 00088 #Two-integer timestamp that is expressed as:\n\ 00089 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00090 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00091 # time-handling sugar is provided by the client library\n\ 00092 time stamp\n\ 00093 #Frame this data is associated with\n\ 00094 # 0: no frame\n\ 00095 # 1: global frame\n\ 00096 string frame_id\n\ 00097 \n\ 00098 ================================================================================\n\ 00099 MSG: geometry_msgs/Pose\n\ 00100 # A representation of pose in free space, composed of postion and orientation. \n\ 00101 Point position\n\ 00102 Quaternion orientation\n\ 00103 \n\ 00104 ================================================================================\n\ 00105 MSG: geometry_msgs/Point\n\ 00106 # This contains the position of a point in free space\n\ 00107 float64 x\n\ 00108 float64 y\n\ 00109 float64 z\n\ 00110 \n\ 00111 ================================================================================\n\ 00112 MSG: geometry_msgs/Quaternion\n\ 00113 # This represents an orientation in free space in quaternion form.\n\ 00114 \n\ 00115 float64 x\n\ 00116 float64 y\n\ 00117 float64 z\n\ 00118 float64 w\n\ 00119 \n\ 00120 ================================================================================\n\ 00121 MSG: geometry_msgs/Twist\n\ 00122 # This expresses velocity in free space broken into it's linear and angular parts. \n\ 00123 Vector3 linear\n\ 00124 Vector3 angular\n\ 00125 \n\ 00126 ================================================================================\n\ 00127 MSG: geometry_msgs/Vector3\n\ 00128 # This represents a vector in free space. \n\ 00129 \n\ 00130 float64 x\n\ 00131 float64 y\n\ 00132 float64 z\n\ 00133 "; } 00134 public: 00135 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00136 00137 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00138 00139 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00140 { 00141 ros::serialization::OStream stream(write_ptr, 1000000000); 00142 ros::serialization::serialize(stream, pose); 00143 ros::serialization::serialize(stream, tolerance); 00144 return stream.getData(); 00145 } 00146 00147 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00148 { 00149 ros::serialization::IStream stream(read_ptr, 1000000000); 00150 ros::serialization::deserialize(stream, pose); 00151 ros::serialization::deserialize(stream, tolerance); 00152 return stream.getData(); 00153 } 00154 00155 ROS_DEPRECATED virtual uint32_t serializationLength() const 00156 { 00157 uint32_t size = 0; 00158 size += ros::serialization::serializationLength(pose); 00159 size += ros::serialization::serializationLength(tolerance); 00160 return size; 00161 } 00162 00163 typedef boost::shared_ptr< ::pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> > Ptr; 00164 typedef boost::shared_ptr< ::pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> const> ConstPtr; 00165 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00166 }; // struct MoveToPoseRequest 00167 typedef ::pr2_manipulation_controllers::MoveToPoseRequest_<std::allocator<void> > MoveToPoseRequest; 00168 00169 typedef boost::shared_ptr< ::pr2_manipulation_controllers::MoveToPoseRequest> MoveToPoseRequestPtr; 00170 typedef boost::shared_ptr< ::pr2_manipulation_controllers::MoveToPoseRequest const> MoveToPoseRequestConstPtr; 00171 00172 00173 template <class ContainerAllocator> 00174 struct MoveToPoseResponse_ { 00175 typedef MoveToPoseResponse_<ContainerAllocator> Type; 00176 00177 MoveToPoseResponse_() 00178 { 00179 } 00180 00181 MoveToPoseResponse_(const ContainerAllocator& _alloc) 00182 { 00183 } 00184 00185 00186 private: 00187 static const char* __s_getDataType_() { return "pr2_manipulation_controllers/MoveToPoseResponse"; } 00188 public: 00189 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00190 00191 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00192 00193 private: 00194 static const char* __s_getMD5Sum_() { return "d41d8cd98f00b204e9800998ecf8427e"; } 00195 public: 00196 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00197 00198 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00199 00200 private: 00201 static const char* __s_getServerMD5Sum_() { return "82f6cf7cdf73d640535ee9f29d47dc63"; } 00202 public: 00203 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00204 00205 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00206 00207 private: 00208 static const char* __s_getMessageDefinition_() { return "\n\ 00209 \n\ 00210 "; } 00211 public: 00212 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00213 00214 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00215 00216 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00217 { 00218 ros::serialization::OStream stream(write_ptr, 1000000000); 00219 return stream.getData(); 00220 } 00221 00222 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00223 { 00224 ros::serialization::IStream stream(read_ptr, 1000000000); 00225 return stream.getData(); 00226 } 00227 00228 ROS_DEPRECATED virtual uint32_t serializationLength() const 00229 { 00230 uint32_t size = 0; 00231 return size; 00232 } 00233 00234 typedef boost::shared_ptr< ::pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> > Ptr; 00235 typedef boost::shared_ptr< ::pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> const> ConstPtr; 00236 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00237 }; // struct MoveToPoseResponse 00238 typedef ::pr2_manipulation_controllers::MoveToPoseResponse_<std::allocator<void> > MoveToPoseResponse; 00239 00240 typedef boost::shared_ptr< ::pr2_manipulation_controllers::MoveToPoseResponse> MoveToPoseResponsePtr; 00241 typedef boost::shared_ptr< ::pr2_manipulation_controllers::MoveToPoseResponse const> MoveToPoseResponseConstPtr; 00242 00243 struct MoveToPose 00244 { 00245 00246 typedef MoveToPoseRequest Request; 00247 typedef MoveToPoseResponse Response; 00248 Request request; 00249 Response response; 00250 00251 typedef Request RequestType; 00252 typedef Response ResponseType; 00253 }; // struct MoveToPose 00254 } // namespace pr2_manipulation_controllers 00255 00256 namespace ros 00257 { 00258 namespace message_traits 00259 { 00260 template<class ContainerAllocator> struct IsMessage< ::pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> > : public TrueType {}; 00261 template<class ContainerAllocator> struct IsMessage< ::pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> const> : public TrueType {}; 00262 template<class ContainerAllocator> 00263 struct MD5Sum< ::pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> > { 00264 static const char* value() 00265 { 00266 return "82f6cf7cdf73d640535ee9f29d47dc63"; 00267 } 00268 00269 static const char* value(const ::pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> &) { return value(); } 00270 static const uint64_t static_value1 = 0x82f6cf7cdf73d640ULL; 00271 static const uint64_t static_value2 = 0x535ee9f29d47dc63ULL; 00272 }; 00273 00274 template<class ContainerAllocator> 00275 struct DataType< ::pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> > { 00276 static const char* value() 00277 { 00278 return "pr2_manipulation_controllers/MoveToPoseRequest"; 00279 } 00280 00281 static const char* value(const ::pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> &) { return value(); } 00282 }; 00283 00284 template<class ContainerAllocator> 00285 struct Definition< ::pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> > { 00286 static const char* value() 00287 { 00288 return "geometry_msgs/PoseStamped pose\n\ 00289 geometry_msgs/Twist tolerance\n\ 00290 \n\ 00291 ================================================================================\n\ 00292 MSG: geometry_msgs/PoseStamped\n\ 00293 # A Pose with reference coordinate frame and timestamp\n\ 00294 Header header\n\ 00295 Pose pose\n\ 00296 \n\ 00297 ================================================================================\n\ 00298 MSG: std_msgs/Header\n\ 00299 # Standard metadata for higher-level stamped data types.\n\ 00300 # This is generally used to communicate timestamped data \n\ 00301 # in a particular coordinate frame.\n\ 00302 # \n\ 00303 # sequence ID: consecutively increasing ID \n\ 00304 uint32 seq\n\ 00305 #Two-integer timestamp that is expressed as:\n\ 00306 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00307 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00308 # time-handling sugar is provided by the client library\n\ 00309 time stamp\n\ 00310 #Frame this data is associated with\n\ 00311 # 0: no frame\n\ 00312 # 1: global frame\n\ 00313 string frame_id\n\ 00314 \n\ 00315 ================================================================================\n\ 00316 MSG: geometry_msgs/Pose\n\ 00317 # A representation of pose in free space, composed of postion and orientation. \n\ 00318 Point position\n\ 00319 Quaternion orientation\n\ 00320 \n\ 00321 ================================================================================\n\ 00322 MSG: geometry_msgs/Point\n\ 00323 # This contains the position of a point in free space\n\ 00324 float64 x\n\ 00325 float64 y\n\ 00326 float64 z\n\ 00327 \n\ 00328 ================================================================================\n\ 00329 MSG: geometry_msgs/Quaternion\n\ 00330 # This represents an orientation in free space in quaternion form.\n\ 00331 \n\ 00332 float64 x\n\ 00333 float64 y\n\ 00334 float64 z\n\ 00335 float64 w\n\ 00336 \n\ 00337 ================================================================================\n\ 00338 MSG: geometry_msgs/Twist\n\ 00339 # This expresses velocity in free space broken into it's linear and angular parts. \n\ 00340 Vector3 linear\n\ 00341 Vector3 angular\n\ 00342 \n\ 00343 ================================================================================\n\ 00344 MSG: geometry_msgs/Vector3\n\ 00345 # This represents a vector in free space. \n\ 00346 \n\ 00347 float64 x\n\ 00348 float64 y\n\ 00349 float64 z\n\ 00350 "; 00351 } 00352 00353 static const char* value(const ::pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> &) { return value(); } 00354 }; 00355 00356 } // namespace message_traits 00357 } // namespace ros 00358 00359 00360 namespace ros 00361 { 00362 namespace message_traits 00363 { 00364 template<class ContainerAllocator> struct IsMessage< ::pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> > : public TrueType {}; 00365 template<class ContainerAllocator> struct IsMessage< ::pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> const> : public TrueType {}; 00366 template<class ContainerAllocator> 00367 struct MD5Sum< ::pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> > { 00368 static const char* value() 00369 { 00370 return "d41d8cd98f00b204e9800998ecf8427e"; 00371 } 00372 00373 static const char* value(const ::pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> &) { return value(); } 00374 static const uint64_t static_value1 = 0xd41d8cd98f00b204ULL; 00375 static const uint64_t static_value2 = 0xe9800998ecf8427eULL; 00376 }; 00377 00378 template<class ContainerAllocator> 00379 struct DataType< ::pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> > { 00380 static const char* value() 00381 { 00382 return "pr2_manipulation_controllers/MoveToPoseResponse"; 00383 } 00384 00385 static const char* value(const ::pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> &) { return value(); } 00386 }; 00387 00388 template<class ContainerAllocator> 00389 struct Definition< ::pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> > { 00390 static const char* value() 00391 { 00392 return "\n\ 00393 \n\ 00394 "; 00395 } 00396 00397 static const char* value(const ::pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> &) { return value(); } 00398 }; 00399 00400 template<class ContainerAllocator> struct IsFixedSize< ::pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> > : public TrueType {}; 00401 } // namespace message_traits 00402 } // namespace ros 00403 00404 namespace ros 00405 { 00406 namespace serialization 00407 { 00408 00409 template<class ContainerAllocator> struct Serializer< ::pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> > 00410 { 00411 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00412 { 00413 stream.next(m.pose); 00414 stream.next(m.tolerance); 00415 } 00416 00417 ROS_DECLARE_ALLINONE_SERIALIZER; 00418 }; // struct MoveToPoseRequest_ 00419 } // namespace serialization 00420 } // namespace ros 00421 00422 00423 namespace ros 00424 { 00425 namespace serialization 00426 { 00427 00428 template<class ContainerAllocator> struct Serializer< ::pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> > 00429 { 00430 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00431 { 00432 } 00433 00434 ROS_DECLARE_ALLINONE_SERIALIZER; 00435 }; // struct MoveToPoseResponse_ 00436 } // namespace serialization 00437 } // namespace ros 00438 00439 namespace ros 00440 { 00441 namespace service_traits 00442 { 00443 template<> 00444 struct MD5Sum<pr2_manipulation_controllers::MoveToPose> { 00445 static const char* value() 00446 { 00447 return "82f6cf7cdf73d640535ee9f29d47dc63"; 00448 } 00449 00450 static const char* value(const pr2_manipulation_controllers::MoveToPose&) { return value(); } 00451 }; 00452 00453 template<> 00454 struct DataType<pr2_manipulation_controllers::MoveToPose> { 00455 static const char* value() 00456 { 00457 return "pr2_manipulation_controllers/MoveToPose"; 00458 } 00459 00460 static const char* value(const pr2_manipulation_controllers::MoveToPose&) { return value(); } 00461 }; 00462 00463 template<class ContainerAllocator> 00464 struct MD5Sum<pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> > { 00465 static const char* value() 00466 { 00467 return "82f6cf7cdf73d640535ee9f29d47dc63"; 00468 } 00469 00470 static const char* value(const pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> &) { return value(); } 00471 }; 00472 00473 template<class ContainerAllocator> 00474 struct DataType<pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> > { 00475 static const char* value() 00476 { 00477 return "pr2_manipulation_controllers/MoveToPose"; 00478 } 00479 00480 static const char* value(const pr2_manipulation_controllers::MoveToPoseRequest_<ContainerAllocator> &) { return value(); } 00481 }; 00482 00483 template<class ContainerAllocator> 00484 struct MD5Sum<pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> > { 00485 static const char* value() 00486 { 00487 return "82f6cf7cdf73d640535ee9f29d47dc63"; 00488 } 00489 00490 static const char* value(const pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> &) { return value(); } 00491 }; 00492 00493 template<class ContainerAllocator> 00494 struct DataType<pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> > { 00495 static const char* value() 00496 { 00497 return "pr2_manipulation_controllers/MoveToPose"; 00498 } 00499 00500 static const char* value(const pr2_manipulation_controllers::MoveToPoseResponse_<ContainerAllocator> &) { return value(); } 00501 }; 00502 00503 } // namespace service_traits 00504 } // namespace ros 00505 00506 #endif // PR2_MANIPULATION_CONTROLLERS_SERVICE_MOVETOPOSE_H 00507