00001
00002 #ifndef NAV_MSGS_SERVICE_GETPLAN_H
00003 #define NAV_MSGS_SERVICE_GETPLAN_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/PoseStamped.h"
00021
00022
00023 #include "nav_msgs/Path.h"
00024
00025 namespace nav_msgs
00026 {
00027 template <class ContainerAllocator>
00028 struct GetPlanRequest_ {
00029 typedef GetPlanRequest_<ContainerAllocator> Type;
00030
00031 GetPlanRequest_()
00032 : start()
00033 , goal()
00034 , tolerance(0.0)
00035 {
00036 }
00037
00038 GetPlanRequest_(const ContainerAllocator& _alloc)
00039 : start(_alloc)
00040 , goal(_alloc)
00041 , tolerance(0.0)
00042 {
00043 }
00044
00045 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _start_type;
00046 ::geometry_msgs::PoseStamped_<ContainerAllocator> start;
00047
00048 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _goal_type;
00049 ::geometry_msgs::PoseStamped_<ContainerAllocator> goal;
00050
00051 typedef float _tolerance_type;
00052 float tolerance;
00053
00054
00055 private:
00056 static const char* __s_getDataType_() { return "nav_msgs/GetPlanRequest"; }
00057 public:
00058 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00059
00060 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00061
00062 private:
00063 static const char* __s_getMD5Sum_() { return "e25a43e0752bcca599a8c2eef8282df8"; }
00064 public:
00065 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00066
00067 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00068
00069 private:
00070 static const char* __s_getServerMD5Sum_() { return "421c8ea4d21c6c9db7054b4bbdf1e024"; }
00071 public:
00072 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00073
00074 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00075
00076 private:
00077 static const char* __s_getMessageDefinition_() { return "\n\
00078 \n\
00079 \n\
00080 geometry_msgs/PoseStamped start\n\
00081 \n\
00082 \n\
00083 geometry_msgs/PoseStamped goal\n\
00084 \n\
00085 \n\
00086 \n\
00087 float32 tolerance\n\
00088 \n\
00089 ================================================================================\n\
00090 MSG: geometry_msgs/PoseStamped\n\
00091 # A Pose with reference coordinate frame and timestamp\n\
00092 Header header\n\
00093 Pose pose\n\
00094 \n\
00095 ================================================================================\n\
00096 MSG: std_msgs/Header\n\
00097 # Standard metadata for higher-level stamped data types.\n\
00098 # This is generally used to communicate timestamped data \n\
00099 # in a particular coordinate frame.\n\
00100 # \n\
00101 # sequence ID: consecutively increasing ID \n\
00102 uint32 seq\n\
00103 #Two-integer timestamp that is expressed as:\n\
00104 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00105 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00106 # time-handling sugar is provided by the client library\n\
00107 time stamp\n\
00108 #Frame this data is associated with\n\
00109 # 0: no frame\n\
00110 # 1: global frame\n\
00111 string frame_id\n\
00112 \n\
00113 ================================================================================\n\
00114 MSG: geometry_msgs/Pose\n\
00115 # A representation of pose in free space, composed of postion and orientation. \n\
00116 Point position\n\
00117 Quaternion orientation\n\
00118 \n\
00119 ================================================================================\n\
00120 MSG: geometry_msgs/Point\n\
00121 # This contains the position of a point in free space\n\
00122 float64 x\n\
00123 float64 y\n\
00124 float64 z\n\
00125 \n\
00126 ================================================================================\n\
00127 MSG: geometry_msgs/Quaternion\n\
00128 # This represents an orientation in free space in quaternion form.\n\
00129 \n\
00130 float64 x\n\
00131 float64 y\n\
00132 float64 z\n\
00133 float64 w\n\
00134 \n\
00135 "; }
00136 public:
00137 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00138
00139 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00140
00141 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00142 {
00143 ros::serialization::OStream stream(write_ptr, 1000000000);
00144 ros::serialization::serialize(stream, start);
00145 ros::serialization::serialize(stream, goal);
00146 ros::serialization::serialize(stream, tolerance);
00147 return stream.getData();
00148 }
00149
00150 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00151 {
00152 ros::serialization::IStream stream(read_ptr, 1000000000);
00153 ros::serialization::deserialize(stream, start);
00154 ros::serialization::deserialize(stream, goal);
00155 ros::serialization::deserialize(stream, tolerance);
00156 return stream.getData();
00157 }
00158
00159 ROS_DEPRECATED virtual uint32_t serializationLength() const
00160 {
00161 uint32_t size = 0;
00162 size += ros::serialization::serializationLength(start);
00163 size += ros::serialization::serializationLength(goal);
00164 size += ros::serialization::serializationLength(tolerance);
00165 return size;
00166 }
00167
00168 typedef boost::shared_ptr< ::nav_msgs::GetPlanRequest_<ContainerAllocator> > Ptr;
00169 typedef boost::shared_ptr< ::nav_msgs::GetPlanRequest_<ContainerAllocator> const> ConstPtr;
00170 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00171 };
00172 typedef ::nav_msgs::GetPlanRequest_<std::allocator<void> > GetPlanRequest;
00173
00174 typedef boost::shared_ptr< ::nav_msgs::GetPlanRequest> GetPlanRequestPtr;
00175 typedef boost::shared_ptr< ::nav_msgs::GetPlanRequest const> GetPlanRequestConstPtr;
00176
00177
00178 template <class ContainerAllocator>
00179 struct GetPlanResponse_ {
00180 typedef GetPlanResponse_<ContainerAllocator> Type;
00181
00182 GetPlanResponse_()
00183 : plan()
00184 {
00185 }
00186
00187 GetPlanResponse_(const ContainerAllocator& _alloc)
00188 : plan(_alloc)
00189 {
00190 }
00191
00192 typedef ::nav_msgs::Path_<ContainerAllocator> _plan_type;
00193 ::nav_msgs::Path_<ContainerAllocator> plan;
00194
00195
00196 private:
00197 static const char* __s_getDataType_() { return "nav_msgs/GetPlanResponse"; }
00198 public:
00199 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00200
00201 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00202
00203 private:
00204 static const char* __s_getMD5Sum_() { return "0002bc113c0259d71f6cf8cbc9430e18"; }
00205 public:
00206 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00207
00208 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00209
00210 private:
00211 static const char* __s_getServerMD5Sum_() { return "421c8ea4d21c6c9db7054b4bbdf1e024"; }
00212 public:
00213 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00214
00215 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00216
00217 private:
00218 static const char* __s_getMessageDefinition_() { return "nav_msgs/Path plan\n\
00219 \n\
00220 \n\
00221 ================================================================================\n\
00222 MSG: nav_msgs/Path\n\
00223 #An array of poses that represents a Path for a robot to follow\n\
00224 Header header\n\
00225 geometry_msgs/PoseStamped[] poses\n\
00226 \n\
00227 ================================================================================\n\
00228 MSG: std_msgs/Header\n\
00229 # Standard metadata for higher-level stamped data types.\n\
00230 # This is generally used to communicate timestamped data \n\
00231 # in a particular coordinate frame.\n\
00232 # \n\
00233 # sequence ID: consecutively increasing ID \n\
00234 uint32 seq\n\
00235 #Two-integer timestamp that is expressed as:\n\
00236 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00237 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00238 # time-handling sugar is provided by the client library\n\
00239 time stamp\n\
00240 #Frame this data is associated with\n\
00241 # 0: no frame\n\
00242 # 1: global frame\n\
00243 string frame_id\n\
00244 \n\
00245 ================================================================================\n\
00246 MSG: geometry_msgs/PoseStamped\n\
00247 # A Pose with reference coordinate frame and timestamp\n\
00248 Header header\n\
00249 Pose pose\n\
00250 \n\
00251 ================================================================================\n\
00252 MSG: geometry_msgs/Pose\n\
00253 # A representation of pose in free space, composed of postion and orientation. \n\
00254 Point position\n\
00255 Quaternion orientation\n\
00256 \n\
00257 ================================================================================\n\
00258 MSG: geometry_msgs/Point\n\
00259 # This contains the position of a point in free space\n\
00260 float64 x\n\
00261 float64 y\n\
00262 float64 z\n\
00263 \n\
00264 ================================================================================\n\
00265 MSG: geometry_msgs/Quaternion\n\
00266 # This represents an orientation in free space in quaternion form.\n\
00267 \n\
00268 float64 x\n\
00269 float64 y\n\
00270 float64 z\n\
00271 float64 w\n\
00272 \n\
00273 "; }
00274 public:
00275 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00276
00277 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00278
00279 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00280 {
00281 ros::serialization::OStream stream(write_ptr, 1000000000);
00282 ros::serialization::serialize(stream, plan);
00283 return stream.getData();
00284 }
00285
00286 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00287 {
00288 ros::serialization::IStream stream(read_ptr, 1000000000);
00289 ros::serialization::deserialize(stream, plan);
00290 return stream.getData();
00291 }
00292
00293 ROS_DEPRECATED virtual uint32_t serializationLength() const
00294 {
00295 uint32_t size = 0;
00296 size += ros::serialization::serializationLength(plan);
00297 return size;
00298 }
00299
00300 typedef boost::shared_ptr< ::nav_msgs::GetPlanResponse_<ContainerAllocator> > Ptr;
00301 typedef boost::shared_ptr< ::nav_msgs::GetPlanResponse_<ContainerAllocator> const> ConstPtr;
00302 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00303 };
00304 typedef ::nav_msgs::GetPlanResponse_<std::allocator<void> > GetPlanResponse;
00305
00306 typedef boost::shared_ptr< ::nav_msgs::GetPlanResponse> GetPlanResponsePtr;
00307 typedef boost::shared_ptr< ::nav_msgs::GetPlanResponse const> GetPlanResponseConstPtr;
00308
00309 struct GetPlan
00310 {
00311
00312 typedef GetPlanRequest Request;
00313 typedef GetPlanResponse Response;
00314 Request request;
00315 Response response;
00316
00317 typedef Request RequestType;
00318 typedef Response ResponseType;
00319 };
00320 }
00321
00322 namespace ros
00323 {
00324 namespace message_traits
00325 {
00326 template<class ContainerAllocator> struct IsMessage< ::nav_msgs::GetPlanRequest_<ContainerAllocator> > : public TrueType {};
00327 template<class ContainerAllocator> struct IsMessage< ::nav_msgs::GetPlanRequest_<ContainerAllocator> const> : public TrueType {};
00328 template<class ContainerAllocator>
00329 struct MD5Sum< ::nav_msgs::GetPlanRequest_<ContainerAllocator> > {
00330 static const char* value()
00331 {
00332 return "e25a43e0752bcca599a8c2eef8282df8";
00333 }
00334
00335 static const char* value(const ::nav_msgs::GetPlanRequest_<ContainerAllocator> &) { return value(); }
00336 static const uint64_t static_value1 = 0xe25a43e0752bcca5ULL;
00337 static const uint64_t static_value2 = 0x99a8c2eef8282df8ULL;
00338 };
00339
00340 template<class ContainerAllocator>
00341 struct DataType< ::nav_msgs::GetPlanRequest_<ContainerAllocator> > {
00342 static const char* value()
00343 {
00344 return "nav_msgs/GetPlanRequest";
00345 }
00346
00347 static const char* value(const ::nav_msgs::GetPlanRequest_<ContainerAllocator> &) { return value(); }
00348 };
00349
00350 template<class ContainerAllocator>
00351 struct Definition< ::nav_msgs::GetPlanRequest_<ContainerAllocator> > {
00352 static const char* value()
00353 {
00354 return "\n\
00355 \n\
00356 \n\
00357 geometry_msgs/PoseStamped start\n\
00358 \n\
00359 \n\
00360 geometry_msgs/PoseStamped goal\n\
00361 \n\
00362 \n\
00363 \n\
00364 float32 tolerance\n\
00365 \n\
00366 ================================================================================\n\
00367 MSG: geometry_msgs/PoseStamped\n\
00368 # A Pose with reference coordinate frame and timestamp\n\
00369 Header header\n\
00370 Pose pose\n\
00371 \n\
00372 ================================================================================\n\
00373 MSG: std_msgs/Header\n\
00374 # Standard metadata for higher-level stamped data types.\n\
00375 # This is generally used to communicate timestamped data \n\
00376 # in a particular coordinate frame.\n\
00377 # \n\
00378 # sequence ID: consecutively increasing ID \n\
00379 uint32 seq\n\
00380 #Two-integer timestamp that is expressed as:\n\
00381 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00382 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00383 # time-handling sugar is provided by the client library\n\
00384 time stamp\n\
00385 #Frame this data is associated with\n\
00386 # 0: no frame\n\
00387 # 1: global frame\n\
00388 string frame_id\n\
00389 \n\
00390 ================================================================================\n\
00391 MSG: geometry_msgs/Pose\n\
00392 # A representation of pose in free space, composed of postion and orientation. \n\
00393 Point position\n\
00394 Quaternion orientation\n\
00395 \n\
00396 ================================================================================\n\
00397 MSG: geometry_msgs/Point\n\
00398 # This contains the position of a point in free space\n\
00399 float64 x\n\
00400 float64 y\n\
00401 float64 z\n\
00402 \n\
00403 ================================================================================\n\
00404 MSG: geometry_msgs/Quaternion\n\
00405 # This represents an orientation in free space in quaternion form.\n\
00406 \n\
00407 float64 x\n\
00408 float64 y\n\
00409 float64 z\n\
00410 float64 w\n\
00411 \n\
00412 ";
00413 }
00414
00415 static const char* value(const ::nav_msgs::GetPlanRequest_<ContainerAllocator> &) { return value(); }
00416 };
00417
00418 }
00419 }
00420
00421
00422 namespace ros
00423 {
00424 namespace message_traits
00425 {
00426 template<class ContainerAllocator> struct IsMessage< ::nav_msgs::GetPlanResponse_<ContainerAllocator> > : public TrueType {};
00427 template<class ContainerAllocator> struct IsMessage< ::nav_msgs::GetPlanResponse_<ContainerAllocator> const> : public TrueType {};
00428 template<class ContainerAllocator>
00429 struct MD5Sum< ::nav_msgs::GetPlanResponse_<ContainerAllocator> > {
00430 static const char* value()
00431 {
00432 return "0002bc113c0259d71f6cf8cbc9430e18";
00433 }
00434
00435 static const char* value(const ::nav_msgs::GetPlanResponse_<ContainerAllocator> &) { return value(); }
00436 static const uint64_t static_value1 = 0x0002bc113c0259d7ULL;
00437 static const uint64_t static_value2 = 0x1f6cf8cbc9430e18ULL;
00438 };
00439
00440 template<class ContainerAllocator>
00441 struct DataType< ::nav_msgs::GetPlanResponse_<ContainerAllocator> > {
00442 static const char* value()
00443 {
00444 return "nav_msgs/GetPlanResponse";
00445 }
00446
00447 static const char* value(const ::nav_msgs::GetPlanResponse_<ContainerAllocator> &) { return value(); }
00448 };
00449
00450 template<class ContainerAllocator>
00451 struct Definition< ::nav_msgs::GetPlanResponse_<ContainerAllocator> > {
00452 static const char* value()
00453 {
00454 return "nav_msgs/Path plan\n\
00455 \n\
00456 \n\
00457 ================================================================================\n\
00458 MSG: nav_msgs/Path\n\
00459 #An array of poses that represents a Path for a robot to follow\n\
00460 Header header\n\
00461 geometry_msgs/PoseStamped[] poses\n\
00462 \n\
00463 ================================================================================\n\
00464 MSG: std_msgs/Header\n\
00465 # Standard metadata for higher-level stamped data types.\n\
00466 # This is generally used to communicate timestamped data \n\
00467 # in a particular coordinate frame.\n\
00468 # \n\
00469 # sequence ID: consecutively increasing ID \n\
00470 uint32 seq\n\
00471 #Two-integer timestamp that is expressed as:\n\
00472 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00473 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00474 # time-handling sugar is provided by the client library\n\
00475 time stamp\n\
00476 #Frame this data is associated with\n\
00477 # 0: no frame\n\
00478 # 1: global frame\n\
00479 string frame_id\n\
00480 \n\
00481 ================================================================================\n\
00482 MSG: geometry_msgs/PoseStamped\n\
00483 # A Pose with reference coordinate frame and timestamp\n\
00484 Header header\n\
00485 Pose pose\n\
00486 \n\
00487 ================================================================================\n\
00488 MSG: geometry_msgs/Pose\n\
00489 # A representation of pose in free space, composed of postion and orientation. \n\
00490 Point position\n\
00491 Quaternion orientation\n\
00492 \n\
00493 ================================================================================\n\
00494 MSG: geometry_msgs/Point\n\
00495 # This contains the position of a point in free space\n\
00496 float64 x\n\
00497 float64 y\n\
00498 float64 z\n\
00499 \n\
00500 ================================================================================\n\
00501 MSG: geometry_msgs/Quaternion\n\
00502 # This represents an orientation in free space in quaternion form.\n\
00503 \n\
00504 float64 x\n\
00505 float64 y\n\
00506 float64 z\n\
00507 float64 w\n\
00508 \n\
00509 ";
00510 }
00511
00512 static const char* value(const ::nav_msgs::GetPlanResponse_<ContainerAllocator> &) { return value(); }
00513 };
00514
00515 }
00516 }
00517
00518 namespace ros
00519 {
00520 namespace serialization
00521 {
00522
00523 template<class ContainerAllocator> struct Serializer< ::nav_msgs::GetPlanRequest_<ContainerAllocator> >
00524 {
00525 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00526 {
00527 stream.next(m.start);
00528 stream.next(m.goal);
00529 stream.next(m.tolerance);
00530 }
00531
00532 ROS_DECLARE_ALLINONE_SERIALIZER;
00533 };
00534 }
00535 }
00536
00537
00538 namespace ros
00539 {
00540 namespace serialization
00541 {
00542
00543 template<class ContainerAllocator> struct Serializer< ::nav_msgs::GetPlanResponse_<ContainerAllocator> >
00544 {
00545 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00546 {
00547 stream.next(m.plan);
00548 }
00549
00550 ROS_DECLARE_ALLINONE_SERIALIZER;
00551 };
00552 }
00553 }
00554
00555 namespace ros
00556 {
00557 namespace service_traits
00558 {
00559 template<>
00560 struct MD5Sum<nav_msgs::GetPlan> {
00561 static const char* value()
00562 {
00563 return "421c8ea4d21c6c9db7054b4bbdf1e024";
00564 }
00565
00566 static const char* value(const nav_msgs::GetPlan&) { return value(); }
00567 };
00568
00569 template<>
00570 struct DataType<nav_msgs::GetPlan> {
00571 static const char* value()
00572 {
00573 return "nav_msgs/GetPlan";
00574 }
00575
00576 static const char* value(const nav_msgs::GetPlan&) { return value(); }
00577 };
00578
00579 template<class ContainerAllocator>
00580 struct MD5Sum<nav_msgs::GetPlanRequest_<ContainerAllocator> > {
00581 static const char* value()
00582 {
00583 return "421c8ea4d21c6c9db7054b4bbdf1e024";
00584 }
00585
00586 static const char* value(const nav_msgs::GetPlanRequest_<ContainerAllocator> &) { return value(); }
00587 };
00588
00589 template<class ContainerAllocator>
00590 struct DataType<nav_msgs::GetPlanRequest_<ContainerAllocator> > {
00591 static const char* value()
00592 {
00593 return "nav_msgs/GetPlan";
00594 }
00595
00596 static const char* value(const nav_msgs::GetPlanRequest_<ContainerAllocator> &) { return value(); }
00597 };
00598
00599 template<class ContainerAllocator>
00600 struct MD5Sum<nav_msgs::GetPlanResponse_<ContainerAllocator> > {
00601 static const char* value()
00602 {
00603 return "421c8ea4d21c6c9db7054b4bbdf1e024";
00604 }
00605
00606 static const char* value(const nav_msgs::GetPlanResponse_<ContainerAllocator> &) { return value(); }
00607 };
00608
00609 template<class ContainerAllocator>
00610 struct DataType<nav_msgs::GetPlanResponse_<ContainerAllocator> > {
00611 static const char* value()
00612 {
00613 return "nav_msgs/GetPlan";
00614 }
00615
00616 static const char* value(const nav_msgs::GetPlanResponse_<ContainerAllocator> &) { return value(); }
00617 };
00618
00619 }
00620 }
00621
00622 #endif // NAV_MSGS_SERVICE_GETPLAN_H
00623