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