Go to the documentation of this file.00001
00002 #ifndef NAVFN_SERVICE_MAKENAVPLAN_H
00003 #define NAVFN_SERVICE_MAKENAVPLAN_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 "geometry_msgs/PoseStamped.h"
00024
00025 namespace navfn
00026 {
00027 template <class ContainerAllocator>
00028 struct MakeNavPlanRequest_ {
00029 typedef MakeNavPlanRequest_<ContainerAllocator> Type;
00030
00031 MakeNavPlanRequest_()
00032 : start()
00033 , goal()
00034 {
00035 }
00036
00037 MakeNavPlanRequest_(const ContainerAllocator& _alloc)
00038 : start(_alloc)
00039 , goal(_alloc)
00040 {
00041 }
00042
00043 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _start_type;
00044 ::geometry_msgs::PoseStamped_<ContainerAllocator> start;
00045
00046 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _goal_type;
00047 ::geometry_msgs::PoseStamped_<ContainerAllocator> goal;
00048
00049
00050 typedef boost::shared_ptr< ::navfn::MakeNavPlanRequest_<ContainerAllocator> > Ptr;
00051 typedef boost::shared_ptr< ::navfn::MakeNavPlanRequest_<ContainerAllocator> const> ConstPtr;
00052 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00053 };
00054 typedef ::navfn::MakeNavPlanRequest_<std::allocator<void> > MakeNavPlanRequest;
00055
00056 typedef boost::shared_ptr< ::navfn::MakeNavPlanRequest> MakeNavPlanRequestPtr;
00057 typedef boost::shared_ptr< ::navfn::MakeNavPlanRequest const> MakeNavPlanRequestConstPtr;
00058
00059
00060 template <class ContainerAllocator>
00061 struct MakeNavPlanResponse_ {
00062 typedef MakeNavPlanResponse_<ContainerAllocator> Type;
00063
00064 MakeNavPlanResponse_()
00065 : plan_found(0)
00066 , error_message()
00067 , path()
00068 {
00069 }
00070
00071 MakeNavPlanResponse_(const ContainerAllocator& _alloc)
00072 : plan_found(0)
00073 , error_message(_alloc)
00074 , path(_alloc)
00075 {
00076 }
00077
00078 typedef uint8_t _plan_found_type;
00079 uint8_t plan_found;
00080
00081 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _error_message_type;
00082 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > error_message;
00083
00084 typedef std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other > _path_type;
00085 std::vector< ::geometry_msgs::PoseStamped_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::other > path;
00086
00087
00088 typedef boost::shared_ptr< ::navfn::MakeNavPlanResponse_<ContainerAllocator> > Ptr;
00089 typedef boost::shared_ptr< ::navfn::MakeNavPlanResponse_<ContainerAllocator> const> ConstPtr;
00090 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00091 };
00092 typedef ::navfn::MakeNavPlanResponse_<std::allocator<void> > MakeNavPlanResponse;
00093
00094 typedef boost::shared_ptr< ::navfn::MakeNavPlanResponse> MakeNavPlanResponsePtr;
00095 typedef boost::shared_ptr< ::navfn::MakeNavPlanResponse const> MakeNavPlanResponseConstPtr;
00096
00097 struct MakeNavPlan
00098 {
00099
00100 typedef MakeNavPlanRequest Request;
00101 typedef MakeNavPlanResponse Response;
00102 Request request;
00103 Response response;
00104
00105 typedef Request RequestType;
00106 typedef Response ResponseType;
00107 };
00108 }
00109
00110 namespace ros
00111 {
00112 namespace message_traits
00113 {
00114 template<class ContainerAllocator> struct IsMessage< ::navfn::MakeNavPlanRequest_<ContainerAllocator> > : public TrueType {};
00115 template<class ContainerAllocator> struct IsMessage< ::navfn::MakeNavPlanRequest_<ContainerAllocator> const> : public TrueType {};
00116 template<class ContainerAllocator>
00117 struct MD5Sum< ::navfn::MakeNavPlanRequest_<ContainerAllocator> > {
00118 static const char* value()
00119 {
00120 return "2fe3126bd5b2d56edd5005220333d4fd";
00121 }
00122
00123 static const char* value(const ::navfn::MakeNavPlanRequest_<ContainerAllocator> &) { return value(); }
00124 static const uint64_t static_value1 = 0x2fe3126bd5b2d56eULL;
00125 static const uint64_t static_value2 = 0xdd5005220333d4fdULL;
00126 };
00127
00128 template<class ContainerAllocator>
00129 struct DataType< ::navfn::MakeNavPlanRequest_<ContainerAllocator> > {
00130 static const char* value()
00131 {
00132 return "navfn/MakeNavPlanRequest";
00133 }
00134
00135 static const char* value(const ::navfn::MakeNavPlanRequest_<ContainerAllocator> &) { return value(); }
00136 };
00137
00138 template<class ContainerAllocator>
00139 struct Definition< ::navfn::MakeNavPlanRequest_<ContainerAllocator> > {
00140 static const char* value()
00141 {
00142 return "geometry_msgs/PoseStamped start\n\
00143 geometry_msgs/PoseStamped goal\n\
00144 \n\
00145 ================================================================================\n\
00146 MSG: geometry_msgs/PoseStamped\n\
00147 # A Pose with reference coordinate frame and timestamp\n\
00148 Header header\n\
00149 Pose pose\n\
00150 \n\
00151 ================================================================================\n\
00152 MSG: std_msgs/Header\n\
00153 # Standard metadata for higher-level stamped data types.\n\
00154 # This is generally used to communicate timestamped data \n\
00155 # in a particular coordinate frame.\n\
00156 # \n\
00157 # sequence ID: consecutively increasing ID \n\
00158 uint32 seq\n\
00159 #Two-integer timestamp that is expressed as:\n\
00160 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00161 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00162 # time-handling sugar is provided by the client library\n\
00163 time stamp\n\
00164 #Frame this data is associated with\n\
00165 # 0: no frame\n\
00166 # 1: global frame\n\
00167 string frame_id\n\
00168 \n\
00169 ================================================================================\n\
00170 MSG: geometry_msgs/Pose\n\
00171 # A representation of pose in free space, composed of postion and orientation. \n\
00172 Point position\n\
00173 Quaternion orientation\n\
00174 \n\
00175 ================================================================================\n\
00176 MSG: geometry_msgs/Point\n\
00177 # This contains the position of a point in free space\n\
00178 float64 x\n\
00179 float64 y\n\
00180 float64 z\n\
00181 \n\
00182 ================================================================================\n\
00183 MSG: geometry_msgs/Quaternion\n\
00184 # This represents an orientation in free space in quaternion form.\n\
00185 \n\
00186 float64 x\n\
00187 float64 y\n\
00188 float64 z\n\
00189 float64 w\n\
00190 \n\
00191 ";
00192 }
00193
00194 static const char* value(const ::navfn::MakeNavPlanRequest_<ContainerAllocator> &) { return value(); }
00195 };
00196
00197 }
00198 }
00199
00200
00201 namespace ros
00202 {
00203 namespace message_traits
00204 {
00205 template<class ContainerAllocator> struct IsMessage< ::navfn::MakeNavPlanResponse_<ContainerAllocator> > : public TrueType {};
00206 template<class ContainerAllocator> struct IsMessage< ::navfn::MakeNavPlanResponse_<ContainerAllocator> const> : public TrueType {};
00207 template<class ContainerAllocator>
00208 struct MD5Sum< ::navfn::MakeNavPlanResponse_<ContainerAllocator> > {
00209 static const char* value()
00210 {
00211 return "8b8ed7edf1b237dc9ddda8c8ffed5d3a";
00212 }
00213
00214 static const char* value(const ::navfn::MakeNavPlanResponse_<ContainerAllocator> &) { return value(); }
00215 static const uint64_t static_value1 = 0x8b8ed7edf1b237dcULL;
00216 static const uint64_t static_value2 = 0x9ddda8c8ffed5d3aULL;
00217 };
00218
00219 template<class ContainerAllocator>
00220 struct DataType< ::navfn::MakeNavPlanResponse_<ContainerAllocator> > {
00221 static const char* value()
00222 {
00223 return "navfn/MakeNavPlanResponse";
00224 }
00225
00226 static const char* value(const ::navfn::MakeNavPlanResponse_<ContainerAllocator> &) { return value(); }
00227 };
00228
00229 template<class ContainerAllocator>
00230 struct Definition< ::navfn::MakeNavPlanResponse_<ContainerAllocator> > {
00231 static const char* value()
00232 {
00233 return "\n\
00234 uint8 plan_found\n\
00235 string error_message\n\
00236 \n\
00237 \n\
00238 geometry_msgs/PoseStamped[] path\n\
00239 \n\
00240 \n\
00241 ================================================================================\n\
00242 MSG: geometry_msgs/PoseStamped\n\
00243 # A Pose with reference coordinate frame and timestamp\n\
00244 Header header\n\
00245 Pose pose\n\
00246 \n\
00247 ================================================================================\n\
00248 MSG: std_msgs/Header\n\
00249 # Standard metadata for higher-level stamped data types.\n\
00250 # This is generally used to communicate timestamped data \n\
00251 # in a particular coordinate frame.\n\
00252 # \n\
00253 # sequence ID: consecutively increasing ID \n\
00254 uint32 seq\n\
00255 #Two-integer timestamp that is expressed as:\n\
00256 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00257 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00258 # time-handling sugar is provided by the client library\n\
00259 time stamp\n\
00260 #Frame this data is associated with\n\
00261 # 0: no frame\n\
00262 # 1: global frame\n\
00263 string frame_id\n\
00264 \n\
00265 ================================================================================\n\
00266 MSG: geometry_msgs/Pose\n\
00267 # A representation of pose in free space, composed of postion and orientation. \n\
00268 Point position\n\
00269 Quaternion orientation\n\
00270 \n\
00271 ================================================================================\n\
00272 MSG: geometry_msgs/Point\n\
00273 # This contains the position of a point in free space\n\
00274 float64 x\n\
00275 float64 y\n\
00276 float64 z\n\
00277 \n\
00278 ================================================================================\n\
00279 MSG: geometry_msgs/Quaternion\n\
00280 # This represents an orientation in free space in quaternion form.\n\
00281 \n\
00282 float64 x\n\
00283 float64 y\n\
00284 float64 z\n\
00285 float64 w\n\
00286 \n\
00287 ";
00288 }
00289
00290 static const char* value(const ::navfn::MakeNavPlanResponse_<ContainerAllocator> &) { return value(); }
00291 };
00292
00293 }
00294 }
00295
00296 namespace ros
00297 {
00298 namespace serialization
00299 {
00300
00301 template<class ContainerAllocator> struct Serializer< ::navfn::MakeNavPlanRequest_<ContainerAllocator> >
00302 {
00303 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00304 {
00305 stream.next(m.start);
00306 stream.next(m.goal);
00307 }
00308
00309 ROS_DECLARE_ALLINONE_SERIALIZER;
00310 };
00311 }
00312 }
00313
00314
00315 namespace ros
00316 {
00317 namespace serialization
00318 {
00319
00320 template<class ContainerAllocator> struct Serializer< ::navfn::MakeNavPlanResponse_<ContainerAllocator> >
00321 {
00322 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00323 {
00324 stream.next(m.plan_found);
00325 stream.next(m.error_message);
00326 stream.next(m.path);
00327 }
00328
00329 ROS_DECLARE_ALLINONE_SERIALIZER;
00330 };
00331 }
00332 }
00333
00334 namespace ros
00335 {
00336 namespace service_traits
00337 {
00338 template<>
00339 struct MD5Sum<navfn::MakeNavPlan> {
00340 static const char* value()
00341 {
00342 return "8ffef29bc8b086289124c16a8daa989d";
00343 }
00344
00345 static const char* value(const navfn::MakeNavPlan&) { return value(); }
00346 };
00347
00348 template<>
00349 struct DataType<navfn::MakeNavPlan> {
00350 static const char* value()
00351 {
00352 return "navfn/MakeNavPlan";
00353 }
00354
00355 static const char* value(const navfn::MakeNavPlan&) { return value(); }
00356 };
00357
00358 template<class ContainerAllocator>
00359 struct MD5Sum<navfn::MakeNavPlanRequest_<ContainerAllocator> > {
00360 static const char* value()
00361 {
00362 return "8ffef29bc8b086289124c16a8daa989d";
00363 }
00364
00365 static const char* value(const navfn::MakeNavPlanRequest_<ContainerAllocator> &) { return value(); }
00366 };
00367
00368 template<class ContainerAllocator>
00369 struct DataType<navfn::MakeNavPlanRequest_<ContainerAllocator> > {
00370 static const char* value()
00371 {
00372 return "navfn/MakeNavPlan";
00373 }
00374
00375 static const char* value(const navfn::MakeNavPlanRequest_<ContainerAllocator> &) { return value(); }
00376 };
00377
00378 template<class ContainerAllocator>
00379 struct MD5Sum<navfn::MakeNavPlanResponse_<ContainerAllocator> > {
00380 static const char* value()
00381 {
00382 return "8ffef29bc8b086289124c16a8daa989d";
00383 }
00384
00385 static const char* value(const navfn::MakeNavPlanResponse_<ContainerAllocator> &) { return value(); }
00386 };
00387
00388 template<class ContainerAllocator>
00389 struct DataType<navfn::MakeNavPlanResponse_<ContainerAllocator> > {
00390 static const char* value()
00391 {
00392 return "navfn/MakeNavPlan";
00393 }
00394
00395 static const char* value(const navfn::MakeNavPlanResponse_<ContainerAllocator> &) { return value(); }
00396 };
00397
00398 }
00399 }
00400
00401 #endif // NAVFN_SERVICE_MAKENAVPLAN_H
00402