Go to the documentation of this file.00001
00002 #ifndef FAST_PLANE_DETECTION_SERVICE_PLANEINREGION_H
00003 #define FAST_PLANE_DETECTION_SERVICE_PLANEINREGION_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/Vector3Stamped.h"
00020
00021
00022 #include "fast_plane_detection/Plane.h"
00023
00024 namespace fast_plane_detection
00025 {
00026 template <class ContainerAllocator>
00027 struct PlaneInRegionRequest_ {
00028 typedef PlaneInRegionRequest_<ContainerAllocator> Type;
00029
00030 PlaneInRegionRequest_()
00031 : point()
00032 , width(0)
00033 , height(0)
00034 {
00035 }
00036
00037 PlaneInRegionRequest_(const ContainerAllocator& _alloc)
00038 : point(_alloc)
00039 , width(0)
00040 , height(0)
00041 {
00042 }
00043
00044 typedef ::geometry_msgs::Vector3Stamped_<ContainerAllocator> _point_type;
00045 ::geometry_msgs::Vector3Stamped_<ContainerAllocator> point;
00046
00047 typedef int64_t _width_type;
00048 int64_t width;
00049
00050 typedef int64_t _height_type;
00051 int64_t height;
00052
00053
00054 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > Ptr;
00055 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> const> ConstPtr;
00056 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00057 };
00058 typedef ::fast_plane_detection::PlaneInRegionRequest_<std::allocator<void> > PlaneInRegionRequest;
00059
00060 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionRequest> PlaneInRegionRequestPtr;
00061 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionRequest const> PlaneInRegionRequestConstPtr;
00062
00063
00064 template <class ContainerAllocator>
00065 struct PlaneInRegionResponse_ {
00066 typedef PlaneInRegionResponse_<ContainerAllocator> Type;
00067
00068 PlaneInRegionResponse_()
00069 : plane()
00070 {
00071 }
00072
00073 PlaneInRegionResponse_(const ContainerAllocator& _alloc)
00074 : plane(_alloc)
00075 {
00076 }
00077
00078 typedef ::fast_plane_detection::Plane_<ContainerAllocator> _plane_type;
00079 ::fast_plane_detection::Plane_<ContainerAllocator> plane;
00080
00081
00082 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > Ptr;
00083 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> const> ConstPtr;
00084 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00085 };
00086 typedef ::fast_plane_detection::PlaneInRegionResponse_<std::allocator<void> > PlaneInRegionResponse;
00087
00088 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionResponse> PlaneInRegionResponsePtr;
00089 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionResponse const> PlaneInRegionResponseConstPtr;
00090
00091 struct PlaneInRegion
00092 {
00093
00094 typedef PlaneInRegionRequest Request;
00095 typedef PlaneInRegionResponse Response;
00096 Request request;
00097 Response response;
00098
00099 typedef Request RequestType;
00100 typedef Response ResponseType;
00101 };
00102 }
00103
00104 namespace ros
00105 {
00106 namespace message_traits
00107 {
00108 template<class ContainerAllocator> struct IsMessage< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > : public TrueType {};
00109 template<class ContainerAllocator> struct IsMessage< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> const> : public TrueType {};
00110 template<class ContainerAllocator>
00111 struct MD5Sum< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > {
00112 static const char* value()
00113 {
00114 return "7d70c4a3215f16e600ab2fb0a95d82d8";
00115 }
00116
00117 static const char* value(const ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> &) { return value(); }
00118 static const uint64_t static_value1 = 0x7d70c4a3215f16e6ULL;
00119 static const uint64_t static_value2 = 0x00ab2fb0a95d82d8ULL;
00120 };
00121
00122 template<class ContainerAllocator>
00123 struct DataType< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > {
00124 static const char* value()
00125 {
00126 return "fast_plane_detection/PlaneInRegionRequest";
00127 }
00128
00129 static const char* value(const ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> &) { return value(); }
00130 };
00131
00132 template<class ContainerAllocator>
00133 struct Definition< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > {
00134 static const char* value()
00135 {
00136 return "\n\
00137 \n\
00138 \n\
00139 geometry_msgs/Vector3Stamped point\n\
00140 \n\
00141 int64 width\n\
00142 int64 height\n\
00143 \n\
00144 \n\
00145 ================================================================================\n\
00146 MSG: geometry_msgs/Vector3Stamped\n\
00147 # This represents a Vector3 with reference coordinate frame and timestamp\n\
00148 Header header\n\
00149 Vector3 vector\n\
00150 \n\
00151 ================================================================================\n\
00152 MSG: std_msgs/Header\n\
00153 # Standard metadata for higher-level stamped data types.\n\
00154 # This is generally used to communicate timestamped data \n\
00155 # in a particular coordinate frame.\n\
00156 # \n\
00157 # sequence ID: consecutively increasing ID \n\
00158 uint32 seq\n\
00159 #Two-integer timestamp that is expressed as:\n\
00160 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00161 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00162 # time-handling sugar is provided by the client library\n\
00163 time stamp\n\
00164 #Frame this data is associated with\n\
00165 # 0: no frame\n\
00166 # 1: global frame\n\
00167 string frame_id\n\
00168 \n\
00169 ================================================================================\n\
00170 MSG: geometry_msgs/Vector3\n\
00171 # This represents a vector in free space. \n\
00172 \n\
00173 float64 x\n\
00174 float64 y\n\
00175 float64 z\n\
00176 ";
00177 }
00178
00179 static const char* value(const ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> &) { return value(); }
00180 };
00181
00182 }
00183 }
00184
00185
00186 namespace ros
00187 {
00188 namespace message_traits
00189 {
00190 template<class ContainerAllocator> struct IsMessage< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > : public TrueType {};
00191 template<class ContainerAllocator> struct IsMessage< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> const> : public TrueType {};
00192 template<class ContainerAllocator>
00193 struct MD5Sum< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > {
00194 static const char* value()
00195 {
00196 return "e716cc2181996b312d7f1ee1e64fa78a";
00197 }
00198
00199 static const char* value(const ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> &) { return value(); }
00200 static const uint64_t static_value1 = 0xe716cc2181996b31ULL;
00201 static const uint64_t static_value2 = 0x2d7f1ee1e64fa78aULL;
00202 };
00203
00204 template<class ContainerAllocator>
00205 struct DataType< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > {
00206 static const char* value()
00207 {
00208 return "fast_plane_detection/PlaneInRegionResponse";
00209 }
00210
00211 static const char* value(const ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> &) { return value(); }
00212 };
00213
00214 template<class ContainerAllocator>
00215 struct Definition< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > {
00216 static const char* value()
00217 {
00218 return "\n\
00219 fast_plane_detection/Plane plane\n\
00220 \n\
00221 \n\
00222 ================================================================================\n\
00223 MSG: fast_plane_detection/Plane\n\
00224 # Informs that a plane has been detected at a given location\n\
00225 \n\
00226 # The pose gives you the transform that take you to the coordinate system\n\
00227 # of the plane, with the origin somewhere in the plane and the \n\
00228 # z axis normal to the plane\n\
00229 geometry_msgs/PoseStamped pose\n\
00230 \n\
00231 # Point + normal vector of the plane\n\
00232 geometry_msgs/PointStamped plane_point\n\
00233 geometry_msgs/Vector3Stamped normal\n\
00234 geometry_msgs/PointStamped slave_point\n\
00235 \n\
00236 # These values give you the observed extents of the plane, along x and y,\n\
00237 # in the plane's own coordinate system (above)\n\
00238 # there is no guarantee that the origin of the plane coordinate system is\n\
00239 # inside the boundary defined by these values. \n\
00240 geometry_msgs/Point32 top_left\n\
00241 geometry_msgs/Point32 top_right\n\
00242 \n\
00243 geometry_msgs/Point32 bottom_left\n\
00244 geometry_msgs/Point32 bottom_right\n\
00245 \n\
00246 # There is no guarantee that the plane doe NOT extend further than these \n\
00247 # values; this is just as far as we've observed it.\n\
00248 \n\
00249 # Whether the detection has succeeded or failed\n\
00250 int32 SUCCESS = 1\n\
00251 int32 FEW_INLIERS = 2\n\
00252 int32 NO_PLANE = 3\n\
00253 int32 OTHER_ERROR = 4\n\
00254 int32 result\n\
00255 \n\
00256 # inliers over whole region\n\
00257 float32 percentage_inliers\n\
00258 # inliers of valid disparities\n\
00259 int32 percentage_disp_inliers\n\
00260 # number of valid disparities\n\
00261 int32 percentage_valid_disp\n\
00262 \n\
00263 # confidence indicators of plane detection\n\
00264 # mean squared error\n\
00265 float32 error\n\
00266 \n\
00267 ================================================================================\n\
00268 MSG: geometry_msgs/PoseStamped\n\
00269 # A Pose with reference coordinate frame and timestamp\n\
00270 Header header\n\
00271 Pose pose\n\
00272 \n\
00273 ================================================================================\n\
00274 MSG: std_msgs/Header\n\
00275 # Standard metadata for higher-level stamped data types.\n\
00276 # This is generally used to communicate timestamped data \n\
00277 # in a particular coordinate frame.\n\
00278 # \n\
00279 # sequence ID: consecutively increasing ID \n\
00280 uint32 seq\n\
00281 #Two-integer timestamp that is expressed as:\n\
00282 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00283 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00284 # time-handling sugar is provided by the client library\n\
00285 time stamp\n\
00286 #Frame this data is associated with\n\
00287 # 0: no frame\n\
00288 # 1: global frame\n\
00289 string frame_id\n\
00290 \n\
00291 ================================================================================\n\
00292 MSG: geometry_msgs/Pose\n\
00293 # A representation of pose in free space, composed of postion and orientation. \n\
00294 Point position\n\
00295 Quaternion orientation\n\
00296 \n\
00297 ================================================================================\n\
00298 MSG: geometry_msgs/Point\n\
00299 # This contains the position of a point in free space\n\
00300 float64 x\n\
00301 float64 y\n\
00302 float64 z\n\
00303 \n\
00304 ================================================================================\n\
00305 MSG: geometry_msgs/Quaternion\n\
00306 # This represents an orientation in free space in quaternion form.\n\
00307 \n\
00308 float64 x\n\
00309 float64 y\n\
00310 float64 z\n\
00311 float64 w\n\
00312 \n\
00313 ================================================================================\n\
00314 MSG: geometry_msgs/PointStamped\n\
00315 # This represents a Point with reference coordinate frame and timestamp\n\
00316 Header header\n\
00317 Point point\n\
00318 \n\
00319 ================================================================================\n\
00320 MSG: geometry_msgs/Vector3Stamped\n\
00321 # This represents a Vector3 with reference coordinate frame and timestamp\n\
00322 Header header\n\
00323 Vector3 vector\n\
00324 \n\
00325 ================================================================================\n\
00326 MSG: geometry_msgs/Vector3\n\
00327 # This represents a vector in free space. \n\
00328 \n\
00329 float64 x\n\
00330 float64 y\n\
00331 float64 z\n\
00332 ================================================================================\n\
00333 MSG: geometry_msgs/Point32\n\
00334 # This contains the position of a point in free space(with 32 bits of precision).\n\
00335 # It is recommeded to use Point wherever possible instead of Point32. \n\
00336 # \n\
00337 # This recommendation is to promote interoperability. \n\
00338 #\n\
00339 # This message is designed to take up less space when sending\n\
00340 # lots of points at once, as in the case of a PointCloud. \n\
00341 \n\
00342 float32 x\n\
00343 float32 y\n\
00344 float32 z\n\
00345 ";
00346 }
00347
00348 static const char* value(const ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> &) { return value(); }
00349 };
00350
00351 }
00352 }
00353
00354 namespace ros
00355 {
00356 namespace serialization
00357 {
00358
00359 template<class ContainerAllocator> struct Serializer< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> >
00360 {
00361 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00362 {
00363 stream.next(m.point);
00364 stream.next(m.width);
00365 stream.next(m.height);
00366 }
00367
00368 ROS_DECLARE_ALLINONE_SERIALIZER;
00369 };
00370 }
00371 }
00372
00373
00374 namespace ros
00375 {
00376 namespace serialization
00377 {
00378
00379 template<class ContainerAllocator> struct Serializer< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> >
00380 {
00381 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00382 {
00383 stream.next(m.plane);
00384 }
00385
00386 ROS_DECLARE_ALLINONE_SERIALIZER;
00387 };
00388 }
00389 }
00390
00391 namespace ros
00392 {
00393 namespace service_traits
00394 {
00395 template<>
00396 struct MD5Sum<fast_plane_detection::PlaneInRegion> {
00397 static const char* value()
00398 {
00399 return "af4f32849bccef799b668b077c0a80c7";
00400 }
00401
00402 static const char* value(const fast_plane_detection::PlaneInRegion&) { return value(); }
00403 };
00404
00405 template<>
00406 struct DataType<fast_plane_detection::PlaneInRegion> {
00407 static const char* value()
00408 {
00409 return "fast_plane_detection/PlaneInRegion";
00410 }
00411
00412 static const char* value(const fast_plane_detection::PlaneInRegion&) { return value(); }
00413 };
00414
00415 template<class ContainerAllocator>
00416 struct MD5Sum<fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > {
00417 static const char* value()
00418 {
00419 return "af4f32849bccef799b668b077c0a80c7";
00420 }
00421
00422 static const char* value(const fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> &) { return value(); }
00423 };
00424
00425 template<class ContainerAllocator>
00426 struct DataType<fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > {
00427 static const char* value()
00428 {
00429 return "fast_plane_detection/PlaneInRegion";
00430 }
00431
00432 static const char* value(const fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> &) { return value(); }
00433 };
00434
00435 template<class ContainerAllocator>
00436 struct MD5Sum<fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > {
00437 static const char* value()
00438 {
00439 return "af4f32849bccef799b668b077c0a80c7";
00440 }
00441
00442 static const char* value(const fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> &) { return value(); }
00443 };
00444
00445 template<class ContainerAllocator>
00446 struct DataType<fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > {
00447 static const char* value()
00448 {
00449 return "fast_plane_detection/PlaneInRegion";
00450 }
00451
00452 static const char* value(const fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> &) { return value(); }
00453 };
00454
00455 }
00456 }
00457
00458 #endif // FAST_PLANE_DETECTION_SERVICE_PLANEINREGION_H
00459