Go to the documentation of this file.00001
00002 #ifndef VISION_SRVS_SERVICE_CLIP_POLYGON_H
00003 #define VISION_SRVS_SERVICE_CLIP_POLYGON_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/Polygon.h"
00020 #include "geometry_msgs/Polygon.h"
00021
00022
00023 #include "geometry_msgs/Polygon.h"
00024
00025 namespace vision_srvs
00026 {
00027 template <class ContainerAllocator>
00028 struct clip_polygonRequest_ {
00029 typedef clip_polygonRequest_<ContainerAllocator> Type;
00030
00031 clip_polygonRequest_()
00032 : operation(0)
00033 , poly1()
00034 , poly2()
00035 {
00036 }
00037
00038 clip_polygonRequest_(const ContainerAllocator& _alloc)
00039 : operation(0)
00040 , poly1(_alloc)
00041 , poly2(_alloc)
00042 {
00043 }
00044
00045 typedef uint32_t _operation_type;
00046 uint32_t operation;
00047
00048 typedef ::geometry_msgs::Polygon_<ContainerAllocator> _poly1_type;
00049 ::geometry_msgs::Polygon_<ContainerAllocator> poly1;
00050
00051 typedef ::geometry_msgs::Polygon_<ContainerAllocator> _poly2_type;
00052 ::geometry_msgs::Polygon_<ContainerAllocator> poly2;
00053
00054 enum { UNION = 0 };
00055 enum { INTERSECTION = 1 };
00056
00057 typedef boost::shared_ptr< ::vision_srvs::clip_polygonRequest_<ContainerAllocator> > Ptr;
00058 typedef boost::shared_ptr< ::vision_srvs::clip_polygonRequest_<ContainerAllocator> const> ConstPtr;
00059 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00060 };
00061 typedef ::vision_srvs::clip_polygonRequest_<std::allocator<void> > clip_polygonRequest;
00062
00063 typedef boost::shared_ptr< ::vision_srvs::clip_polygonRequest> clip_polygonRequestPtr;
00064 typedef boost::shared_ptr< ::vision_srvs::clip_polygonRequest const> clip_polygonRequestConstPtr;
00065
00066
00067
00068 template <class ContainerAllocator>
00069 struct clip_polygonResponse_ {
00070 typedef clip_polygonResponse_<ContainerAllocator> Type;
00071
00072 clip_polygonResponse_()
00073 : poly_clip()
00074 {
00075 }
00076
00077 clip_polygonResponse_(const ContainerAllocator& _alloc)
00078 : poly_clip(_alloc)
00079 {
00080 }
00081
00082 typedef ::geometry_msgs::Polygon_<ContainerAllocator> _poly_clip_type;
00083 ::geometry_msgs::Polygon_<ContainerAllocator> poly_clip;
00084
00085
00086 typedef boost::shared_ptr< ::vision_srvs::clip_polygonResponse_<ContainerAllocator> > Ptr;
00087 typedef boost::shared_ptr< ::vision_srvs::clip_polygonResponse_<ContainerAllocator> const> ConstPtr;
00088 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00089 };
00090 typedef ::vision_srvs::clip_polygonResponse_<std::allocator<void> > clip_polygonResponse;
00091
00092 typedef boost::shared_ptr< ::vision_srvs::clip_polygonResponse> clip_polygonResponsePtr;
00093 typedef boost::shared_ptr< ::vision_srvs::clip_polygonResponse const> clip_polygonResponseConstPtr;
00094
00095
00096 struct clip_polygon
00097 {
00098
00099 typedef clip_polygonRequest Request;
00100 typedef clip_polygonResponse Response;
00101 Request request;
00102 Response response;
00103
00104 typedef Request RequestType;
00105 typedef Response ResponseType;
00106 };
00107 }
00108
00109 namespace ros
00110 {
00111 namespace message_traits
00112 {
00113 template<class ContainerAllocator> struct IsMessage< ::vision_srvs::clip_polygonRequest_<ContainerAllocator> > : public TrueType {};
00114 template<class ContainerAllocator> struct IsMessage< ::vision_srvs::clip_polygonRequest_<ContainerAllocator> const> : public TrueType {};
00115 template<class ContainerAllocator>
00116 struct MD5Sum< ::vision_srvs::clip_polygonRequest_<ContainerAllocator> > {
00117 static const char* value()
00118 {
00119 return "90ec19340207537b530d3a37f5d3aaff";
00120 }
00121
00122 static const char* value(const ::vision_srvs::clip_polygonRequest_<ContainerAllocator> &) { return value(); }
00123 static const uint64_t static_value1 = 0x90ec19340207537bULL;
00124 static const uint64_t static_value2 = 0x530d3a37f5d3aaffULL;
00125 };
00126
00127 template<class ContainerAllocator>
00128 struct DataType< ::vision_srvs::clip_polygonRequest_<ContainerAllocator> > {
00129 static const char* value()
00130 {
00131 return "vision_srvs/clip_polygonRequest";
00132 }
00133
00134 static const char* value(const ::vision_srvs::clip_polygonRequest_<ContainerAllocator> &) { return value(); }
00135 };
00136
00137 template<class ContainerAllocator>
00138 struct Definition< ::vision_srvs::clip_polygonRequest_<ContainerAllocator> > {
00139 static const char* value()
00140 {
00141 return "uint32 UNION = 0\n\
00142 uint32 INTERSECTION = 1\n\
00143 uint32 operation\n\
00144 geometry_msgs/Polygon poly1\n\
00145 geometry_msgs/Polygon poly2\n\
00146 \n\
00147 ================================================================================\n\
00148 MSG: geometry_msgs/Polygon\n\
00149 #A specification of a polygon where the first and last points are assumed to be connected\n\
00150 Point32[] points\n\
00151 \n\
00152 ================================================================================\n\
00153 MSG: geometry_msgs/Point32\n\
00154 # This contains the position of a point in free space(with 32 bits of precision).\n\
00155 # It is recommeded to use Point wherever possible instead of Point32. \n\
00156 # \n\
00157 # This recommendation is to promote interoperability. \n\
00158 #\n\
00159 # This message is designed to take up less space when sending\n\
00160 # lots of points at once, as in the case of a PointCloud. \n\
00161 \n\
00162 float32 x\n\
00163 float32 y\n\
00164 float32 z\n\
00165 ";
00166 }
00167
00168 static const char* value(const ::vision_srvs::clip_polygonRequest_<ContainerAllocator> &) { return value(); }
00169 };
00170
00171 }
00172 }
00173
00174
00175 namespace ros
00176 {
00177 namespace message_traits
00178 {
00179 template<class ContainerAllocator> struct IsMessage< ::vision_srvs::clip_polygonResponse_<ContainerAllocator> > : public TrueType {};
00180 template<class ContainerAllocator> struct IsMessage< ::vision_srvs::clip_polygonResponse_<ContainerAllocator> const> : public TrueType {};
00181 template<class ContainerAllocator>
00182 struct MD5Sum< ::vision_srvs::clip_polygonResponse_<ContainerAllocator> > {
00183 static const char* value()
00184 {
00185 return "8ac99714bd719c813589b0f74ded28d5";
00186 }
00187
00188 static const char* value(const ::vision_srvs::clip_polygonResponse_<ContainerAllocator> &) { return value(); }
00189 static const uint64_t static_value1 = 0x8ac99714bd719c81ULL;
00190 static const uint64_t static_value2 = 0x3589b0f74ded28d5ULL;
00191 };
00192
00193 template<class ContainerAllocator>
00194 struct DataType< ::vision_srvs::clip_polygonResponse_<ContainerAllocator> > {
00195 static const char* value()
00196 {
00197 return "vision_srvs/clip_polygonResponse";
00198 }
00199
00200 static const char* value(const ::vision_srvs::clip_polygonResponse_<ContainerAllocator> &) { return value(); }
00201 };
00202
00203 template<class ContainerAllocator>
00204 struct Definition< ::vision_srvs::clip_polygonResponse_<ContainerAllocator> > {
00205 static const char* value()
00206 {
00207 return "geometry_msgs/Polygon poly_clip\n\
00208 \n\
00209 \n\
00210 ================================================================================\n\
00211 MSG: geometry_msgs/Polygon\n\
00212 #A specification of a polygon where the first and last points are assumed to be connected\n\
00213 Point32[] points\n\
00214 \n\
00215 ================================================================================\n\
00216 MSG: geometry_msgs/Point32\n\
00217 # This contains the position of a point in free space(with 32 bits of precision).\n\
00218 # It is recommeded to use Point wherever possible instead of Point32. \n\
00219 # \n\
00220 # This recommendation is to promote interoperability. \n\
00221 #\n\
00222 # This message is designed to take up less space when sending\n\
00223 # lots of points at once, as in the case of a PointCloud. \n\
00224 \n\
00225 float32 x\n\
00226 float32 y\n\
00227 float32 z\n\
00228 ";
00229 }
00230
00231 static const char* value(const ::vision_srvs::clip_polygonResponse_<ContainerAllocator> &) { return value(); }
00232 };
00233
00234 }
00235 }
00236
00237 namespace ros
00238 {
00239 namespace serialization
00240 {
00241
00242 template<class ContainerAllocator> struct Serializer< ::vision_srvs::clip_polygonRequest_<ContainerAllocator> >
00243 {
00244 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00245 {
00246 stream.next(m.operation);
00247 stream.next(m.poly1);
00248 stream.next(m.poly2);
00249 }
00250
00251 ROS_DECLARE_ALLINONE_SERIALIZER;
00252 };
00253 }
00254 }
00255
00256
00257 namespace ros
00258 {
00259 namespace serialization
00260 {
00261
00262 template<class ContainerAllocator> struct Serializer< ::vision_srvs::clip_polygonResponse_<ContainerAllocator> >
00263 {
00264 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00265 {
00266 stream.next(m.poly_clip);
00267 }
00268
00269 ROS_DECLARE_ALLINONE_SERIALIZER;
00270 };
00271 }
00272 }
00273
00274 namespace ros
00275 {
00276 namespace service_traits
00277 {
00278 template<>
00279 struct MD5Sum<vision_srvs::clip_polygon> {
00280 static const char* value()
00281 {
00282 return "833de208811dbf84e2b0e6af79d60331";
00283 }
00284
00285 static const char* value(const vision_srvs::clip_polygon&) { return value(); }
00286 };
00287
00288 template<>
00289 struct DataType<vision_srvs::clip_polygon> {
00290 static const char* value()
00291 {
00292 return "vision_srvs/clip_polygon";
00293 }
00294
00295 static const char* value(const vision_srvs::clip_polygon&) { return value(); }
00296 };
00297
00298 template<class ContainerAllocator>
00299 struct MD5Sum<vision_srvs::clip_polygonRequest_<ContainerAllocator> > {
00300 static const char* value()
00301 {
00302 return "833de208811dbf84e2b0e6af79d60331";
00303 }
00304
00305 static const char* value(const vision_srvs::clip_polygonRequest_<ContainerAllocator> &) { return value(); }
00306 };
00307
00308 template<class ContainerAllocator>
00309 struct DataType<vision_srvs::clip_polygonRequest_<ContainerAllocator> > {
00310 static const char* value()
00311 {
00312 return "vision_srvs/clip_polygon";
00313 }
00314
00315 static const char* value(const vision_srvs::clip_polygonRequest_<ContainerAllocator> &) { return value(); }
00316 };
00317
00318 template<class ContainerAllocator>
00319 struct MD5Sum<vision_srvs::clip_polygonResponse_<ContainerAllocator> > {
00320 static const char* value()
00321 {
00322 return "833de208811dbf84e2b0e6af79d60331";
00323 }
00324
00325 static const char* value(const vision_srvs::clip_polygonResponse_<ContainerAllocator> &) { return value(); }
00326 };
00327
00328 template<class ContainerAllocator>
00329 struct DataType<vision_srvs::clip_polygonResponse_<ContainerAllocator> > {
00330 static const char* value()
00331 {
00332 return "vision_srvs/clip_polygon";
00333 }
00334
00335 static const char* value(const vision_srvs::clip_polygonResponse_<ContainerAllocator> &) { return value(); }
00336 };
00337
00338 }
00339 }
00340
00341 #endif // VISION_SRVS_SERVICE_CLIP_POLYGON_H
00342