SetDefaultVel.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-fuerte-cob_common/doc_stacks/2013-03-01_17-42-56.130276/cob_common/cob_srvs/srv/SetDefaultVel.srv */
00002 #ifndef COB_SRVS_SERVICE_SETDEFAULTVEL_H
00003 #define COB_SRVS_SERVICE_SETDEFAULTVEL_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 
00020 
00021 #include "std_msgs/Bool.h"
00022 #include "std_msgs/String.h"
00023 
00024 namespace cob_srvs
00025 {
00026 template <class ContainerAllocator>
00027 struct SetDefaultVelRequest_ {
00028   typedef SetDefaultVelRequest_<ContainerAllocator> Type;
00029 
00030   SetDefaultVelRequest_()
00031   : default_vel(0.0)
00032   {
00033   }
00034 
00035   SetDefaultVelRequest_(const ContainerAllocator& _alloc)
00036   : default_vel(0.0)
00037   {
00038   }
00039 
00040   typedef float _default_vel_type;
00041   float default_vel;
00042 
00043 
00044   typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > Ptr;
00045   typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator>  const> ConstPtr;
00046   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00047 }; // struct SetDefaultVelRequest
00048 typedef  ::cob_srvs::SetDefaultVelRequest_<std::allocator<void> > SetDefaultVelRequest;
00049 
00050 typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelRequest> SetDefaultVelRequestPtr;
00051 typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelRequest const> SetDefaultVelRequestConstPtr;
00052 
00053 
00054 template <class ContainerAllocator>
00055 struct SetDefaultVelResponse_ {
00056   typedef SetDefaultVelResponse_<ContainerAllocator> Type;
00057 
00058   SetDefaultVelResponse_()
00059   : success()
00060   , error_message()
00061   {
00062   }
00063 
00064   SetDefaultVelResponse_(const ContainerAllocator& _alloc)
00065   : success(_alloc)
00066   , error_message(_alloc)
00067   {
00068   }
00069 
00070   typedef  ::std_msgs::Bool_<ContainerAllocator>  _success_type;
00071    ::std_msgs::Bool_<ContainerAllocator>  success;
00072 
00073   typedef  ::std_msgs::String_<ContainerAllocator>  _error_message_type;
00074    ::std_msgs::String_<ContainerAllocator>  error_message;
00075 
00076 
00077   typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> > Ptr;
00078   typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator>  const> ConstPtr;
00079   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00080 }; // struct SetDefaultVelResponse
00081 typedef  ::cob_srvs::SetDefaultVelResponse_<std::allocator<void> > SetDefaultVelResponse;
00082 
00083 typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelResponse> SetDefaultVelResponsePtr;
00084 typedef boost::shared_ptr< ::cob_srvs::SetDefaultVelResponse const> SetDefaultVelResponseConstPtr;
00085 
00086 struct SetDefaultVel
00087 {
00088 
00089 typedef SetDefaultVelRequest Request;
00090 typedef SetDefaultVelResponse Response;
00091 Request request;
00092 Response response;
00093 
00094 typedef Request RequestType;
00095 typedef Response ResponseType;
00096 }; // struct SetDefaultVel
00097 } // namespace cob_srvs
00098 
00099 namespace ros
00100 {
00101 namespace message_traits
00102 {
00103 template<class ContainerAllocator> struct IsMessage< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > : public TrueType {};
00104 template<class ContainerAllocator> struct IsMessage< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator>  const> : public TrueType {};
00105 template<class ContainerAllocator>
00106 struct MD5Sum< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > {
00107   static const char* value() 
00108   {
00109     return "06408962e6bcadda2e07880ad9dedbec";
00110   }
00111 
00112   static const char* value(const  ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> &) { return value(); } 
00113   static const uint64_t static_value1 = 0x06408962e6bcaddaULL;
00114   static const uint64_t static_value2 = 0x2e07880ad9dedbecULL;
00115 };
00116 
00117 template<class ContainerAllocator>
00118 struct DataType< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > {
00119   static const char* value() 
00120   {
00121     return "cob_srvs/SetDefaultVelRequest";
00122   }
00123 
00124   static const char* value(const  ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> &) { return value(); } 
00125 };
00126 
00127 template<class ContainerAllocator>
00128 struct Definition< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > {
00129   static const char* value() 
00130   {
00131     return "float32 default_vel\n\
00132 \n\
00133 ";
00134   }
00135 
00136   static const char* value(const  ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> &) { return value(); } 
00137 };
00138 
00139 template<class ContainerAllocator> struct IsFixedSize< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > : public TrueType {};
00140 } // namespace message_traits
00141 } // namespace ros
00142 
00143 
00144 namespace ros
00145 {
00146 namespace message_traits
00147 {
00148 template<class ContainerAllocator> struct IsMessage< ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> > : public TrueType {};
00149 template<class ContainerAllocator> struct IsMessage< ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator>  const> : public TrueType {};
00150 template<class ContainerAllocator>
00151 struct MD5Sum< ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> > {
00152   static const char* value() 
00153   {
00154     return "bdad515e8f4c013bd650d3407753d2b8";
00155   }
00156 
00157   static const char* value(const  ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> &) { return value(); } 
00158   static const uint64_t static_value1 = 0xbdad515e8f4c013bULL;
00159   static const uint64_t static_value2 = 0xd650d3407753d2b8ULL;
00160 };
00161 
00162 template<class ContainerAllocator>
00163 struct DataType< ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> > {
00164   static const char* value() 
00165   {
00166     return "cob_srvs/SetDefaultVelResponse";
00167   }
00168 
00169   static const char* value(const  ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> &) { return value(); } 
00170 };
00171 
00172 template<class ContainerAllocator>
00173 struct Definition< ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> > {
00174   static const char* value() 
00175   {
00176     return "std_msgs/Bool success\n\
00177 std_msgs/String error_message\n\
00178 \n\
00179 \n\
00180 ================================================================================\n\
00181 MSG: std_msgs/Bool\n\
00182 bool data\n\
00183 ================================================================================\n\
00184 MSG: std_msgs/String\n\
00185 string data\n\
00186 \n\
00187 ";
00188   }
00189 
00190   static const char* value(const  ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> &) { return value(); } 
00191 };
00192 
00193 } // namespace message_traits
00194 } // namespace ros
00195 
00196 namespace ros
00197 {
00198 namespace serialization
00199 {
00200 
00201 template<class ContainerAllocator> struct Serializer< ::cob_srvs::SetDefaultVelRequest_<ContainerAllocator> >
00202 {
00203   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00204   {
00205     stream.next(m.default_vel);
00206   }
00207 
00208   ROS_DECLARE_ALLINONE_SERIALIZER;
00209 }; // struct SetDefaultVelRequest_
00210 } // namespace serialization
00211 } // namespace ros
00212 
00213 
00214 namespace ros
00215 {
00216 namespace serialization
00217 {
00218 
00219 template<class ContainerAllocator> struct Serializer< ::cob_srvs::SetDefaultVelResponse_<ContainerAllocator> >
00220 {
00221   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00222   {
00223     stream.next(m.success);
00224     stream.next(m.error_message);
00225   }
00226 
00227   ROS_DECLARE_ALLINONE_SERIALIZER;
00228 }; // struct SetDefaultVelResponse_
00229 } // namespace serialization
00230 } // namespace ros
00231 
00232 namespace ros
00233 {
00234 namespace service_traits
00235 {
00236 template<>
00237 struct MD5Sum<cob_srvs::SetDefaultVel> {
00238   static const char* value() 
00239   {
00240     return "a7159156625f755343070ad39bfaf3a3";
00241   }
00242 
00243   static const char* value(const cob_srvs::SetDefaultVel&) { return value(); } 
00244 };
00245 
00246 template<>
00247 struct DataType<cob_srvs::SetDefaultVel> {
00248   static const char* value() 
00249   {
00250     return "cob_srvs/SetDefaultVel";
00251   }
00252 
00253   static const char* value(const cob_srvs::SetDefaultVel&) { return value(); } 
00254 };
00255 
00256 template<class ContainerAllocator>
00257 struct MD5Sum<cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > {
00258   static const char* value() 
00259   {
00260     return "a7159156625f755343070ad39bfaf3a3";
00261   }
00262 
00263   static const char* value(const cob_srvs::SetDefaultVelRequest_<ContainerAllocator> &) { return value(); } 
00264 };
00265 
00266 template<class ContainerAllocator>
00267 struct DataType<cob_srvs::SetDefaultVelRequest_<ContainerAllocator> > {
00268   static const char* value() 
00269   {
00270     return "cob_srvs/SetDefaultVel";
00271   }
00272 
00273   static const char* value(const cob_srvs::SetDefaultVelRequest_<ContainerAllocator> &) { return value(); } 
00274 };
00275 
00276 template<class ContainerAllocator>
00277 struct MD5Sum<cob_srvs::SetDefaultVelResponse_<ContainerAllocator> > {
00278   static const char* value() 
00279   {
00280     return "a7159156625f755343070ad39bfaf3a3";
00281   }
00282 
00283   static const char* value(const cob_srvs::SetDefaultVelResponse_<ContainerAllocator> &) { return value(); } 
00284 };
00285 
00286 template<class ContainerAllocator>
00287 struct DataType<cob_srvs::SetDefaultVelResponse_<ContainerAllocator> > {
00288   static const char* value() 
00289   {
00290     return "cob_srvs/SetDefaultVel";
00291   }
00292 
00293   static const char* value(const cob_srvs::SetDefaultVelResponse_<ContainerAllocator> &) { return value(); } 
00294 };
00295 
00296 } // namespace service_traits
00297 } // namespace ros
00298 
00299 #endif // COB_SRVS_SERVICE_SETDEFAULTVEL_H
00300 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


cob_srvs
Author(s): Florian Weisshardt
autogenerated on Fri Mar 1 2013 17:46:00