Go to the documentation of this file.00001
00002 #ifndef HUMANOID_NAV_MSGS_SERVICE_STEPTARGETSERVICE_H
00003 #define HUMANOID_NAV_MSGS_SERVICE_STEPTARGETSERVICE_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 "humanoid_nav_msgs/StepTarget.h"
00020
00021
00022
00023 namespace humanoid_nav_msgs
00024 {
00025 template <class ContainerAllocator>
00026 struct StepTargetServiceRequest_ {
00027 typedef StepTargetServiceRequest_<ContainerAllocator> Type;
00028
00029 StepTargetServiceRequest_()
00030 : step()
00031 {
00032 }
00033
00034 StepTargetServiceRequest_(const ContainerAllocator& _alloc)
00035 : step(_alloc)
00036 {
00037 }
00038
00039 typedef ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> _step_type;
00040 ::humanoid_nav_msgs::StepTarget_<ContainerAllocator> step;
00041
00042
00043 typedef boost::shared_ptr< ::humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> > Ptr;
00044 typedef boost::shared_ptr< ::humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> const> ConstPtr;
00045 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00046 };
00047 typedef ::humanoid_nav_msgs::StepTargetServiceRequest_<std::allocator<void> > StepTargetServiceRequest;
00048
00049 typedef boost::shared_ptr< ::humanoid_nav_msgs::StepTargetServiceRequest> StepTargetServiceRequestPtr;
00050 typedef boost::shared_ptr< ::humanoid_nav_msgs::StepTargetServiceRequest const> StepTargetServiceRequestConstPtr;
00051
00052
00053 template <class ContainerAllocator>
00054 struct StepTargetServiceResponse_ {
00055 typedef StepTargetServiceResponse_<ContainerAllocator> Type;
00056
00057 StepTargetServiceResponse_()
00058 {
00059 }
00060
00061 StepTargetServiceResponse_(const ContainerAllocator& _alloc)
00062 {
00063 }
00064
00065
00066 typedef boost::shared_ptr< ::humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> > Ptr;
00067 typedef boost::shared_ptr< ::humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> const> ConstPtr;
00068 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00069 };
00070 typedef ::humanoid_nav_msgs::StepTargetServiceResponse_<std::allocator<void> > StepTargetServiceResponse;
00071
00072 typedef boost::shared_ptr< ::humanoid_nav_msgs::StepTargetServiceResponse> StepTargetServiceResponsePtr;
00073 typedef boost::shared_ptr< ::humanoid_nav_msgs::StepTargetServiceResponse const> StepTargetServiceResponseConstPtr;
00074
00075 struct StepTargetService
00076 {
00077
00078 typedef StepTargetServiceRequest Request;
00079 typedef StepTargetServiceResponse Response;
00080 Request request;
00081 Response response;
00082
00083 typedef Request RequestType;
00084 typedef Response ResponseType;
00085 };
00086 }
00087
00088 namespace ros
00089 {
00090 namespace message_traits
00091 {
00092 template<class ContainerAllocator> struct IsMessage< ::humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> > : public TrueType {};
00093 template<class ContainerAllocator> struct IsMessage< ::humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> const> : public TrueType {};
00094 template<class ContainerAllocator>
00095 struct MD5Sum< ::humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> > {
00096 static const char* value()
00097 {
00098 return "f22cfce442b381849d82602383b052c7";
00099 }
00100
00101 static const char* value(const ::humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> &) { return value(); }
00102 static const uint64_t static_value1 = 0xf22cfce442b38184ULL;
00103 static const uint64_t static_value2 = 0x9d82602383b052c7ULL;
00104 };
00105
00106 template<class ContainerAllocator>
00107 struct DataType< ::humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> > {
00108 static const char* value()
00109 {
00110 return "humanoid_nav_msgs/StepTargetServiceRequest";
00111 }
00112
00113 static const char* value(const ::humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> &) { return value(); }
00114 };
00115
00116 template<class ContainerAllocator>
00117 struct Definition< ::humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> > {
00118 static const char* value()
00119 {
00120 return "\n\
00121 humanoid_nav_msgs/StepTarget step\n\
00122 \n\
00123 ================================================================================\n\
00124 MSG: humanoid_nav_msgs/StepTarget\n\
00125 # Target for a single stepping motion of a humanoid's leg\n\
00126 \n\
00127 geometry_msgs/Pose2D pose # step pose as relative offset to last leg\n\
00128 uint8 leg # which leg to use (left/right, see below)\n\
00129 \n\
00130 uint8 right=0 # right leg constant\n\
00131 uint8 left=1 # left leg constant\n\
00132 \n\
00133 ================================================================================\n\
00134 MSG: geometry_msgs/Pose2D\n\
00135 # This expresses a position and orientation on a 2D manifold.\n\
00136 \n\
00137 float64 x\n\
00138 float64 y\n\
00139 float64 theta\n\
00140 ";
00141 }
00142
00143 static const char* value(const ::humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> &) { return value(); }
00144 };
00145
00146 template<class ContainerAllocator> struct IsFixedSize< ::humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> > : public TrueType {};
00147 }
00148 }
00149
00150
00151 namespace ros
00152 {
00153 namespace message_traits
00154 {
00155 template<class ContainerAllocator> struct IsMessage< ::humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> > : public TrueType {};
00156 template<class ContainerAllocator> struct IsMessage< ::humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> const> : public TrueType {};
00157 template<class ContainerAllocator>
00158 struct MD5Sum< ::humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> > {
00159 static const char* value()
00160 {
00161 return "d41d8cd98f00b204e9800998ecf8427e";
00162 }
00163
00164 static const char* value(const ::humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> &) { return value(); }
00165 static const uint64_t static_value1 = 0xd41d8cd98f00b204ULL;
00166 static const uint64_t static_value2 = 0xe9800998ecf8427eULL;
00167 };
00168
00169 template<class ContainerAllocator>
00170 struct DataType< ::humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> > {
00171 static const char* value()
00172 {
00173 return "humanoid_nav_msgs/StepTargetServiceResponse";
00174 }
00175
00176 static const char* value(const ::humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> &) { return value(); }
00177 };
00178
00179 template<class ContainerAllocator>
00180 struct Definition< ::humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> > {
00181 static const char* value()
00182 {
00183 return "\n\
00184 \n\
00185 ";
00186 }
00187
00188 static const char* value(const ::humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> &) { return value(); }
00189 };
00190
00191 template<class ContainerAllocator> struct IsFixedSize< ::humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> > : public TrueType {};
00192 }
00193 }
00194
00195 namespace ros
00196 {
00197 namespace serialization
00198 {
00199
00200 template<class ContainerAllocator> struct Serializer< ::humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> >
00201 {
00202 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00203 {
00204 stream.next(m.step);
00205 }
00206
00207 ROS_DECLARE_ALLINONE_SERIALIZER;
00208 };
00209 }
00210 }
00211
00212
00213 namespace ros
00214 {
00215 namespace serialization
00216 {
00217
00218 template<class ContainerAllocator> struct Serializer< ::humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> >
00219 {
00220 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00221 {
00222 }
00223
00224 ROS_DECLARE_ALLINONE_SERIALIZER;
00225 };
00226 }
00227 }
00228
00229 namespace ros
00230 {
00231 namespace service_traits
00232 {
00233 template<>
00234 struct MD5Sum<humanoid_nav_msgs::StepTargetService> {
00235 static const char* value()
00236 {
00237 return "f22cfce442b381849d82602383b052c7";
00238 }
00239
00240 static const char* value(const humanoid_nav_msgs::StepTargetService&) { return value(); }
00241 };
00242
00243 template<>
00244 struct DataType<humanoid_nav_msgs::StepTargetService> {
00245 static const char* value()
00246 {
00247 return "humanoid_nav_msgs/StepTargetService";
00248 }
00249
00250 static const char* value(const humanoid_nav_msgs::StepTargetService&) { return value(); }
00251 };
00252
00253 template<class ContainerAllocator>
00254 struct MD5Sum<humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> > {
00255 static const char* value()
00256 {
00257 return "f22cfce442b381849d82602383b052c7";
00258 }
00259
00260 static const char* value(const humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> &) { return value(); }
00261 };
00262
00263 template<class ContainerAllocator>
00264 struct DataType<humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> > {
00265 static const char* value()
00266 {
00267 return "humanoid_nav_msgs/StepTargetService";
00268 }
00269
00270 static const char* value(const humanoid_nav_msgs::StepTargetServiceRequest_<ContainerAllocator> &) { return value(); }
00271 };
00272
00273 template<class ContainerAllocator>
00274 struct MD5Sum<humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> > {
00275 static const char* value()
00276 {
00277 return "f22cfce442b381849d82602383b052c7";
00278 }
00279
00280 static const char* value(const humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> &) { return value(); }
00281 };
00282
00283 template<class ContainerAllocator>
00284 struct DataType<humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> > {
00285 static const char* value()
00286 {
00287 return "humanoid_nav_msgs/StepTargetService";
00288 }
00289
00290 static const char* value(const humanoid_nav_msgs::StepTargetServiceResponse_<ContainerAllocator> &) { return value(); }
00291 };
00292
00293 }
00294 }
00295
00296 #endif // HUMANOID_NAV_MSGS_SERVICE_STEPTARGETSERVICE_H
00297