00001
00002 #ifndef SRS_ENV_MODEL_PERCP_SERVICE_CLEARPLANES_H
00003 #define SRS_ENV_MODEL_PERCP_SERVICE_CLEARPLANES_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 "std_msgs/Header.h"
00020
00021
00022
00023 namespace srs_env_model_percp
00024 {
00025 template <class ContainerAllocator>
00026 struct ClearPlanesRequest_ {
00027 typedef ClearPlanesRequest_<ContainerAllocator> Type;
00028
00029 ClearPlanesRequest_()
00030 : header()
00031 {
00032 }
00033
00034 ClearPlanesRequest_(const ContainerAllocator& _alloc)
00035 : header(_alloc)
00036 {
00037 }
00038
00039 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00040 ::std_msgs::Header_<ContainerAllocator> header;
00041
00042
00043 private:
00044 static const char* __s_getDataType_() { return "srs_env_model_percp/ClearPlanesRequest"; }
00045 public:
00046 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00047
00048 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00049
00050 private:
00051 static const char* __s_getMD5Sum_() { return "d7be0bb39af8fb9129d5a76e6b63a290"; }
00052 public:
00053 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00054
00055 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00056
00057 private:
00058 static const char* __s_getServerMD5Sum_() { return "2198c46fe39dc9af0a46ecd66c4a97ea"; }
00059 public:
00060 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00061
00062 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00063
00064 private:
00065 static const char* __s_getMessageDefinition_() { return "\n\
00066 \n\
00067 Header header\n\
00068 \n\
00069 \n\
00070 ================================================================================\n\
00071 MSG: std_msgs/Header\n\
00072 # Standard metadata for higher-level stamped data types.\n\
00073 # This is generally used to communicate timestamped data \n\
00074 # in a particular coordinate frame.\n\
00075 # \n\
00076 # sequence ID: consecutively increasing ID \n\
00077 uint32 seq\n\
00078 #Two-integer timestamp that is expressed as:\n\
00079 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00080 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00081 # time-handling sugar is provided by the client library\n\
00082 time stamp\n\
00083 #Frame this data is associated with\n\
00084 # 0: no frame\n\
00085 # 1: global frame\n\
00086 string frame_id\n\
00087 \n\
00088 "; }
00089 public:
00090 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00091
00092 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00093
00094 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00095 {
00096 ros::serialization::OStream stream(write_ptr, 1000000000);
00097 ros::serialization::serialize(stream, header);
00098 return stream.getData();
00099 }
00100
00101 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00102 {
00103 ros::serialization::IStream stream(read_ptr, 1000000000);
00104 ros::serialization::deserialize(stream, header);
00105 return stream.getData();
00106 }
00107
00108 ROS_DEPRECATED virtual uint32_t serializationLength() const
00109 {
00110 uint32_t size = 0;
00111 size += ros::serialization::serializationLength(header);
00112 return size;
00113 }
00114
00115 typedef boost::shared_ptr< ::srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> > Ptr;
00116 typedef boost::shared_ptr< ::srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> const> ConstPtr;
00117 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00118 };
00119 typedef ::srs_env_model_percp::ClearPlanesRequest_<std::allocator<void> > ClearPlanesRequest;
00120
00121 typedef boost::shared_ptr< ::srs_env_model_percp::ClearPlanesRequest> ClearPlanesRequestPtr;
00122 typedef boost::shared_ptr< ::srs_env_model_percp::ClearPlanesRequest const> ClearPlanesRequestConstPtr;
00123
00124
00125 template <class ContainerAllocator>
00126 struct ClearPlanesResponse_ {
00127 typedef ClearPlanesResponse_<ContainerAllocator> Type;
00128
00129 ClearPlanesResponse_()
00130 : message()
00131 {
00132 }
00133
00134 ClearPlanesResponse_(const ContainerAllocator& _alloc)
00135 : message(_alloc)
00136 {
00137 }
00138
00139 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _message_type;
00140 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > message;
00141
00142
00143 private:
00144 static const char* __s_getDataType_() { return "srs_env_model_percp/ClearPlanesResponse"; }
00145 public:
00146 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00147
00148 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00149
00150 private:
00151 static const char* __s_getMD5Sum_() { return "5f003d6bcc824cbd51361d66d8e4f76c"; }
00152 public:
00153 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00154
00155 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00156
00157 private:
00158 static const char* __s_getServerMD5Sum_() { return "2198c46fe39dc9af0a46ecd66c4a97ea"; }
00159 public:
00160 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00161
00162 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00163
00164 private:
00165 static const char* __s_getMessageDefinition_() { return "\n\
00166 \n\
00167 \n\
00168 string message\n\
00169 \n\
00170 "; }
00171 public:
00172 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00173
00174 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00175
00176 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00177 {
00178 ros::serialization::OStream stream(write_ptr, 1000000000);
00179 ros::serialization::serialize(stream, message);
00180 return stream.getData();
00181 }
00182
00183 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00184 {
00185 ros::serialization::IStream stream(read_ptr, 1000000000);
00186 ros::serialization::deserialize(stream, message);
00187 return stream.getData();
00188 }
00189
00190 ROS_DEPRECATED virtual uint32_t serializationLength() const
00191 {
00192 uint32_t size = 0;
00193 size += ros::serialization::serializationLength(message);
00194 return size;
00195 }
00196
00197 typedef boost::shared_ptr< ::srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> > Ptr;
00198 typedef boost::shared_ptr< ::srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> const> ConstPtr;
00199 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00200 };
00201 typedef ::srs_env_model_percp::ClearPlanesResponse_<std::allocator<void> > ClearPlanesResponse;
00202
00203 typedef boost::shared_ptr< ::srs_env_model_percp::ClearPlanesResponse> ClearPlanesResponsePtr;
00204 typedef boost::shared_ptr< ::srs_env_model_percp::ClearPlanesResponse const> ClearPlanesResponseConstPtr;
00205
00206 struct ClearPlanes
00207 {
00208
00209 typedef ClearPlanesRequest Request;
00210 typedef ClearPlanesResponse Response;
00211 Request request;
00212 Response response;
00213
00214 typedef Request RequestType;
00215 typedef Response ResponseType;
00216 };
00217 }
00218
00219 namespace ros
00220 {
00221 namespace message_traits
00222 {
00223 template<class ContainerAllocator> struct IsMessage< ::srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> > : public TrueType {};
00224 template<class ContainerAllocator> struct IsMessage< ::srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> const> : public TrueType {};
00225 template<class ContainerAllocator>
00226 struct MD5Sum< ::srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> > {
00227 static const char* value()
00228 {
00229 return "d7be0bb39af8fb9129d5a76e6b63a290";
00230 }
00231
00232 static const char* value(const ::srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> &) { return value(); }
00233 static const uint64_t static_value1 = 0xd7be0bb39af8fb91ULL;
00234 static const uint64_t static_value2 = 0x29d5a76e6b63a290ULL;
00235 };
00236
00237 template<class ContainerAllocator>
00238 struct DataType< ::srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> > {
00239 static const char* value()
00240 {
00241 return "srs_env_model_percp/ClearPlanesRequest";
00242 }
00243
00244 static const char* value(const ::srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> &) { return value(); }
00245 };
00246
00247 template<class ContainerAllocator>
00248 struct Definition< ::srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> > {
00249 static const char* value()
00250 {
00251 return "\n\
00252 \n\
00253 Header header\n\
00254 \n\
00255 \n\
00256 ================================================================================\n\
00257 MSG: std_msgs/Header\n\
00258 # Standard metadata for higher-level stamped data types.\n\
00259 # This is generally used to communicate timestamped data \n\
00260 # in a particular coordinate frame.\n\
00261 # \n\
00262 # sequence ID: consecutively increasing ID \n\
00263 uint32 seq\n\
00264 #Two-integer timestamp that is expressed as:\n\
00265 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00266 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00267 # time-handling sugar is provided by the client library\n\
00268 time stamp\n\
00269 #Frame this data is associated with\n\
00270 # 0: no frame\n\
00271 # 1: global frame\n\
00272 string frame_id\n\
00273 \n\
00274 ";
00275 }
00276
00277 static const char* value(const ::srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> &) { return value(); }
00278 };
00279
00280 template<class ContainerAllocator> struct HasHeader< ::srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> > : public TrueType {};
00281 template<class ContainerAllocator> struct HasHeader< const ::srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> > : public TrueType {};
00282 }
00283 }
00284
00285
00286 namespace ros
00287 {
00288 namespace message_traits
00289 {
00290 template<class ContainerAllocator> struct IsMessage< ::srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> > : public TrueType {};
00291 template<class ContainerAllocator> struct IsMessage< ::srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> const> : public TrueType {};
00292 template<class ContainerAllocator>
00293 struct MD5Sum< ::srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> > {
00294 static const char* value()
00295 {
00296 return "5f003d6bcc824cbd51361d66d8e4f76c";
00297 }
00298
00299 static const char* value(const ::srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> &) { return value(); }
00300 static const uint64_t static_value1 = 0x5f003d6bcc824cbdULL;
00301 static const uint64_t static_value2 = 0x51361d66d8e4f76cULL;
00302 };
00303
00304 template<class ContainerAllocator>
00305 struct DataType< ::srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> > {
00306 static const char* value()
00307 {
00308 return "srs_env_model_percp/ClearPlanesResponse";
00309 }
00310
00311 static const char* value(const ::srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> &) { return value(); }
00312 };
00313
00314 template<class ContainerAllocator>
00315 struct Definition< ::srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> > {
00316 static const char* value()
00317 {
00318 return "\n\
00319 \n\
00320 \n\
00321 string message\n\
00322 \n\
00323 ";
00324 }
00325
00326 static const char* value(const ::srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> &) { return value(); }
00327 };
00328
00329 }
00330 }
00331
00332 namespace ros
00333 {
00334 namespace serialization
00335 {
00336
00337 template<class ContainerAllocator> struct Serializer< ::srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> >
00338 {
00339 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00340 {
00341 stream.next(m.header);
00342 }
00343
00344 ROS_DECLARE_ALLINONE_SERIALIZER;
00345 };
00346 }
00347 }
00348
00349
00350 namespace ros
00351 {
00352 namespace serialization
00353 {
00354
00355 template<class ContainerAllocator> struct Serializer< ::srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> >
00356 {
00357 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00358 {
00359 stream.next(m.message);
00360 }
00361
00362 ROS_DECLARE_ALLINONE_SERIALIZER;
00363 };
00364 }
00365 }
00366
00367 namespace ros
00368 {
00369 namespace service_traits
00370 {
00371 template<>
00372 struct MD5Sum<srs_env_model_percp::ClearPlanes> {
00373 static const char* value()
00374 {
00375 return "2198c46fe39dc9af0a46ecd66c4a97ea";
00376 }
00377
00378 static const char* value(const srs_env_model_percp::ClearPlanes&) { return value(); }
00379 };
00380
00381 template<>
00382 struct DataType<srs_env_model_percp::ClearPlanes> {
00383 static const char* value()
00384 {
00385 return "srs_env_model_percp/ClearPlanes";
00386 }
00387
00388 static const char* value(const srs_env_model_percp::ClearPlanes&) { return value(); }
00389 };
00390
00391 template<class ContainerAllocator>
00392 struct MD5Sum<srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> > {
00393 static const char* value()
00394 {
00395 return "2198c46fe39dc9af0a46ecd66c4a97ea";
00396 }
00397
00398 static const char* value(const srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> &) { return value(); }
00399 };
00400
00401 template<class ContainerAllocator>
00402 struct DataType<srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> > {
00403 static const char* value()
00404 {
00405 return "srs_env_model_percp/ClearPlanes";
00406 }
00407
00408 static const char* value(const srs_env_model_percp::ClearPlanesRequest_<ContainerAllocator> &) { return value(); }
00409 };
00410
00411 template<class ContainerAllocator>
00412 struct MD5Sum<srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> > {
00413 static const char* value()
00414 {
00415 return "2198c46fe39dc9af0a46ecd66c4a97ea";
00416 }
00417
00418 static const char* value(const srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> &) { return value(); }
00419 };
00420
00421 template<class ContainerAllocator>
00422 struct DataType<srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> > {
00423 static const char* value()
00424 {
00425 return "srs_env_model_percp/ClearPlanes";
00426 }
00427
00428 static const char* value(const srs_env_model_percp::ClearPlanesResponse_<ContainerAllocator> &) { return value(); }
00429 };
00430
00431 }
00432 }
00433
00434 #endif // SRS_ENV_MODEL_PERCP_SERVICE_CLEARPLANES_H
00435