PlanFootsteps.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-fuerte-alufr-humanoid_stacks/doc_stacks/2013-10-15_10-01-44.393682/humanoid_msgs/humanoid_nav_msgs/srv/PlanFootsteps.srv */
00002 #ifndef HUMANOID_NAV_MSGS_SERVICE_PLANFOOTSTEPS_H
00003 #define HUMANOID_NAV_MSGS_SERVICE_PLANFOOTSTEPS_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/Pose2D.h"
00020 #include "geometry_msgs/Pose2D.h"
00021 
00022 
00023 #include "humanoid_nav_msgs/StepTarget.h"
00024 
00025 namespace humanoid_nav_msgs
00026 {
00027 template <class ContainerAllocator>
00028 struct PlanFootstepsRequest_ {
00029   typedef PlanFootstepsRequest_<ContainerAllocator> Type;
00030 
00031   PlanFootstepsRequest_()
00032   : start()
00033   , goal()
00034   {
00035   }
00036 
00037   PlanFootstepsRequest_(const ContainerAllocator& _alloc)
00038   : start(_alloc)
00039   , goal(_alloc)
00040   {
00041   }
00042 
00043   typedef  ::geometry_msgs::Pose2D_<ContainerAllocator>  _start_type;
00044    ::geometry_msgs::Pose2D_<ContainerAllocator>  start;
00045 
00046   typedef  ::geometry_msgs::Pose2D_<ContainerAllocator>  _goal_type;
00047    ::geometry_msgs::Pose2D_<ContainerAllocator>  goal;
00048 
00049 
00050   typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > Ptr;
00051   typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator>  const> ConstPtr;
00052   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00053 }; // struct PlanFootstepsRequest
00054 typedef  ::humanoid_nav_msgs::PlanFootstepsRequest_<std::allocator<void> > PlanFootstepsRequest;
00055 
00056 typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsRequest> PlanFootstepsRequestPtr;
00057 typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsRequest const> PlanFootstepsRequestConstPtr;
00058 
00059 
00060 template <class ContainerAllocator>
00061 struct PlanFootstepsResponse_ {
00062   typedef PlanFootstepsResponse_<ContainerAllocator> Type;
00063 
00064   PlanFootstepsResponse_()
00065   : result(false)
00066   , footsteps()
00067   , costs(0.0)
00068   , final_eps(0.0)
00069   , planning_time(0.0)
00070   , expanded_states(0)
00071   {
00072   }
00073 
00074   PlanFootstepsResponse_(const ContainerAllocator& _alloc)
00075   : result(false)
00076   , footsteps(_alloc)
00077   , costs(0.0)
00078   , final_eps(0.0)
00079   , planning_time(0.0)
00080   , expanded_states(0)
00081   {
00082   }
00083 
00084   typedef uint8_t _result_type;
00085   uint8_t result;
00086 
00087   typedef std::vector< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> >::other >  _footsteps_type;
00088   std::vector< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> >::other >  footsteps;
00089 
00090   typedef double _costs_type;
00091   double costs;
00092 
00093   typedef double _final_eps_type;
00094   double final_eps;
00095 
00096   typedef double _planning_time_type;
00097   double planning_time;
00098 
00099   typedef int64_t _expanded_states_type;
00100   int64_t expanded_states;
00101 
00102 
00103   typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > Ptr;
00104   typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator>  const> ConstPtr;
00105   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00106 }; // struct PlanFootstepsResponse
00107 typedef  ::humanoid_nav_msgs::PlanFootstepsResponse_<std::allocator<void> > PlanFootstepsResponse;
00108 
00109 typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsResponse> PlanFootstepsResponsePtr;
00110 typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsResponse const> PlanFootstepsResponseConstPtr;
00111 
00112 struct PlanFootsteps
00113 {
00114 
00115 typedef PlanFootstepsRequest Request;
00116 typedef PlanFootstepsResponse Response;
00117 Request request;
00118 Response response;
00119 
00120 typedef Request RequestType;
00121 typedef Response ResponseType;
00122 }; // struct PlanFootsteps
00123 } // namespace humanoid_nav_msgs
00124 
00125 namespace ros
00126 {
00127 namespace message_traits
00128 {
00129 template<class ContainerAllocator> struct IsMessage< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > : public TrueType {};
00130 template<class ContainerAllocator> struct IsMessage< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator>  const> : public TrueType {};
00131 template<class ContainerAllocator>
00132 struct MD5Sum< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > {
00133   static const char* value() 
00134   {
00135     return "5e8ecd9fb61e382b8974a904baeee367";
00136   }
00137 
00138   static const char* value(const  ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> &) { return value(); } 
00139   static const uint64_t static_value1 = 0x5e8ecd9fb61e382bULL;
00140   static const uint64_t static_value2 = 0x8974a904baeee367ULL;
00141 };
00142 
00143 template<class ContainerAllocator>
00144 struct DataType< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > {
00145   static const char* value() 
00146   {
00147     return "humanoid_nav_msgs/PlanFootstepsRequest";
00148   }
00149 
00150   static const char* value(const  ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> &) { return value(); } 
00151 };
00152 
00153 template<class ContainerAllocator>
00154 struct Definition< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > {
00155   static const char* value() 
00156   {
00157     return "geometry_msgs/Pose2D start\n\
00158 geometry_msgs/Pose2D goal\n\
00159 \n\
00160 ================================================================================\n\
00161 MSG: geometry_msgs/Pose2D\n\
00162 # This expresses a position and orientation on a 2D manifold.\n\
00163 \n\
00164 float64 x\n\
00165 float64 y\n\
00166 float64 theta\n\
00167 ";
00168   }
00169 
00170   static const char* value(const  ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> &) { return value(); } 
00171 };
00172 
00173 template<class ContainerAllocator> struct IsFixedSize< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > : public TrueType {};
00174 } // namespace message_traits
00175 } // namespace ros
00176 
00177 
00178 namespace ros
00179 {
00180 namespace message_traits
00181 {
00182 template<class ContainerAllocator> struct IsMessage< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > : public TrueType {};
00183 template<class ContainerAllocator> struct IsMessage< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator>  const> : public TrueType {};
00184 template<class ContainerAllocator>
00185 struct MD5Sum< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > {
00186   static const char* value() 
00187   {
00188     return "1af07cd1d4ffe34a9a731e87aa13835c";
00189   }
00190 
00191   static const char* value(const  ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> &) { return value(); } 
00192   static const uint64_t static_value1 = 0x1af07cd1d4ffe34aULL;
00193   static const uint64_t static_value2 = 0x9a731e87aa13835cULL;
00194 };
00195 
00196 template<class ContainerAllocator>
00197 struct DataType< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > {
00198   static const char* value() 
00199   {
00200     return "humanoid_nav_msgs/PlanFootstepsResponse";
00201   }
00202 
00203   static const char* value(const  ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> &) { return value(); } 
00204 };
00205 
00206 template<class ContainerAllocator>
00207 struct Definition< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > {
00208   static const char* value() 
00209   {
00210     return "bool result\n\
00211 humanoid_nav_msgs/StepTarget[] footsteps\n\
00212 float64 costs\n\
00213 float64 final_eps\n\
00214 float64 planning_time\n\
00215 int64 expanded_states\n\
00216 \n\
00217 \n\
00218 ================================================================================\n\
00219 MSG: humanoid_nav_msgs/StepTarget\n\
00220 # Target for a single stepping motion of a humanoid's leg\n\
00221 \n\
00222 geometry_msgs/Pose2D pose   # step pose as relative offset to last leg\n\
00223 uint8 leg                   # which leg to use (left/right, see below)\n\
00224 \n\
00225 uint8 right=0               # right leg constant\n\
00226 uint8 left=1                # left leg constant\n\
00227 \n\
00228 ================================================================================\n\
00229 MSG: geometry_msgs/Pose2D\n\
00230 # This expresses a position and orientation on a 2D manifold.\n\
00231 \n\
00232 float64 x\n\
00233 float64 y\n\
00234 float64 theta\n\
00235 ";
00236   }
00237 
00238   static const char* value(const  ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> &) { return value(); } 
00239 };
00240 
00241 } // namespace message_traits
00242 } // namespace ros
00243 
00244 namespace ros
00245 {
00246 namespace serialization
00247 {
00248 
00249 template<class ContainerAllocator> struct Serializer< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> >
00250 {
00251   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00252   {
00253     stream.next(m.start);
00254     stream.next(m.goal);
00255   }
00256 
00257   ROS_DECLARE_ALLINONE_SERIALIZER;
00258 }; // struct PlanFootstepsRequest_
00259 } // namespace serialization
00260 } // namespace ros
00261 
00262 
00263 namespace ros
00264 {
00265 namespace serialization
00266 {
00267 
00268 template<class ContainerAllocator> struct Serializer< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> >
00269 {
00270   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00271   {
00272     stream.next(m.result);
00273     stream.next(m.footsteps);
00274     stream.next(m.costs);
00275     stream.next(m.final_eps);
00276     stream.next(m.planning_time);
00277     stream.next(m.expanded_states);
00278   }
00279 
00280   ROS_DECLARE_ALLINONE_SERIALIZER;
00281 }; // struct PlanFootstepsResponse_
00282 } // namespace serialization
00283 } // namespace ros
00284 
00285 namespace ros
00286 {
00287 namespace service_traits
00288 {
00289 template<>
00290 struct MD5Sum<humanoid_nav_msgs::PlanFootsteps> {
00291   static const char* value() 
00292   {
00293     return "6776471c1b6635688929b81b014b1c1c";
00294   }
00295 
00296   static const char* value(const humanoid_nav_msgs::PlanFootsteps&) { return value(); } 
00297 };
00298 
00299 template<>
00300 struct DataType<humanoid_nav_msgs::PlanFootsteps> {
00301   static const char* value() 
00302   {
00303     return "humanoid_nav_msgs/PlanFootsteps";
00304   }
00305 
00306   static const char* value(const humanoid_nav_msgs::PlanFootsteps&) { return value(); } 
00307 };
00308 
00309 template<class ContainerAllocator>
00310 struct MD5Sum<humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > {
00311   static const char* value() 
00312   {
00313     return "6776471c1b6635688929b81b014b1c1c";
00314   }
00315 
00316   static const char* value(const humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> &) { return value(); } 
00317 };
00318 
00319 template<class ContainerAllocator>
00320 struct DataType<humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > {
00321   static const char* value() 
00322   {
00323     return "humanoid_nav_msgs/PlanFootsteps";
00324   }
00325 
00326   static const char* value(const humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> &) { return value(); } 
00327 };
00328 
00329 template<class ContainerAllocator>
00330 struct MD5Sum<humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > {
00331   static const char* value() 
00332   {
00333     return "6776471c1b6635688929b81b014b1c1c";
00334   }
00335 
00336   static const char* value(const humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> &) { return value(); } 
00337 };
00338 
00339 template<class ContainerAllocator>
00340 struct DataType<humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > {
00341   static const char* value() 
00342   {
00343     return "humanoid_nav_msgs/PlanFootsteps";
00344   }
00345 
00346   static const char* value(const humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> &) { return value(); } 
00347 };
00348 
00349 } // namespace service_traits
00350 } // namespace ros
00351 
00352 #endif // HUMANOID_NAV_MSGS_SERVICE_PLANFOOTSTEPS_H
00353 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


humanoid_nav_msgs
Author(s): Armin Hornung
autogenerated on Tue Oct 15 2013 10:05:54