00001
00002 #ifndef COB_SRVS_SERVICE_SETDEFAULTVEL_H
00003 #define COB_SRVS_SERVICE_SETDEFAULTVEL_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/service_traits.h"
00014
00015
00016
00017 #include "std_msgs/Bool.h"
00018 #include "std_msgs/String.h"
00019
00020 namespace cob_srvs
00021 {
00022 template <class ContainerAllocator>
00023 struct SetDefaultVelRequest_ : public ros::Message
00024 {
00025 typedef SetDefaultVelRequest_<ContainerAllocator> Type;
00026
00027 SetDefaultVelRequest_()
00028 : default_vel(0.0)
00029 {
00030 }
00031
00032 SetDefaultVelRequest_(const ContainerAllocator& _alloc)
00033 : default_vel(0.0)
00034 {
00035 }
00036
00037 typedef float _default_vel_type;
00038 float default_vel;
00039
00040
00041 private:
00042 static const char* __s_getDataType_() { return "cob_srvs/SetDefaultVelRequest"; }
00043 public:
00044 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00045
00046 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00047
00048 private:
00049 static const char* __s_getMD5Sum_() { return "06408962e6bcadda2e07880ad9dedbec"; }
00050 public:
00051 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00052
00053 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00054
00055 private:
00056 static const char* __s_getServerMD5Sum_() { return "a7159156625f755343070ad39bfaf3a3"; }
00057 public:
00058 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00059
00060 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00061
00062 private:
00063 static const char* __s_getMessageDefinition_() { return "float32 default_vel\n\
00064 \n\
00065 "; }
00066 public:
00067 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00068
00069 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00070
00071 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00072 {
00073 ros::serialization::OStream stream(write_ptr, 1000000000);
00074 ros::serialization::serialize(stream, default_vel);
00075 return stream.getData();
00076 }
00077
00078 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00079 {
00080 ros::serialization::IStream stream(read_ptr, 1000000000);
00081 ros::serialization::deserialize(stream, default_vel);
00082 return stream.getData();
00083 }
00084
00085 ROS_DEPRECATED virtual uint32_t serializationLength() const
00086 {
00087 uint32_t size = 0;
00088 size += ros::serialization::serializationLength(default_vel);
00089 return size;
00090 }
00091
00092 typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > Ptr;
00093 typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> const> ConstPtr;
00094 };
00095 typedef ::cob_srvs::SetDefaultVelRequest_<std::allocator<void> > SetDefaultVelRequest;
00096
00097 typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelRequest> SetDefaultVelRequestPtr;
00098 typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelRequest const> SetDefaultVelRequestConstPtr;
00099
00100
00101 template <class ContainerAllocator>
00102 struct SetDefaultVelResponse_ : public ros::Message
00103 {
00104 typedef SetDefaultVelResponse_<ContainerAllocator> Type;
00105
00106 SetDefaultVelResponse_()
00107 : success()
00108 , error_message()
00109 {
00110 }
00111
00112 SetDefaultVelResponse_(const ContainerAllocator& _alloc)
00113 : success(_alloc)
00114 , error_message(_alloc)
00115 {
00116 }
00117
00118 typedef ::std_msgs::Bool_<ContainerAllocator> _success_type;
00119 ::std_msgs::Bool_<ContainerAllocator> success;
00120
00121 typedef ::std_msgs::String_<ContainerAllocator> _error_message_type;
00122 ::std_msgs::String_<ContainerAllocator> error_message;
00123
00124
00125 private:
00126 static const char* __s_getDataType_() { return "cob_srvs/SetDefaultVelResponse"; }
00127 public:
00128 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00129
00130 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00131
00132 private:
00133 static const char* __s_getMD5Sum_() { return "bdad515e8f4c013bd650d3407753d2b8"; }
00134 public:
00135 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00136
00137 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00138
00139 private:
00140 static const char* __s_getServerMD5Sum_() { return "a7159156625f755343070ad39bfaf3a3"; }
00141 public:
00142 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00143
00144 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00145
00146 private:
00147 static const char* __s_getMessageDefinition_() { return "std_msgs/Bool success\n\
00148 std_msgs/String error_message\n\
00149 \n\
00150 \n\
00151 ================================================================================\n\
00152 MSG: std_msgs/Bool\n\
00153 bool data\n\
00154 ================================================================================\n\
00155 MSG: std_msgs/String\n\
00156 string data\n\
00157 \n\
00158 "; }
00159 public:
00160 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00161
00162 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00163
00164 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00165 {
00166 ros::serialization::OStream stream(write_ptr, 1000000000);
00167 ros::serialization::serialize(stream, success);
00168 ros::serialization::serialize(stream, error_message);
00169 return stream.getData();
00170 }
00171
00172 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00173 {
00174 ros::serialization::IStream stream(read_ptr, 1000000000);
00175 ros::serialization::deserialize(stream, success);
00176 ros::serialization::deserialize(stream, error_message);
00177 return stream.getData();
00178 }
00179
00180 ROS_DEPRECATED virtual uint32_t serializationLength() const
00181 {
00182 uint32_t size = 0;
00183 size += ros::serialization::serializationLength(success);
00184 size += ros::serialization::serializationLength(error_message);
00185 return size;
00186 }
00187
00188 typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> > Ptr;
00189 typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> const> ConstPtr;
00190 };
00191 typedef ::cob_srvs::SetDefaultVelResponse_<std::allocator<void> > SetDefaultVelResponse;
00192
00193 typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelResponse> SetDefaultVelResponsePtr;
00194 typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelResponse const> SetDefaultVelResponseConstPtr;
00195
00196 struct SetDefaultVel
00197 {
00198
00199 typedef SetDefaultVelRequest Request;
00200 typedef SetDefaultVelResponse Response;
00201 Request request;
00202 Response response;
00203
00204 typedef Request RequestType;
00205 typedef Response ResponseType;
00206 };
00207 }
00208
00209 namespace ros
00210 {
00211 namespace message_traits
00212 {
00213 template<class ContainerAllocator>
00214 struct MD5Sum< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > {
00215 static const char* value()
00216 {
00217 return "06408962e6bcadda2e07880ad9dedbec";
00218 }
00219
00220 static const char* value(const ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> &) { return value(); }
00221 static const uint64_t static_value1 = 0x06408962e6bcaddaULL;
00222 static const uint64_t static_value2 = 0x2e07880ad9dedbecULL;
00223 };
00224
00225 template<class ContainerAllocator>
00226 struct DataType< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > {
00227 static const char* value()
00228 {
00229 return "cob_srvs/SetDefaultVelRequest";
00230 }
00231
00232 static const char* value(const ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> &) { return value(); }
00233 };
00234
00235 template<class ContainerAllocator>
00236 struct Definition< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > {
00237 static const char* value()
00238 {
00239 return "float32 default_vel\n\
00240 \n\
00241 ";
00242 }
00243
00244 static const char* value(const ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> &) { return value(); }
00245 };
00246
00247 template<class ContainerAllocator> struct IsFixedSize< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > : public TrueType {};
00248 }
00249 }
00250
00251
00252 namespace ros
00253 {
00254 namespace message_traits
00255 {
00256 template<class ContainerAllocator>
00257 struct MD5Sum< ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> > {
00258 static const char* value()
00259 {
00260 return "bdad515e8f4c013bd650d3407753d2b8";
00261 }
00262
00263 static const char* value(const ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> &) { return value(); }
00264 static const uint64_t static_value1 = 0xbdad515e8f4c013bULL;
00265 static const uint64_t static_value2 = 0xd650d3407753d2b8ULL;
00266 };
00267
00268 template<class ContainerAllocator>
00269 struct DataType< ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> > {
00270 static const char* value()
00271 {
00272 return "cob_srvs/SetDefaultVelResponse";
00273 }
00274
00275 static const char* value(const ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> &) { return value(); }
00276 };
00277
00278 template<class ContainerAllocator>
00279 struct Definition< ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> > {
00280 static const char* value()
00281 {
00282 return "std_msgs/Bool success\n\
00283 std_msgs/String error_message\n\
00284 \n\
00285 \n\
00286 ================================================================================\n\
00287 MSG: std_msgs/Bool\n\
00288 bool data\n\
00289 ================================================================================\n\
00290 MSG: std_msgs/String\n\
00291 string data\n\
00292 \n\
00293 ";
00294 }
00295
00296 static const char* value(const ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> &) { return value(); }
00297 };
00298
00299 }
00300 }
00301
00302 namespace ros
00303 {
00304 namespace serialization
00305 {
00306
00307 template<class ContainerAllocator> struct Serializer< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> >
00308 {
00309 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00310 {
00311 stream.next(m.default_vel);
00312 }
00313
00314 ROS_DECLARE_ALLINONE_SERIALIZER;
00315 };
00316 }
00317 }
00318
00319
00320 namespace ros
00321 {
00322 namespace serialization
00323 {
00324
00325 template<class ContainerAllocator> struct Serializer< ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> >
00326 {
00327 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00328 {
00329 stream.next(m.success);
00330 stream.next(m.error_message);
00331 }
00332
00333 ROS_DECLARE_ALLINONE_SERIALIZER;
00334 };
00335 }
00336 }
00337
00338 namespace ros
00339 {
00340 namespace service_traits
00341 {
00342 template<>
00343 struct MD5Sum<cob_srvs::SetDefaultVel> {
00344 static const char* value()
00345 {
00346 return "a7159156625f755343070ad39bfaf3a3";
00347 }
00348
00349 static const char* value(const cob_srvs::SetDefaultVel&) { return value(); }
00350 };
00351
00352 template<>
00353 struct DataType<cob_srvs::SetDefaultVel> {
00354 static const char* value()
00355 {
00356 return "cob_srvs/SetDefaultVel";
00357 }
00358
00359 static const char* value(const cob_srvs::SetDefaultVel&) { return value(); }
00360 };
00361
00362 template<class ContainerAllocator>
00363 struct MD5Sum<cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > {
00364 static const char* value()
00365 {
00366 return "a7159156625f755343070ad39bfaf3a3";
00367 }
00368
00369 static const char* value(const cob_srvs::SetDefaultVelRequest_<ContainerAllocator> &) { return value(); }
00370 };
00371
00372 template<class ContainerAllocator>
00373 struct DataType<cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > {
00374 static const char* value()
00375 {
00376 return "cob_srvs/SetDefaultVel";
00377 }
00378
00379 static const char* value(const cob_srvs::SetDefaultVelRequest_<ContainerAllocator> &) { return value(); }
00380 };
00381
00382 template<class ContainerAllocator>
00383 struct MD5Sum<cob_srvs::SetDefaultVelResponse_<ContainerAllocator> > {
00384 static const char* value()
00385 {
00386 return "a7159156625f755343070ad39bfaf3a3";
00387 }
00388
00389 static const char* value(const cob_srvs::SetDefaultVelResponse_<ContainerAllocator> &) { return value(); }
00390 };
00391
00392 template<class ContainerAllocator>
00393 struct DataType<cob_srvs::SetDefaultVelResponse_<ContainerAllocator> > {
00394 static const char* value()
00395 {
00396 return "cob_srvs/SetDefaultVel";
00397 }
00398
00399 static const char* value(const cob_srvs::SetDefaultVelResponse_<ContainerAllocator> &) { return value(); }
00400 };
00401
00402 }
00403 }
00404
00405 #endif // COB_SRVS_SERVICE_SETDEFAULTVEL_H
00406