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/halfsteps_pattern_generator/srv/GetPath.srv */
00002 #ifndef HALFSTEPS_PATTERN_GENERATOR_SERVICE_GETPATH_H
00003 #define HALFSTEPS_PATTERN_GENERATOR_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 "halfsteps_pattern_generator/Footprint.h"
00026 
00027 
00028 #include "walk_msgs/WalkPath.h"
00029 
00030 namespace halfsteps_pattern_generator
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< ::halfsteps_pattern_generator::Footprint_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::halfsteps_pattern_generator::Footprint_<ContainerAllocator> >::other >  _footprints_type;
00082   std::vector< ::halfsteps_pattern_generator::Footprint_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::halfsteps_pattern_generator::Footprint_<ContainerAllocator> >::other >  footprints;
00083 
00084 
00085   typedef boost::shared_ptr< ::halfsteps_pattern_generator::GetPathRequest_<ContainerAllocator> > Ptr;
00086   typedef boost::shared_ptr< ::halfsteps_pattern_generator::GetPathRequest_<ContainerAllocator>  const> ConstPtr;
00087   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00088 }; // struct GetPathRequest
00089 typedef  ::halfsteps_pattern_generator::GetPathRequest_<std::allocator<void> > GetPathRequest;
00090 
00091 typedef boost::shared_ptr< ::halfsteps_pattern_generator::GetPathRequest> GetPathRequestPtr;
00092 typedef boost::shared_ptr< ::halfsteps_pattern_generator::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< ::halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator> > Ptr;
00114   typedef boost::shared_ptr< ::halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator>  const> ConstPtr;
00115   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00116 }; // struct GetPathResponse
00117 typedef  ::halfsteps_pattern_generator::GetPathResponse_<std::allocator<void> > GetPathResponse;
00118 
00119 typedef boost::shared_ptr< ::halfsteps_pattern_generator::GetPathResponse> GetPathResponsePtr;
00120 typedef boost::shared_ptr< ::halfsteps_pattern_generator::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 halfsteps_pattern_generator
00134 
00135 namespace ros
00136 {
00137 namespace message_traits
00138 {
00139 template<class ContainerAllocator> struct IsMessage< ::halfsteps_pattern_generator::GetPathRequest_<ContainerAllocator> > : public TrueType {};
00140 template<class ContainerAllocator> struct IsMessage< ::halfsteps_pattern_generator::GetPathRequest_<ContainerAllocator>  const> : public TrueType {};
00141 template<class ContainerAllocator>
00142 struct MD5Sum< ::halfsteps_pattern_generator::GetPathRequest_<ContainerAllocator> > {
00143   static const char* value() 
00144   {
00145     return "e063e957046b30786d0c14db34db37f1";
00146   }
00147 
00148   static const char* value(const  ::halfsteps_pattern_generator::GetPathRequest_<ContainerAllocator> &) { return value(); } 
00149   static const uint64_t static_value1 = 0xe063e957046b3078ULL;
00150   static const uint64_t static_value2 = 0x6d0c14db34db37f1ULL;
00151 };
00152 
00153 template<class ContainerAllocator>
00154 struct DataType< ::halfsteps_pattern_generator::GetPathRequest_<ContainerAllocator> > {
00155   static const char* value() 
00156   {
00157     return "halfsteps_pattern_generator/GetPathRequest";
00158   }
00159 
00160   static const char* value(const  ::halfsteps_pattern_generator::GetPathRequest_<ContainerAllocator> &) { return value(); } 
00161 };
00162 
00163 template<class ContainerAllocator>
00164 struct Definition< ::halfsteps_pattern_generator::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 halfsteps_pattern_generator/Footprint[] 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: halfsteps_pattern_generator/Footprint\n\
00203 walk_msgs/Footprint2d footprint\n\
00204 float64 slideUp\n\
00205 float64 slideDown\n\
00206 float64 horizontalDistance\n\
00207 float64 stepHeight\n\
00208 \n\
00209 ================================================================================\n\
00210 MSG: walk_msgs/Footprint2d\n\
00211 time beginTime\n\
00212 duration duration\n\
00213 float64 x\n\
00214 float64 y\n\
00215 float64 theta\n\
00216 \n\
00217 ";
00218   }
00219 
00220   static const char* value(const  ::halfsteps_pattern_generator::GetPathRequest_<ContainerAllocator> &) { return value(); } 
00221 };
00222 
00223 } // namespace message_traits
00224 } // namespace ros
00225 
00226 
00227 namespace ros
00228 {
00229 namespace message_traits
00230 {
00231 template<class ContainerAllocator> struct IsMessage< ::halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator> > : public TrueType {};
00232 template<class ContainerAllocator> struct IsMessage< ::halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator>  const> : public TrueType {};
00233 template<class ContainerAllocator>
00234 struct MD5Sum< ::halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator> > {
00235   static const char* value() 
00236   {
00237     return "76d3891998acfa84511d5b8b9e0f9b97";
00238   }
00239 
00240   static const char* value(const  ::halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator> &) { return value(); } 
00241   static const uint64_t static_value1 = 0x76d3891998acfa84ULL;
00242   static const uint64_t static_value2 = 0x511d5b8b9e0f9b97ULL;
00243 };
00244 
00245 template<class ContainerAllocator>
00246 struct DataType< ::halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator> > {
00247   static const char* value() 
00248   {
00249     return "halfsteps_pattern_generator/GetPathResponse";
00250   }
00251 
00252   static const char* value(const  ::halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator> &) { return value(); } 
00253 };
00254 
00255 template<class ContainerAllocator>
00256 struct Definition< ::halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator> > {
00257   static const char* value() 
00258   {
00259     return "walk_msgs/WalkPath path\n\
00260 \n\
00261 \n\
00262 ================================================================================\n\
00263 MSG: walk_msgs/WalkPath\n\
00264 nav_msgs/Path left_foot\n\
00265 nav_msgs/Path right_foot\n\
00266 walk_msgs/PathPoint3d center_of_mass\n\
00267 walk_msgs/PathPoint2d zmp\n\
00268 \n\
00269 ================================================================================\n\
00270 MSG: nav_msgs/Path\n\
00271 #An array of poses that represents a Path for a robot to follow\n\
00272 Header header\n\
00273 geometry_msgs/PoseStamped[] poses\n\
00274 \n\
00275 ================================================================================\n\
00276 MSG: std_msgs/Header\n\
00277 # Standard metadata for higher-level stamped data types.\n\
00278 # This is generally used to communicate timestamped data \n\
00279 # in a particular coordinate frame.\n\
00280 # \n\
00281 # sequence ID: consecutively increasing ID \n\
00282 uint32 seq\n\
00283 #Two-integer timestamp that is expressed as:\n\
00284 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00285 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00286 # time-handling sugar is provided by the client library\n\
00287 time stamp\n\
00288 #Frame this data is associated with\n\
00289 # 0: no frame\n\
00290 # 1: global frame\n\
00291 string frame_id\n\
00292 \n\
00293 ================================================================================\n\
00294 MSG: geometry_msgs/PoseStamped\n\
00295 # A Pose with reference coordinate frame and timestamp\n\
00296 Header header\n\
00297 Pose pose\n\
00298 \n\
00299 ================================================================================\n\
00300 MSG: geometry_msgs/Pose\n\
00301 # A representation of pose in free space, composed of postion and orientation. \n\
00302 Point position\n\
00303 Quaternion orientation\n\
00304 \n\
00305 ================================================================================\n\
00306 MSG: geometry_msgs/Point\n\
00307 # This contains the position of a point in free space\n\
00308 float64 x\n\
00309 float64 y\n\
00310 float64 z\n\
00311 \n\
00312 ================================================================================\n\
00313 MSG: geometry_msgs/Quaternion\n\
00314 # This represents an orientation in free space in quaternion form.\n\
00315 \n\
00316 float64 x\n\
00317 float64 y\n\
00318 float64 z\n\
00319 float64 w\n\
00320 \n\
00321 ================================================================================\n\
00322 MSG: walk_msgs/PathPoint3d\n\
00323 Header header\n\
00324 geometry_msgs/PointStamped[] points\n\
00325 \n\
00326 ================================================================================\n\
00327 MSG: geometry_msgs/PointStamped\n\
00328 # This represents a Point with reference coordinate frame and timestamp\n\
00329 Header header\n\
00330 Point point\n\
00331 \n\
00332 ================================================================================\n\
00333 MSG: walk_msgs/PathPoint2d\n\
00334 Header header\n\
00335 walk_msgs/Point2dStamped[] points\n\
00336 \n\
00337 ================================================================================\n\
00338 MSG: walk_msgs/Point2dStamped\n\
00339 Header header\n\
00340 Point2d point\n\
00341 \n\
00342 ================================================================================\n\
00343 MSG: walk_msgs/Point2d\n\
00344 float64 x\n\
00345 float64 y\n\
00346 \n\
00347 ";
00348   }
00349 
00350   static const char* value(const  ::halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator> &) { return value(); } 
00351 };
00352 
00353 } // namespace message_traits
00354 } // namespace ros
00355 
00356 namespace ros
00357 {
00358 namespace serialization
00359 {
00360 
00361 template<class ContainerAllocator> struct Serializer< ::halfsteps_pattern_generator::GetPathRequest_<ContainerAllocator> >
00362 {
00363   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00364   {
00365     stream.next(m.initial_left_foot_position);
00366     stream.next(m.initial_right_foot_position);
00367     stream.next(m.initial_center_of_mass_position);
00368     stream.next(m.final_left_foot_position);
00369     stream.next(m.final_right_foot_position);
00370     stream.next(m.final_center_of_mass_position);
00371     stream.next(m.start_with_left_foot);
00372     stream.next(m.footprints);
00373   }
00374 
00375   ROS_DECLARE_ALLINONE_SERIALIZER;
00376 }; // struct GetPathRequest_
00377 } // namespace serialization
00378 } // namespace ros
00379 
00380 
00381 namespace ros
00382 {
00383 namespace serialization
00384 {
00385 
00386 template<class ContainerAllocator> struct Serializer< ::halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator> >
00387 {
00388   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00389   {
00390     stream.next(m.path);
00391   }
00392 
00393   ROS_DECLARE_ALLINONE_SERIALIZER;
00394 }; // struct GetPathResponse_
00395 } // namespace serialization
00396 } // namespace ros
00397 
00398 namespace ros
00399 {
00400 namespace service_traits
00401 {
00402 template<>
00403 struct MD5Sum<halfsteps_pattern_generator::GetPath> {
00404   static const char* value() 
00405   {
00406     return "52f659c3ddcbd1a61d82d7784cec1a56";
00407   }
00408 
00409   static const char* value(const halfsteps_pattern_generator::GetPath&) { return value(); } 
00410 };
00411 
00412 template<>
00413 struct DataType<halfsteps_pattern_generator::GetPath> {
00414   static const char* value() 
00415   {
00416     return "halfsteps_pattern_generator/GetPath";
00417   }
00418 
00419   static const char* value(const halfsteps_pattern_generator::GetPath&) { return value(); } 
00420 };
00421 
00422 template<class ContainerAllocator>
00423 struct MD5Sum<halfsteps_pattern_generator::GetPathRequest_<ContainerAllocator> > {
00424   static const char* value() 
00425   {
00426     return "52f659c3ddcbd1a61d82d7784cec1a56";
00427   }
00428 
00429   static const char* value(const halfsteps_pattern_generator::GetPathRequest_<ContainerAllocator> &) { return value(); } 
00430 };
00431 
00432 template<class ContainerAllocator>
00433 struct DataType<halfsteps_pattern_generator::GetPathRequest_<ContainerAllocator> > {
00434   static const char* value() 
00435   {
00436     return "halfsteps_pattern_generator/GetPath";
00437   }
00438 
00439   static const char* value(const halfsteps_pattern_generator::GetPathRequest_<ContainerAllocator> &) { return value(); } 
00440 };
00441 
00442 template<class ContainerAllocator>
00443 struct MD5Sum<halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator> > {
00444   static const char* value() 
00445   {
00446     return "52f659c3ddcbd1a61d82d7784cec1a56";
00447   }
00448 
00449   static const char* value(const halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator> &) { return value(); } 
00450 };
00451 
00452 template<class ContainerAllocator>
00453 struct DataType<halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator> > {
00454   static const char* value() 
00455   {
00456     return "halfsteps_pattern_generator/GetPath";
00457   }
00458 
00459   static const char* value(const halfsteps_pattern_generator::GetPathResponse_<ContainerAllocator> &) { return value(); } 
00460 };
00461 
00462 } // namespace service_traits
00463 } // namespace ros
00464 
00465 #endif // HALFSTEPS_PATTERN_GENERATOR_SERVICE_GETPATH_H
00466 


halfsteps_pattern_generator
Author(s): Nicolas Perrin, Thomas Moulard/thomas.moulard@gmail.com
autogenerated on Sat Dec 28 2013 17:05:31