$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-humanoid_msgs/doc_stacks/2013-03-05_11-57-21.881989/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 private: 00051 static const char* __s_getDataType_() { return "humanoid_nav_msgs/PlanFootstepsRequest"; } 00052 public: 00053 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00054 00055 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00056 00057 private: 00058 static const char* __s_getMD5Sum_() { return "5e8ecd9fb61e382b8974a904baeee367"; } 00059 public: 00060 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00061 00062 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00063 00064 private: 00065 static const char* __s_getServerMD5Sum_() { return "6776471c1b6635688929b81b014b1c1c"; } 00066 public: 00067 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00068 00069 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00070 00071 private: 00072 static const char* __s_getMessageDefinition_() { return "geometry_msgs/Pose2D start\n\ 00073 geometry_msgs/Pose2D goal\n\ 00074 \n\ 00075 ================================================================================\n\ 00076 MSG: geometry_msgs/Pose2D\n\ 00077 # This expresses a position and orientation on a 2D manifold.\n\ 00078 \n\ 00079 float64 x\n\ 00080 float64 y\n\ 00081 float64 theta\n\ 00082 "; } 00083 public: 00084 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00085 00086 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00087 00088 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00089 { 00090 ros::serialization::OStream stream(write_ptr, 1000000000); 00091 ros::serialization::serialize(stream, start); 00092 ros::serialization::serialize(stream, goal); 00093 return stream.getData(); 00094 } 00095 00096 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00097 { 00098 ros::serialization::IStream stream(read_ptr, 1000000000); 00099 ros::serialization::deserialize(stream, start); 00100 ros::serialization::deserialize(stream, goal); 00101 return stream.getData(); 00102 } 00103 00104 ROS_DEPRECATED virtual uint32_t serializationLength() const 00105 { 00106 uint32_t size = 0; 00107 size += ros::serialization::serializationLength(start); 00108 size += ros::serialization::serializationLength(goal); 00109 return size; 00110 } 00111 00112 typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > Ptr; 00113 typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> const> ConstPtr; 00114 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00115 }; // struct PlanFootstepsRequest 00116 typedef ::humanoid_nav_msgs::PlanFootstepsRequest_<std::allocator<void> > PlanFootstepsRequest; 00117 00118 typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsRequest> PlanFootstepsRequestPtr; 00119 typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsRequest const> PlanFootstepsRequestConstPtr; 00120 00121 00122 template <class ContainerAllocator> 00123 struct PlanFootstepsResponse_ { 00124 typedef PlanFootstepsResponse_<ContainerAllocator> Type; 00125 00126 PlanFootstepsResponse_() 00127 : result(false) 00128 , footsteps() 00129 , costs(0.0) 00130 , final_eps(0.0) 00131 , planning_time(0.0) 00132 , expanded_states(0) 00133 { 00134 } 00135 00136 PlanFootstepsResponse_(const ContainerAllocator& _alloc) 00137 : result(false) 00138 , footsteps(_alloc) 00139 , costs(0.0) 00140 , final_eps(0.0) 00141 , planning_time(0.0) 00142 , expanded_states(0) 00143 { 00144 } 00145 00146 typedef uint8_t _result_type; 00147 uint8_t result; 00148 00149 typedef std::vector< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> >::other > _footsteps_type; 00150 std::vector< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> >::other > footsteps; 00151 00152 typedef double _costs_type; 00153 double costs; 00154 00155 typedef double _final_eps_type; 00156 double final_eps; 00157 00158 typedef double _planning_time_type; 00159 double planning_time; 00160 00161 typedef int64_t _expanded_states_type; 00162 int64_t expanded_states; 00163 00164 00165 ROS_DEPRECATED uint32_t get_footsteps_size() const { return (uint32_t)footsteps.size(); } 00166 ROS_DEPRECATED void set_footsteps_size(uint32_t size) { footsteps.resize((size_t)size); } 00167 ROS_DEPRECATED void get_footsteps_vec(std::vector< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> >::other > & vec) const { vec = this->footsteps; } 00168 ROS_DEPRECATED void set_footsteps_vec(const std::vector< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> >::other > & vec) { this->footsteps = vec; } 00169 private: 00170 static const char* __s_getDataType_() { return "humanoid_nav_msgs/PlanFootstepsResponse"; } 00171 public: 00172 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00173 00174 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00175 00176 private: 00177 static const char* __s_getMD5Sum_() { return "1af07cd1d4ffe34a9a731e87aa13835c"; } 00178 public: 00179 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00180 00181 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00182 00183 private: 00184 static const char* __s_getServerMD5Sum_() { return "6776471c1b6635688929b81b014b1c1c"; } 00185 public: 00186 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00187 00188 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00189 00190 private: 00191 static const char* __s_getMessageDefinition_() { return "bool result\n\ 00192 humanoid_nav_msgs/StepTarget[] footsteps\n\ 00193 float64 costs\n\ 00194 float64 final_eps\n\ 00195 float64 planning_time\n\ 00196 int64 expanded_states\n\ 00197 \n\ 00198 \n\ 00199 ================================================================================\n\ 00200 MSG: humanoid_nav_msgs/StepTarget\n\ 00201 # Target for a single stepping motion of a humanoid's leg\n\ 00202 \n\ 00203 geometry_msgs/Pose2D pose # step pose as relative offset to last leg\n\ 00204 uint8 leg # which leg to use (left/right, see below)\n\ 00205 \n\ 00206 uint8 right=0 # right leg constant\n\ 00207 uint8 left=1 # left leg constant\n\ 00208 \n\ 00209 ================================================================================\n\ 00210 MSG: geometry_msgs/Pose2D\n\ 00211 # This expresses a position and orientation on a 2D manifold.\n\ 00212 \n\ 00213 float64 x\n\ 00214 float64 y\n\ 00215 float64 theta\n\ 00216 "; } 00217 public: 00218 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00219 00220 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00221 00222 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00223 { 00224 ros::serialization::OStream stream(write_ptr, 1000000000); 00225 ros::serialization::serialize(stream, result); 00226 ros::serialization::serialize(stream, footsteps); 00227 ros::serialization::serialize(stream, costs); 00228 ros::serialization::serialize(stream, final_eps); 00229 ros::serialization::serialize(stream, planning_time); 00230 ros::serialization::serialize(stream, expanded_states); 00231 return stream.getData(); 00232 } 00233 00234 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00235 { 00236 ros::serialization::IStream stream(read_ptr, 1000000000); 00237 ros::serialization::deserialize(stream, result); 00238 ros::serialization::deserialize(stream, footsteps); 00239 ros::serialization::deserialize(stream, costs); 00240 ros::serialization::deserialize(stream, final_eps); 00241 ros::serialization::deserialize(stream, planning_time); 00242 ros::serialization::deserialize(stream, expanded_states); 00243 return stream.getData(); 00244 } 00245 00246 ROS_DEPRECATED virtual uint32_t serializationLength() const 00247 { 00248 uint32_t size = 0; 00249 size += ros::serialization::serializationLength(result); 00250 size += ros::serialization::serializationLength(footsteps); 00251 size += ros::serialization::serializationLength(costs); 00252 size += ros::serialization::serializationLength(final_eps); 00253 size += ros::serialization::serializationLength(planning_time); 00254 size += ros::serialization::serializationLength(expanded_states); 00255 return size; 00256 } 00257 00258 typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > Ptr; 00259 typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> const> ConstPtr; 00260 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00261 }; // struct PlanFootstepsResponse 00262 typedef ::humanoid_nav_msgs::PlanFootstepsResponse_<std::allocator<void> > PlanFootstepsResponse; 00263 00264 typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsResponse> PlanFootstepsResponsePtr; 00265 typedef boost::shared_ptr< ::humanoid_nav_msgs::PlanFootstepsResponse const> PlanFootstepsResponseConstPtr; 00266 00267 struct PlanFootsteps 00268 { 00269 00270 typedef PlanFootstepsRequest Request; 00271 typedef PlanFootstepsResponse Response; 00272 Request request; 00273 Response response; 00274 00275 typedef Request RequestType; 00276 typedef Response ResponseType; 00277 }; // struct PlanFootsteps 00278 } // namespace humanoid_nav_msgs 00279 00280 namespace ros 00281 { 00282 namespace message_traits 00283 { 00284 template<class ContainerAllocator> struct IsMessage< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > : public TrueType {}; 00285 template<class ContainerAllocator> struct IsMessage< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> const> : public TrueType {}; 00286 template<class ContainerAllocator> 00287 struct MD5Sum< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > { 00288 static const char* value() 00289 { 00290 return "5e8ecd9fb61e382b8974a904baeee367"; 00291 } 00292 00293 static const char* value(const ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> &) { return value(); } 00294 static const uint64_t static_value1 = 0x5e8ecd9fb61e382bULL; 00295 static const uint64_t static_value2 = 0x8974a904baeee367ULL; 00296 }; 00297 00298 template<class ContainerAllocator> 00299 struct DataType< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > { 00300 static const char* value() 00301 { 00302 return "humanoid_nav_msgs/PlanFootstepsRequest"; 00303 } 00304 00305 static const char* value(const ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> &) { return value(); } 00306 }; 00307 00308 template<class ContainerAllocator> 00309 struct Definition< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > { 00310 static const char* value() 00311 { 00312 return "geometry_msgs/Pose2D start\n\ 00313 geometry_msgs/Pose2D goal\n\ 00314 \n\ 00315 ================================================================================\n\ 00316 MSG: geometry_msgs/Pose2D\n\ 00317 # This expresses a position and orientation on a 2D manifold.\n\ 00318 \n\ 00319 float64 x\n\ 00320 float64 y\n\ 00321 float64 theta\n\ 00322 "; 00323 } 00324 00325 static const char* value(const ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> &) { return value(); } 00326 }; 00327 00328 template<class ContainerAllocator> struct IsFixedSize< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > : public TrueType {}; 00329 } // namespace message_traits 00330 } // namespace ros 00331 00332 00333 namespace ros 00334 { 00335 namespace message_traits 00336 { 00337 template<class ContainerAllocator> struct IsMessage< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > : public TrueType {}; 00338 template<class ContainerAllocator> struct IsMessage< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> const> : public TrueType {}; 00339 template<class ContainerAllocator> 00340 struct MD5Sum< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > { 00341 static const char* value() 00342 { 00343 return "1af07cd1d4ffe34a9a731e87aa13835c"; 00344 } 00345 00346 static const char* value(const ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> &) { return value(); } 00347 static const uint64_t static_value1 = 0x1af07cd1d4ffe34aULL; 00348 static const uint64_t static_value2 = 0x9a731e87aa13835cULL; 00349 }; 00350 00351 template<class ContainerAllocator> 00352 struct DataType< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > { 00353 static const char* value() 00354 { 00355 return "humanoid_nav_msgs/PlanFootstepsResponse"; 00356 } 00357 00358 static const char* value(const ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> &) { return value(); } 00359 }; 00360 00361 template<class ContainerAllocator> 00362 struct Definition< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > { 00363 static const char* value() 00364 { 00365 return "bool result\n\ 00366 humanoid_nav_msgs/StepTarget[] footsteps\n\ 00367 float64 costs\n\ 00368 float64 final_eps\n\ 00369 float64 planning_time\n\ 00370 int64 expanded_states\n\ 00371 \n\ 00372 \n\ 00373 ================================================================================\n\ 00374 MSG: humanoid_nav_msgs/StepTarget\n\ 00375 # Target for a single stepping motion of a humanoid's leg\n\ 00376 \n\ 00377 geometry_msgs/Pose2D pose # step pose as relative offset to last leg\n\ 00378 uint8 leg # which leg to use (left/right, see below)\n\ 00379 \n\ 00380 uint8 right=0 # right leg constant\n\ 00381 uint8 left=1 # left leg constant\n\ 00382 \n\ 00383 ================================================================================\n\ 00384 MSG: geometry_msgs/Pose2D\n\ 00385 # This expresses a position and orientation on a 2D manifold.\n\ 00386 \n\ 00387 float64 x\n\ 00388 float64 y\n\ 00389 float64 theta\n\ 00390 "; 00391 } 00392 00393 static const char* value(const ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> &) { return value(); } 00394 }; 00395 00396 } // namespace message_traits 00397 } // namespace ros 00398 00399 namespace ros 00400 { 00401 namespace serialization 00402 { 00403 00404 template<class ContainerAllocator> struct Serializer< ::humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > 00405 { 00406 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00407 { 00408 stream.next(m.start); 00409 stream.next(m.goal); 00410 } 00411 00412 ROS_DECLARE_ALLINONE_SERIALIZER; 00413 }; // struct PlanFootstepsRequest_ 00414 } // namespace serialization 00415 } // namespace ros 00416 00417 00418 namespace ros 00419 { 00420 namespace serialization 00421 { 00422 00423 template<class ContainerAllocator> struct Serializer< ::humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > 00424 { 00425 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00426 { 00427 stream.next(m.result); 00428 stream.next(m.footsteps); 00429 stream.next(m.costs); 00430 stream.next(m.final_eps); 00431 stream.next(m.planning_time); 00432 stream.next(m.expanded_states); 00433 } 00434 00435 ROS_DECLARE_ALLINONE_SERIALIZER; 00436 }; // struct PlanFootstepsResponse_ 00437 } // namespace serialization 00438 } // namespace ros 00439 00440 namespace ros 00441 { 00442 namespace service_traits 00443 { 00444 template<> 00445 struct MD5Sum<humanoid_nav_msgs::PlanFootsteps> { 00446 static const char* value() 00447 { 00448 return "6776471c1b6635688929b81b014b1c1c"; 00449 } 00450 00451 static const char* value(const humanoid_nav_msgs::PlanFootsteps&) { return value(); } 00452 }; 00453 00454 template<> 00455 struct DataType<humanoid_nav_msgs::PlanFootsteps> { 00456 static const char* value() 00457 { 00458 return "humanoid_nav_msgs/PlanFootsteps"; 00459 } 00460 00461 static const char* value(const humanoid_nav_msgs::PlanFootsteps&) { return value(); } 00462 }; 00463 00464 template<class ContainerAllocator> 00465 struct MD5Sum<humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > { 00466 static const char* value() 00467 { 00468 return "6776471c1b6635688929b81b014b1c1c"; 00469 } 00470 00471 static const char* value(const humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> &) { return value(); } 00472 }; 00473 00474 template<class ContainerAllocator> 00475 struct DataType<humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> > { 00476 static const char* value() 00477 { 00478 return "humanoid_nav_msgs/PlanFootsteps"; 00479 } 00480 00481 static const char* value(const humanoid_nav_msgs::PlanFootstepsRequest_<ContainerAllocator> &) { return value(); } 00482 }; 00483 00484 template<class ContainerAllocator> 00485 struct MD5Sum<humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > { 00486 static const char* value() 00487 { 00488 return "6776471c1b6635688929b81b014b1c1c"; 00489 } 00490 00491 static const char* value(const humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> &) { return value(); } 00492 }; 00493 00494 template<class ContainerAllocator> 00495 struct DataType<humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> > { 00496 static const char* value() 00497 { 00498 return "humanoid_nav_msgs/PlanFootsteps"; 00499 } 00500 00501 static const char* value(const humanoid_nav_msgs::PlanFootstepsResponse_<ContainerAllocator> &) { return value(); } 00502 }; 00503 00504 } // namespace service_traits 00505 } // namespace ros 00506 00507 #endif // HUMANOID_NAV_MSGS_SERVICE_PLANFOOTSTEPS_H 00508