$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-pr2_object_manipulation/doc_stacks/2013-03-05_12-10-38.333207/pr2_object_manipulation/perception/fast_plane_detection/srv/PlaneInRegion.srv */ 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 private: 00055 static const char* __s_getDataType_() { return "fast_plane_detection/PlaneInRegionRequest"; } 00056 public: 00057 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00058 00059 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00060 00061 private: 00062 static const char* __s_getMD5Sum_() { return "7d70c4a3215f16e600ab2fb0a95d82d8"; } 00063 public: 00064 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00065 00066 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00067 00068 private: 00069 static const char* __s_getServerMD5Sum_() { return "af4f32849bccef799b668b077c0a80c7"; } 00070 public: 00071 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00072 00073 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00074 00075 private: 00076 static const char* __s_getMessageDefinition_() { return "\n\ 00077 \n\ 00078 \n\ 00079 geometry_msgs/Vector3Stamped point\n\ 00080 \n\ 00081 int64 width\n\ 00082 int64 height\n\ 00083 \n\ 00084 \n\ 00085 ================================================================================\n\ 00086 MSG: geometry_msgs/Vector3Stamped\n\ 00087 # This represents a Vector3 with reference coordinate frame and timestamp\n\ 00088 Header header\n\ 00089 Vector3 vector\n\ 00090 \n\ 00091 ================================================================================\n\ 00092 MSG: std_msgs/Header\n\ 00093 # Standard metadata for higher-level stamped data types.\n\ 00094 # This is generally used to communicate timestamped data \n\ 00095 # in a particular coordinate frame.\n\ 00096 # \n\ 00097 # sequence ID: consecutively increasing ID \n\ 00098 uint32 seq\n\ 00099 #Two-integer timestamp that is expressed as:\n\ 00100 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00101 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00102 # time-handling sugar is provided by the client library\n\ 00103 time stamp\n\ 00104 #Frame this data is associated with\n\ 00105 # 0: no frame\n\ 00106 # 1: global frame\n\ 00107 string frame_id\n\ 00108 \n\ 00109 ================================================================================\n\ 00110 MSG: geometry_msgs/Vector3\n\ 00111 # This represents a vector in free space. \n\ 00112 \n\ 00113 float64 x\n\ 00114 float64 y\n\ 00115 float64 z\n\ 00116 "; } 00117 public: 00118 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00119 00120 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00121 00122 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00123 { 00124 ros::serialization::OStream stream(write_ptr, 1000000000); 00125 ros::serialization::serialize(stream, point); 00126 ros::serialization::serialize(stream, width); 00127 ros::serialization::serialize(stream, height); 00128 return stream.getData(); 00129 } 00130 00131 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00132 { 00133 ros::serialization::IStream stream(read_ptr, 1000000000); 00134 ros::serialization::deserialize(stream, point); 00135 ros::serialization::deserialize(stream, width); 00136 ros::serialization::deserialize(stream, height); 00137 return stream.getData(); 00138 } 00139 00140 ROS_DEPRECATED virtual uint32_t serializationLength() const 00141 { 00142 uint32_t size = 0; 00143 size += ros::serialization::serializationLength(point); 00144 size += ros::serialization::serializationLength(width); 00145 size += ros::serialization::serializationLength(height); 00146 return size; 00147 } 00148 00149 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > Ptr; 00150 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> const> ConstPtr; 00151 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00152 }; // struct PlaneInRegionRequest 00153 typedef ::fast_plane_detection::PlaneInRegionRequest_<std::allocator<void> > PlaneInRegionRequest; 00154 00155 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionRequest> PlaneInRegionRequestPtr; 00156 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionRequest const> PlaneInRegionRequestConstPtr; 00157 00158 00159 template <class ContainerAllocator> 00160 struct PlaneInRegionResponse_ { 00161 typedef PlaneInRegionResponse_<ContainerAllocator> Type; 00162 00163 PlaneInRegionResponse_() 00164 : plane() 00165 { 00166 } 00167 00168 PlaneInRegionResponse_(const ContainerAllocator& _alloc) 00169 : plane(_alloc) 00170 { 00171 } 00172 00173 typedef ::fast_plane_detection::Plane_<ContainerAllocator> _plane_type; 00174 ::fast_plane_detection::Plane_<ContainerAllocator> plane; 00175 00176 00177 private: 00178 static const char* __s_getDataType_() { return "fast_plane_detection/PlaneInRegionResponse"; } 00179 public: 00180 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00181 00182 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00183 00184 private: 00185 static const char* __s_getMD5Sum_() { return "e716cc2181996b312d7f1ee1e64fa78a"; } 00186 public: 00187 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00188 00189 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00190 00191 private: 00192 static const char* __s_getServerMD5Sum_() { return "af4f32849bccef799b668b077c0a80c7"; } 00193 public: 00194 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00195 00196 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00197 00198 private: 00199 static const char* __s_getMessageDefinition_() { return "\n\ 00200 fast_plane_detection/Plane plane\n\ 00201 \n\ 00202 \n\ 00203 ================================================================================\n\ 00204 MSG: fast_plane_detection/Plane\n\ 00205 # Informs that a plane has been detected at a given location\n\ 00206 \n\ 00207 # The pose gives you the transform that take you to the coordinate system\n\ 00208 # of the plane, with the origin somewhere in the plane and the \n\ 00209 # z axis normal to the plane\n\ 00210 geometry_msgs/PoseStamped pose\n\ 00211 \n\ 00212 # Point + normal vector of the plane\n\ 00213 geometry_msgs/PointStamped plane_point\n\ 00214 geometry_msgs/Vector3Stamped normal\n\ 00215 geometry_msgs/PointStamped slave_point\n\ 00216 \n\ 00217 # These values give you the observed extents of the plane, along x and y,\n\ 00218 # in the plane's own coordinate system (above)\n\ 00219 # there is no guarantee that the origin of the plane coordinate system is\n\ 00220 # inside the boundary defined by these values. \n\ 00221 geometry_msgs/Point32 top_left\n\ 00222 geometry_msgs/Point32 top_right\n\ 00223 \n\ 00224 geometry_msgs/Point32 bottom_left\n\ 00225 geometry_msgs/Point32 bottom_right\n\ 00226 \n\ 00227 # There is no guarantee that the plane doe NOT extend further than these \n\ 00228 # values; this is just as far as we've observed it.\n\ 00229 \n\ 00230 # Whether the detection has succeeded or failed\n\ 00231 int32 SUCCESS = 1\n\ 00232 int32 FEW_INLIERS = 2\n\ 00233 int32 NO_PLANE = 3\n\ 00234 int32 OTHER_ERROR = 4\n\ 00235 int32 result\n\ 00236 \n\ 00237 # inliers over whole region\n\ 00238 float32 percentage_inliers\n\ 00239 # inliers of valid disparities\n\ 00240 int32 percentage_disp_inliers\n\ 00241 # number of valid disparities\n\ 00242 int32 percentage_valid_disp\n\ 00243 \n\ 00244 # confidence indicators of plane detection\n\ 00245 # mean squared error\n\ 00246 float32 error\n\ 00247 \n\ 00248 ================================================================================\n\ 00249 MSG: geometry_msgs/PoseStamped\n\ 00250 # A Pose with reference coordinate frame and timestamp\n\ 00251 Header header\n\ 00252 Pose pose\n\ 00253 \n\ 00254 ================================================================================\n\ 00255 MSG: std_msgs/Header\n\ 00256 # Standard metadata for higher-level stamped data types.\n\ 00257 # This is generally used to communicate timestamped data \n\ 00258 # in a particular coordinate frame.\n\ 00259 # \n\ 00260 # sequence ID: consecutively increasing ID \n\ 00261 uint32 seq\n\ 00262 #Two-integer timestamp that is expressed as:\n\ 00263 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00264 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00265 # time-handling sugar is provided by the client library\n\ 00266 time stamp\n\ 00267 #Frame this data is associated with\n\ 00268 # 0: no frame\n\ 00269 # 1: global frame\n\ 00270 string frame_id\n\ 00271 \n\ 00272 ================================================================================\n\ 00273 MSG: geometry_msgs/Pose\n\ 00274 # A representation of pose in free space, composed of postion and orientation. \n\ 00275 Point position\n\ 00276 Quaternion orientation\n\ 00277 \n\ 00278 ================================================================================\n\ 00279 MSG: geometry_msgs/Point\n\ 00280 # This contains the position of a point in free space\n\ 00281 float64 x\n\ 00282 float64 y\n\ 00283 float64 z\n\ 00284 \n\ 00285 ================================================================================\n\ 00286 MSG: geometry_msgs/Quaternion\n\ 00287 # This represents an orientation in free space in quaternion form.\n\ 00288 \n\ 00289 float64 x\n\ 00290 float64 y\n\ 00291 float64 z\n\ 00292 float64 w\n\ 00293 \n\ 00294 ================================================================================\n\ 00295 MSG: geometry_msgs/PointStamped\n\ 00296 # This represents a Point with reference coordinate frame and timestamp\n\ 00297 Header header\n\ 00298 Point point\n\ 00299 \n\ 00300 ================================================================================\n\ 00301 MSG: geometry_msgs/Vector3Stamped\n\ 00302 # This represents a Vector3 with reference coordinate frame and timestamp\n\ 00303 Header header\n\ 00304 Vector3 vector\n\ 00305 \n\ 00306 ================================================================================\n\ 00307 MSG: geometry_msgs/Vector3\n\ 00308 # This represents a vector in free space. \n\ 00309 \n\ 00310 float64 x\n\ 00311 float64 y\n\ 00312 float64 z\n\ 00313 ================================================================================\n\ 00314 MSG: geometry_msgs/Point32\n\ 00315 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00316 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00317 # \n\ 00318 # This recommendation is to promote interoperability. \n\ 00319 #\n\ 00320 # This message is designed to take up less space when sending\n\ 00321 # lots of points at once, as in the case of a PointCloud. \n\ 00322 \n\ 00323 float32 x\n\ 00324 float32 y\n\ 00325 float32 z\n\ 00326 "; } 00327 public: 00328 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00329 00330 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00331 00332 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00333 { 00334 ros::serialization::OStream stream(write_ptr, 1000000000); 00335 ros::serialization::serialize(stream, plane); 00336 return stream.getData(); 00337 } 00338 00339 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00340 { 00341 ros::serialization::IStream stream(read_ptr, 1000000000); 00342 ros::serialization::deserialize(stream, plane); 00343 return stream.getData(); 00344 } 00345 00346 ROS_DEPRECATED virtual uint32_t serializationLength() const 00347 { 00348 uint32_t size = 0; 00349 size += ros::serialization::serializationLength(plane); 00350 return size; 00351 } 00352 00353 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > Ptr; 00354 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> const> ConstPtr; 00355 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00356 }; // struct PlaneInRegionResponse 00357 typedef ::fast_plane_detection::PlaneInRegionResponse_<std::allocator<void> > PlaneInRegionResponse; 00358 00359 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionResponse> PlaneInRegionResponsePtr; 00360 typedef boost::shared_ptr< ::fast_plane_detection::PlaneInRegionResponse const> PlaneInRegionResponseConstPtr; 00361 00362 struct PlaneInRegion 00363 { 00364 00365 typedef PlaneInRegionRequest Request; 00366 typedef PlaneInRegionResponse Response; 00367 Request request; 00368 Response response; 00369 00370 typedef Request RequestType; 00371 typedef Response ResponseType; 00372 }; // struct PlaneInRegion 00373 } // namespace fast_plane_detection 00374 00375 namespace ros 00376 { 00377 namespace message_traits 00378 { 00379 template<class ContainerAllocator> struct IsMessage< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > : public TrueType {}; 00380 template<class ContainerAllocator> struct IsMessage< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> const> : public TrueType {}; 00381 template<class ContainerAllocator> 00382 struct MD5Sum< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > { 00383 static const char* value() 00384 { 00385 return "7d70c4a3215f16e600ab2fb0a95d82d8"; 00386 } 00387 00388 static const char* value(const ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> &) { return value(); } 00389 static const uint64_t static_value1 = 0x7d70c4a3215f16e6ULL; 00390 static const uint64_t static_value2 = 0x00ab2fb0a95d82d8ULL; 00391 }; 00392 00393 template<class ContainerAllocator> 00394 struct DataType< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > { 00395 static const char* value() 00396 { 00397 return "fast_plane_detection/PlaneInRegionRequest"; 00398 } 00399 00400 static const char* value(const ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> &) { return value(); } 00401 }; 00402 00403 template<class ContainerAllocator> 00404 struct Definition< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > { 00405 static const char* value() 00406 { 00407 return "\n\ 00408 \n\ 00409 \n\ 00410 geometry_msgs/Vector3Stamped point\n\ 00411 \n\ 00412 int64 width\n\ 00413 int64 height\n\ 00414 \n\ 00415 \n\ 00416 ================================================================================\n\ 00417 MSG: geometry_msgs/Vector3Stamped\n\ 00418 # This represents a Vector3 with reference coordinate frame and timestamp\n\ 00419 Header header\n\ 00420 Vector3 vector\n\ 00421 \n\ 00422 ================================================================================\n\ 00423 MSG: std_msgs/Header\n\ 00424 # Standard metadata for higher-level stamped data types.\n\ 00425 # This is generally used to communicate timestamped data \n\ 00426 # in a particular coordinate frame.\n\ 00427 # \n\ 00428 # sequence ID: consecutively increasing ID \n\ 00429 uint32 seq\n\ 00430 #Two-integer timestamp that is expressed as:\n\ 00431 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00432 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00433 # time-handling sugar is provided by the client library\n\ 00434 time stamp\n\ 00435 #Frame this data is associated with\n\ 00436 # 0: no frame\n\ 00437 # 1: global frame\n\ 00438 string frame_id\n\ 00439 \n\ 00440 ================================================================================\n\ 00441 MSG: geometry_msgs/Vector3\n\ 00442 # This represents a vector in free space. \n\ 00443 \n\ 00444 float64 x\n\ 00445 float64 y\n\ 00446 float64 z\n\ 00447 "; 00448 } 00449 00450 static const char* value(const ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> &) { return value(); } 00451 }; 00452 00453 } // namespace message_traits 00454 } // namespace ros 00455 00456 00457 namespace ros 00458 { 00459 namespace message_traits 00460 { 00461 template<class ContainerAllocator> struct IsMessage< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > : public TrueType {}; 00462 template<class ContainerAllocator> struct IsMessage< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> const> : public TrueType {}; 00463 template<class ContainerAllocator> 00464 struct MD5Sum< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > { 00465 static const char* value() 00466 { 00467 return "e716cc2181996b312d7f1ee1e64fa78a"; 00468 } 00469 00470 static const char* value(const ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> &) { return value(); } 00471 static const uint64_t static_value1 = 0xe716cc2181996b31ULL; 00472 static const uint64_t static_value2 = 0x2d7f1ee1e64fa78aULL; 00473 }; 00474 00475 template<class ContainerAllocator> 00476 struct DataType< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > { 00477 static const char* value() 00478 { 00479 return "fast_plane_detection/PlaneInRegionResponse"; 00480 } 00481 00482 static const char* value(const ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> &) { return value(); } 00483 }; 00484 00485 template<class ContainerAllocator> 00486 struct Definition< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > { 00487 static const char* value() 00488 { 00489 return "\n\ 00490 fast_plane_detection/Plane plane\n\ 00491 \n\ 00492 \n\ 00493 ================================================================================\n\ 00494 MSG: fast_plane_detection/Plane\n\ 00495 # Informs that a plane has been detected at a given location\n\ 00496 \n\ 00497 # The pose gives you the transform that take you to the coordinate system\n\ 00498 # of the plane, with the origin somewhere in the plane and the \n\ 00499 # z axis normal to the plane\n\ 00500 geometry_msgs/PoseStamped pose\n\ 00501 \n\ 00502 # Point + normal vector of the plane\n\ 00503 geometry_msgs/PointStamped plane_point\n\ 00504 geometry_msgs/Vector3Stamped normal\n\ 00505 geometry_msgs/PointStamped slave_point\n\ 00506 \n\ 00507 # These values give you the observed extents of the plane, along x and y,\n\ 00508 # in the plane's own coordinate system (above)\n\ 00509 # there is no guarantee that the origin of the plane coordinate system is\n\ 00510 # inside the boundary defined by these values. \n\ 00511 geometry_msgs/Point32 top_left\n\ 00512 geometry_msgs/Point32 top_right\n\ 00513 \n\ 00514 geometry_msgs/Point32 bottom_left\n\ 00515 geometry_msgs/Point32 bottom_right\n\ 00516 \n\ 00517 # There is no guarantee that the plane doe NOT extend further than these \n\ 00518 # values; this is just as far as we've observed it.\n\ 00519 \n\ 00520 # Whether the detection has succeeded or failed\n\ 00521 int32 SUCCESS = 1\n\ 00522 int32 FEW_INLIERS = 2\n\ 00523 int32 NO_PLANE = 3\n\ 00524 int32 OTHER_ERROR = 4\n\ 00525 int32 result\n\ 00526 \n\ 00527 # inliers over whole region\n\ 00528 float32 percentage_inliers\n\ 00529 # inliers of valid disparities\n\ 00530 int32 percentage_disp_inliers\n\ 00531 # number of valid disparities\n\ 00532 int32 percentage_valid_disp\n\ 00533 \n\ 00534 # confidence indicators of plane detection\n\ 00535 # mean squared error\n\ 00536 float32 error\n\ 00537 \n\ 00538 ================================================================================\n\ 00539 MSG: geometry_msgs/PoseStamped\n\ 00540 # A Pose with reference coordinate frame and timestamp\n\ 00541 Header header\n\ 00542 Pose pose\n\ 00543 \n\ 00544 ================================================================================\n\ 00545 MSG: std_msgs/Header\n\ 00546 # Standard metadata for higher-level stamped data types.\n\ 00547 # This is generally used to communicate timestamped data \n\ 00548 # in a particular coordinate frame.\n\ 00549 # \n\ 00550 # sequence ID: consecutively increasing ID \n\ 00551 uint32 seq\n\ 00552 #Two-integer timestamp that is expressed as:\n\ 00553 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00554 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00555 # time-handling sugar is provided by the client library\n\ 00556 time stamp\n\ 00557 #Frame this data is associated with\n\ 00558 # 0: no frame\n\ 00559 # 1: global frame\n\ 00560 string frame_id\n\ 00561 \n\ 00562 ================================================================================\n\ 00563 MSG: geometry_msgs/Pose\n\ 00564 # A representation of pose in free space, composed of postion and orientation. \n\ 00565 Point position\n\ 00566 Quaternion orientation\n\ 00567 \n\ 00568 ================================================================================\n\ 00569 MSG: geometry_msgs/Point\n\ 00570 # This contains the position of a point in free space\n\ 00571 float64 x\n\ 00572 float64 y\n\ 00573 float64 z\n\ 00574 \n\ 00575 ================================================================================\n\ 00576 MSG: geometry_msgs/Quaternion\n\ 00577 # This represents an orientation in free space in quaternion form.\n\ 00578 \n\ 00579 float64 x\n\ 00580 float64 y\n\ 00581 float64 z\n\ 00582 float64 w\n\ 00583 \n\ 00584 ================================================================================\n\ 00585 MSG: geometry_msgs/PointStamped\n\ 00586 # This represents a Point with reference coordinate frame and timestamp\n\ 00587 Header header\n\ 00588 Point point\n\ 00589 \n\ 00590 ================================================================================\n\ 00591 MSG: geometry_msgs/Vector3Stamped\n\ 00592 # This represents a Vector3 with reference coordinate frame and timestamp\n\ 00593 Header header\n\ 00594 Vector3 vector\n\ 00595 \n\ 00596 ================================================================================\n\ 00597 MSG: geometry_msgs/Vector3\n\ 00598 # This represents a vector in free space. \n\ 00599 \n\ 00600 float64 x\n\ 00601 float64 y\n\ 00602 float64 z\n\ 00603 ================================================================================\n\ 00604 MSG: geometry_msgs/Point32\n\ 00605 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00606 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00607 # \n\ 00608 # This recommendation is to promote interoperability. \n\ 00609 #\n\ 00610 # This message is designed to take up less space when sending\n\ 00611 # lots of points at once, as in the case of a PointCloud. \n\ 00612 \n\ 00613 float32 x\n\ 00614 float32 y\n\ 00615 float32 z\n\ 00616 "; 00617 } 00618 00619 static const char* value(const ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> &) { return value(); } 00620 }; 00621 00622 } // namespace message_traits 00623 } // namespace ros 00624 00625 namespace ros 00626 { 00627 namespace serialization 00628 { 00629 00630 template<class ContainerAllocator> struct Serializer< ::fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > 00631 { 00632 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00633 { 00634 stream.next(m.point); 00635 stream.next(m.width); 00636 stream.next(m.height); 00637 } 00638 00639 ROS_DECLARE_ALLINONE_SERIALIZER; 00640 }; // struct PlaneInRegionRequest_ 00641 } // namespace serialization 00642 } // namespace ros 00643 00644 00645 namespace ros 00646 { 00647 namespace serialization 00648 { 00649 00650 template<class ContainerAllocator> struct Serializer< ::fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > 00651 { 00652 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00653 { 00654 stream.next(m.plane); 00655 } 00656 00657 ROS_DECLARE_ALLINONE_SERIALIZER; 00658 }; // struct PlaneInRegionResponse_ 00659 } // namespace serialization 00660 } // namespace ros 00661 00662 namespace ros 00663 { 00664 namespace service_traits 00665 { 00666 template<> 00667 struct MD5Sum<fast_plane_detection::PlaneInRegion> { 00668 static const char* value() 00669 { 00670 return "af4f32849bccef799b668b077c0a80c7"; 00671 } 00672 00673 static const char* value(const fast_plane_detection::PlaneInRegion&) { return value(); } 00674 }; 00675 00676 template<> 00677 struct DataType<fast_plane_detection::PlaneInRegion> { 00678 static const char* value() 00679 { 00680 return "fast_plane_detection/PlaneInRegion"; 00681 } 00682 00683 static const char* value(const fast_plane_detection::PlaneInRegion&) { return value(); } 00684 }; 00685 00686 template<class ContainerAllocator> 00687 struct MD5Sum<fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > { 00688 static const char* value() 00689 { 00690 return "af4f32849bccef799b668b077c0a80c7"; 00691 } 00692 00693 static const char* value(const fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> &) { return value(); } 00694 }; 00695 00696 template<class ContainerAllocator> 00697 struct DataType<fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> > { 00698 static const char* value() 00699 { 00700 return "fast_plane_detection/PlaneInRegion"; 00701 } 00702 00703 static const char* value(const fast_plane_detection::PlaneInRegionRequest_<ContainerAllocator> &) { return value(); } 00704 }; 00705 00706 template<class ContainerAllocator> 00707 struct MD5Sum<fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > { 00708 static const char* value() 00709 { 00710 return "af4f32849bccef799b668b077c0a80c7"; 00711 } 00712 00713 static const char* value(const fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> &) { return value(); } 00714 }; 00715 00716 template<class ContainerAllocator> 00717 struct DataType<fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> > { 00718 static const char* value() 00719 { 00720 return "fast_plane_detection/PlaneInRegion"; 00721 } 00722 00723 static const char* value(const fast_plane_detection::PlaneInRegionResponse_<ContainerAllocator> &) { return value(); } 00724 }; 00725 00726 } // namespace service_traits 00727 } // namespace ros 00728 00729 #endif // FAST_PLANE_DETECTION_SERVICE_PLANEINREGION_H 00730