GetPath.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-fuerte-humanoid_walk/doc_stacks/2013-12-28_17-04-02.394386/humanoid_walk/walk_msgs/srv/GetPath.srv */
00002 #ifndef WALK_MSGS_SERVICE_GETPATH_H
00003 #define WALK_MSGS_SERVICE_GETPATH_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/Pose.h"
00020 #include "geometry_msgs/Pose.h"
00021 #include "geometry_msgs/Point.h"
00022 #include "geometry_msgs/Pose.h"
00023 #include "geometry_msgs/Pose.h"
00024 #include "geometry_msgs/Point.h"
00025 #include "walk_msgs/Footprint2d.h"
00026 
00027 
00028 #include "walk_msgs/WalkPath.h"
00029 
00030 namespace walk_msgs
00031 {
00032 template <class ContainerAllocator>
00033 struct GetPathRequest_ {
00034   typedef GetPathRequest_<ContainerAllocator> Type;
00035 
00036   GetPathRequest_()
00037   : initial_left_foot_position()
00038   , initial_right_foot_position()
00039   , initial_center_of_mass_position()
00040   , final_left_foot_position()
00041   , final_right_foot_position()
00042   , final_center_of_mass_position()
00043   , start_with_left_foot(false)
00044   , footprints()
00045   {
00046   }
00047 
00048   GetPathRequest_(const ContainerAllocator& _alloc)
00049   : initial_left_foot_position(_alloc)
00050   , initial_right_foot_position(_alloc)
00051   , initial_center_of_mass_position(_alloc)
00052   , final_left_foot_position(_alloc)
00053   , final_right_foot_position(_alloc)
00054   , final_center_of_mass_position(_alloc)
00055   , start_with_left_foot(false)
00056   , footprints(_alloc)
00057   {
00058   }
00059 
00060   typedef  ::geometry_msgs::Pose_<ContainerAllocator>  _initial_left_foot_position_type;
00061    ::geometry_msgs::Pose_<ContainerAllocator>  initial_left_foot_position;
00062 
00063   typedef  ::geometry_msgs::Pose_<ContainerAllocator>  _initial_right_foot_position_type;
00064    ::geometry_msgs::Pose_<ContainerAllocator>  initial_right_foot_position;
00065 
00066   typedef  ::geometry_msgs::Point_<ContainerAllocator>  _initial_center_of_mass_position_type;
00067    ::geometry_msgs::Point_<ContainerAllocator>  initial_center_of_mass_position;
00068 
00069   typedef  ::geometry_msgs::Pose_<ContainerAllocator>  _final_left_foot_position_type;
00070    ::geometry_msgs::Pose_<ContainerAllocator>  final_left_foot_position;
00071 
00072   typedef  ::geometry_msgs::Pose_<ContainerAllocator>  _final_right_foot_position_type;
00073    ::geometry_msgs::Pose_<ContainerAllocator>  final_right_foot_position;
00074 
00075   typedef  ::geometry_msgs::Point_<ContainerAllocator>  _final_center_of_mass_position_type;
00076    ::geometry_msgs::Point_<ContainerAllocator>  final_center_of_mass_position;
00077 
00078   typedef uint8_t _start_with_left_foot_type;
00079   uint8_t start_with_left_foot;
00080 
00081   typedef std::vector< ::walk_msgs::Footprint2d_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::walk_msgs::Footprint2d_<ContainerAllocator> >::other >  _footprints_type;
00082   std::vector< ::walk_msgs::Footprint2d_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::walk_msgs::Footprint2d_<ContainerAllocator> >::other >  footprints;
00083 
00084 
00085   typedef boost::shared_ptr< ::walk_msgs::GetPathRequest_<ContainerAllocator> > Ptr;
00086   typedef boost::shared_ptr< ::walk_msgs::GetPathRequest_<ContainerAllocator>  const> ConstPtr;
00087   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00088 }; // struct GetPathRequest
00089 typedef  ::walk_msgs::GetPathRequest_<std::allocator<void> > GetPathRequest;
00090 
00091 typedef boost::shared_ptr< ::walk_msgs::GetPathRequest> GetPathRequestPtr;
00092 typedef boost::shared_ptr< ::walk_msgs::GetPathRequest const> GetPathRequestConstPtr;
00093 
00094 
00095 template <class ContainerAllocator>
00096 struct GetPathResponse_ {
00097   typedef GetPathResponse_<ContainerAllocator> Type;
00098 
00099   GetPathResponse_()
00100   : path()
00101   {
00102   }
00103 
00104   GetPathResponse_(const ContainerAllocator& _alloc)
00105   : path(_alloc)
00106   {
00107   }
00108 
00109   typedef  ::walk_msgs::WalkPath_<ContainerAllocator>  _path_type;
00110    ::walk_msgs::WalkPath_<ContainerAllocator>  path;
00111 
00112 
00113   typedef boost::shared_ptr< ::walk_msgs::GetPathResponse_<ContainerAllocator> > Ptr;
00114   typedef boost::shared_ptr< ::walk_msgs::GetPathResponse_<ContainerAllocator>  const> ConstPtr;
00115   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00116 }; // struct GetPathResponse
00117 typedef  ::walk_msgs::GetPathResponse_<std::allocator<void> > GetPathResponse;
00118 
00119 typedef boost::shared_ptr< ::walk_msgs::GetPathResponse> GetPathResponsePtr;
00120 typedef boost::shared_ptr< ::walk_msgs::GetPathResponse const> GetPathResponseConstPtr;
00121 
00122 struct GetPath
00123 {
00124 
00125 typedef GetPathRequest Request;
00126 typedef GetPathResponse Response;
00127 Request request;
00128 Response response;
00129 
00130 typedef Request RequestType;
00131 typedef Response ResponseType;
00132 }; // struct GetPath
00133 } // namespace walk_msgs
00134 
00135 namespace ros
00136 {
00137 namespace message_traits
00138 {
00139 template<class ContainerAllocator> struct IsMessage< ::walk_msgs::GetPathRequest_<ContainerAllocator> > : public TrueType {};
00140 template<class ContainerAllocator> struct IsMessage< ::walk_msgs::GetPathRequest_<ContainerAllocator>  const> : public TrueType {};
00141 template<class ContainerAllocator>
00142 struct MD5Sum< ::walk_msgs::GetPathRequest_<ContainerAllocator> > {
00143   static const char* value() 
00144   {
00145     return "9325cbcfc330e3e7667ffad5cb6d4c50";
00146   }
00147 
00148   static const char* value(const  ::walk_msgs::GetPathRequest_<ContainerAllocator> &) { return value(); } 
00149   static const uint64_t static_value1 = 0x9325cbcfc330e3e7ULL;
00150   static const uint64_t static_value2 = 0x667ffad5cb6d4c50ULL;
00151 };
00152 
00153 template<class ContainerAllocator>
00154 struct DataType< ::walk_msgs::GetPathRequest_<ContainerAllocator> > {
00155   static const char* value() 
00156   {
00157     return "walk_msgs/GetPathRequest";
00158   }
00159 
00160   static const char* value(const  ::walk_msgs::GetPathRequest_<ContainerAllocator> &) { return value(); } 
00161 };
00162 
00163 template<class ContainerAllocator>
00164 struct Definition< ::walk_msgs::GetPathRequest_<ContainerAllocator> > {
00165   static const char* value() 
00166   {
00167     return "geometry_msgs/Pose initial_left_foot_position\n\
00168 geometry_msgs/Pose initial_right_foot_position\n\
00169 geometry_msgs/Point initial_center_of_mass_position\n\
00170 \n\
00171 geometry_msgs/Pose final_left_foot_position\n\
00172 geometry_msgs/Pose final_right_foot_position\n\
00173 geometry_msgs/Point final_center_of_mass_position\n\
00174 \n\
00175 bool start_with_left_foot\n\
00176 \n\
00177 walk_msgs/Footprint2d[] footprints\n\
00178 \n\
00179 ================================================================================\n\
00180 MSG: geometry_msgs/Pose\n\
00181 # A representation of pose in free space, composed of postion and orientation. \n\
00182 Point position\n\
00183 Quaternion orientation\n\
00184 \n\
00185 ================================================================================\n\
00186 MSG: geometry_msgs/Point\n\
00187 # This contains the position of a point in free space\n\
00188 float64 x\n\
00189 float64 y\n\
00190 float64 z\n\
00191 \n\
00192 ================================================================================\n\
00193 MSG: geometry_msgs/Quaternion\n\
00194 # This represents an orientation in free space in quaternion form.\n\
00195 \n\
00196 float64 x\n\
00197 float64 y\n\
00198 float64 z\n\
00199 float64 w\n\
00200 \n\
00201 ================================================================================\n\
00202 MSG: walk_msgs/Footprint2d\n\
00203 time beginTime\n\
00204 duration duration\n\
00205 float64 x\n\
00206 float64 y\n\
00207 float64 theta\n\
00208 \n\
00209 ";
00210   }
00211 
00212   static const char* value(const  ::walk_msgs::GetPathRequest_<ContainerAllocator> &) { return value(); } 
00213 };
00214 
00215 } // namespace message_traits
00216 } // namespace ros
00217 
00218 
00219 namespace ros
00220 {
00221 namespace message_traits
00222 {
00223 template<class ContainerAllocator> struct IsMessage< ::walk_msgs::GetPathResponse_<ContainerAllocator> > : public TrueType {};
00224 template<class ContainerAllocator> struct IsMessage< ::walk_msgs::GetPathResponse_<ContainerAllocator>  const> : public TrueType {};
00225 template<class ContainerAllocator>
00226 struct MD5Sum< ::walk_msgs::GetPathResponse_<ContainerAllocator> > {
00227   static const char* value() 
00228   {
00229     return "76d3891998acfa84511d5b8b9e0f9b97";
00230   }
00231 
00232   static const char* value(const  ::walk_msgs::GetPathResponse_<ContainerAllocator> &) { return value(); } 
00233   static const uint64_t static_value1 = 0x76d3891998acfa84ULL;
00234   static const uint64_t static_value2 = 0x511d5b8b9e0f9b97ULL;
00235 };
00236 
00237 template<class ContainerAllocator>
00238 struct DataType< ::walk_msgs::GetPathResponse_<ContainerAllocator> > {
00239   static const char* value() 
00240   {
00241     return "walk_msgs/GetPathResponse";
00242   }
00243 
00244   static const char* value(const  ::walk_msgs::GetPathResponse_<ContainerAllocator> &) { return value(); } 
00245 };
00246 
00247 template<class ContainerAllocator>
00248 struct Definition< ::walk_msgs::GetPathResponse_<ContainerAllocator> > {
00249   static const char* value() 
00250   {
00251     return "walk_msgs/WalkPath path\n\
00252 \n\
00253 \n\
00254 ================================================================================\n\
00255 MSG: walk_msgs/WalkPath\n\
00256 nav_msgs/Path left_foot\n\
00257 nav_msgs/Path right_foot\n\
00258 walk_msgs/PathPoint3d center_of_mass\n\
00259 walk_msgs/PathPoint2d zmp\n\
00260 \n\
00261 ================================================================================\n\
00262 MSG: nav_msgs/Path\n\
00263 #An array of poses that represents a Path for a robot to follow\n\
00264 Header header\n\
00265 geometry_msgs/PoseStamped[] poses\n\
00266 \n\
00267 ================================================================================\n\
00268 MSG: std_msgs/Header\n\
00269 # Standard metadata for higher-level stamped data types.\n\
00270 # This is generally used to communicate timestamped data \n\
00271 # in a particular coordinate frame.\n\
00272 # \n\
00273 # sequence ID: consecutively increasing ID \n\
00274 uint32 seq\n\
00275 #Two-integer timestamp that is expressed as:\n\
00276 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00277 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00278 # time-handling sugar is provided by the client library\n\
00279 time stamp\n\
00280 #Frame this data is associated with\n\
00281 # 0: no frame\n\
00282 # 1: global frame\n\
00283 string frame_id\n\
00284 \n\
00285 ================================================================================\n\
00286 MSG: geometry_msgs/PoseStamped\n\
00287 # A Pose with reference coordinate frame and timestamp\n\
00288 Header header\n\
00289 Pose pose\n\
00290 \n\
00291 ================================================================================\n\
00292 MSG: geometry_msgs/Pose\n\
00293 # A representation of pose in free space, composed of postion and orientation. \n\
00294 Point position\n\
00295 Quaternion orientation\n\
00296 \n\
00297 ================================================================================\n\
00298 MSG: geometry_msgs/Point\n\
00299 # This contains the position of a point in free space\n\
00300 float64 x\n\
00301 float64 y\n\
00302 float64 z\n\
00303 \n\
00304 ================================================================================\n\
00305 MSG: geometry_msgs/Quaternion\n\
00306 # This represents an orientation in free space in quaternion form.\n\
00307 \n\
00308 float64 x\n\
00309 float64 y\n\
00310 float64 z\n\
00311 float64 w\n\
00312 \n\
00313 ================================================================================\n\
00314 MSG: walk_msgs/PathPoint3d\n\
00315 Header header\n\
00316 geometry_msgs/PointStamped[] points\n\
00317 \n\
00318 ================================================================================\n\
00319 MSG: geometry_msgs/PointStamped\n\
00320 # This represents a Point with reference coordinate frame and timestamp\n\
00321 Header header\n\
00322 Point point\n\
00323 \n\
00324 ================================================================================\n\
00325 MSG: walk_msgs/PathPoint2d\n\
00326 Header header\n\
00327 walk_msgs/Point2dStamped[] points\n\
00328 \n\
00329 ================================================================================\n\
00330 MSG: walk_msgs/Point2dStamped\n\
00331 Header header\n\
00332 Point2d point\n\
00333 \n\
00334 ================================================================================\n\
00335 MSG: walk_msgs/Point2d\n\
00336 float64 x\n\
00337 float64 y\n\
00338 \n\
00339 ";
00340   }
00341 
00342   static const char* value(const  ::walk_msgs::GetPathResponse_<ContainerAllocator> &) { return value(); } 
00343 };
00344 
00345 } // namespace message_traits
00346 } // namespace ros
00347 
00348 namespace ros
00349 {
00350 namespace serialization
00351 {
00352 
00353 template<class ContainerAllocator> struct Serializer< ::walk_msgs::GetPathRequest_<ContainerAllocator> >
00354 {
00355   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00356   {
00357     stream.next(m.initial_left_foot_position);
00358     stream.next(m.initial_right_foot_position);
00359     stream.next(m.initial_center_of_mass_position);
00360     stream.next(m.final_left_foot_position);
00361     stream.next(m.final_right_foot_position);
00362     stream.next(m.final_center_of_mass_position);
00363     stream.next(m.start_with_left_foot);
00364     stream.next(m.footprints);
00365   }
00366 
00367   ROS_DECLARE_ALLINONE_SERIALIZER;
00368 }; // struct GetPathRequest_
00369 } // namespace serialization
00370 } // namespace ros
00371 
00372 
00373 namespace ros
00374 {
00375 namespace serialization
00376 {
00377 
00378 template<class ContainerAllocator> struct Serializer< ::walk_msgs::GetPathResponse_<ContainerAllocator> >
00379 {
00380   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00381   {
00382     stream.next(m.path);
00383   }
00384 
00385   ROS_DECLARE_ALLINONE_SERIALIZER;
00386 }; // struct GetPathResponse_
00387 } // namespace serialization
00388 } // namespace ros
00389 
00390 namespace ros
00391 {
00392 namespace service_traits
00393 {
00394 template<>
00395 struct MD5Sum<walk_msgs::GetPath> {
00396   static const char* value() 
00397   {
00398     return "2b6fd7b841642a7520d3b2fd459370d2";
00399   }
00400 
00401   static const char* value(const walk_msgs::GetPath&) { return value(); } 
00402 };
00403 
00404 template<>
00405 struct DataType<walk_msgs::GetPath> {
00406   static const char* value() 
00407   {
00408     return "walk_msgs/GetPath";
00409   }
00410 
00411   static const char* value(const walk_msgs::GetPath&) { return value(); } 
00412 };
00413 
00414 template<class ContainerAllocator>
00415 struct MD5Sum<walk_msgs::GetPathRequest_<ContainerAllocator> > {
00416   static const char* value() 
00417   {
00418     return "2b6fd7b841642a7520d3b2fd459370d2";
00419   }
00420 
00421   static const char* value(const walk_msgs::GetPathRequest_<ContainerAllocator> &) { return value(); } 
00422 };
00423 
00424 template<class ContainerAllocator>
00425 struct DataType<walk_msgs::GetPathRequest_<ContainerAllocator> > {
00426   static const char* value() 
00427   {
00428     return "walk_msgs/GetPath";
00429   }
00430 
00431   static const char* value(const walk_msgs::GetPathRequest_<ContainerAllocator> &) { return value(); } 
00432 };
00433 
00434 template<class ContainerAllocator>
00435 struct MD5Sum<walk_msgs::GetPathResponse_<ContainerAllocator> > {
00436   static const char* value() 
00437   {
00438     return "2b6fd7b841642a7520d3b2fd459370d2";
00439   }
00440 
00441   static const char* value(const walk_msgs::GetPathResponse_<ContainerAllocator> &) { return value(); } 
00442 };
00443 
00444 template<class ContainerAllocator>
00445 struct DataType<walk_msgs::GetPathResponse_<ContainerAllocator> > {
00446   static const char* value() 
00447   {
00448     return "walk_msgs/GetPath";
00449   }
00450 
00451   static const char* value(const walk_msgs::GetPathResponse_<ContainerAllocator> &) { return value(); } 
00452 };
00453 
00454 } // namespace service_traits
00455 } // namespace ros
00456 
00457 #endif // WALK_MSGS_SERVICE_GETPATH_H
00458 


walk_msgs
Author(s): Thomas Moulard
autogenerated on Sat Dec 28 2013 17:05:25