$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/msg/Plane.msg */ 00002 #ifndef FAST_PLANE_DETECTION_MESSAGE_PLANE_H 00003 #define FAST_PLANE_DETECTION_MESSAGE_PLANE_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 "geometry_msgs/PoseStamped.h" 00018 #include "geometry_msgs/PointStamped.h" 00019 #include "geometry_msgs/Vector3Stamped.h" 00020 #include "geometry_msgs/PointStamped.h" 00021 #include "geometry_msgs/Point32.h" 00022 #include "geometry_msgs/Point32.h" 00023 #include "geometry_msgs/Point32.h" 00024 #include "geometry_msgs/Point32.h" 00025 00026 namespace fast_plane_detection 00027 { 00028 template <class ContainerAllocator> 00029 struct Plane_ { 00030 typedef Plane_<ContainerAllocator> Type; 00031 00032 Plane_() 00033 : pose() 00034 , plane_point() 00035 , normal() 00036 , slave_point() 00037 , top_left() 00038 , top_right() 00039 , bottom_left() 00040 , bottom_right() 00041 , result(0) 00042 , percentage_inliers(0.0) 00043 , percentage_disp_inliers(0) 00044 , percentage_valid_disp(0) 00045 , error(0.0) 00046 { 00047 } 00048 00049 Plane_(const ContainerAllocator& _alloc) 00050 : pose(_alloc) 00051 , plane_point(_alloc) 00052 , normal(_alloc) 00053 , slave_point(_alloc) 00054 , top_left(_alloc) 00055 , top_right(_alloc) 00056 , bottom_left(_alloc) 00057 , bottom_right(_alloc) 00058 , result(0) 00059 , percentage_inliers(0.0) 00060 , percentage_disp_inliers(0) 00061 , percentage_valid_disp(0) 00062 , error(0.0) 00063 { 00064 } 00065 00066 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _pose_type; 00067 ::geometry_msgs::PoseStamped_<ContainerAllocator> pose; 00068 00069 typedef ::geometry_msgs::PointStamped_<ContainerAllocator> _plane_point_type; 00070 ::geometry_msgs::PointStamped_<ContainerAllocator> plane_point; 00071 00072 typedef ::geometry_msgs::Vector3Stamped_<ContainerAllocator> _normal_type; 00073 ::geometry_msgs::Vector3Stamped_<ContainerAllocator> normal; 00074 00075 typedef ::geometry_msgs::PointStamped_<ContainerAllocator> _slave_point_type; 00076 ::geometry_msgs::PointStamped_<ContainerAllocator> slave_point; 00077 00078 typedef ::geometry_msgs::Point32_<ContainerAllocator> _top_left_type; 00079 ::geometry_msgs::Point32_<ContainerAllocator> top_left; 00080 00081 typedef ::geometry_msgs::Point32_<ContainerAllocator> _top_right_type; 00082 ::geometry_msgs::Point32_<ContainerAllocator> top_right; 00083 00084 typedef ::geometry_msgs::Point32_<ContainerAllocator> _bottom_left_type; 00085 ::geometry_msgs::Point32_<ContainerAllocator> bottom_left; 00086 00087 typedef ::geometry_msgs::Point32_<ContainerAllocator> _bottom_right_type; 00088 ::geometry_msgs::Point32_<ContainerAllocator> bottom_right; 00089 00090 typedef int32_t _result_type; 00091 int32_t result; 00092 00093 typedef float _percentage_inliers_type; 00094 float percentage_inliers; 00095 00096 typedef int32_t _percentage_disp_inliers_type; 00097 int32_t percentage_disp_inliers; 00098 00099 typedef int32_t _percentage_valid_disp_type; 00100 int32_t percentage_valid_disp; 00101 00102 typedef float _error_type; 00103 float error; 00104 00105 enum { SUCCESS = 1 }; 00106 enum { FEW_INLIERS = 2 }; 00107 enum { NO_PLANE = 3 }; 00108 enum { OTHER_ERROR = 4 }; 00109 00110 private: 00111 static const char* __s_getDataType_() { return "fast_plane_detection/Plane"; } 00112 public: 00113 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00114 00115 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00116 00117 private: 00118 static const char* __s_getMD5Sum_() { return "e876d3c2247eeda0c0207fae33ce01a9"; } 00119 public: 00120 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00121 00122 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00123 00124 private: 00125 static const char* __s_getMessageDefinition_() { return "# Informs that a plane has been detected at a given location\n\ 00126 \n\ 00127 # The pose gives you the transform that take you to the coordinate system\n\ 00128 # of the plane, with the origin somewhere in the plane and the \n\ 00129 # z axis normal to the plane\n\ 00130 geometry_msgs/PoseStamped pose\n\ 00131 \n\ 00132 # Point + normal vector of the plane\n\ 00133 geometry_msgs/PointStamped plane_point\n\ 00134 geometry_msgs/Vector3Stamped normal\n\ 00135 geometry_msgs/PointStamped slave_point\n\ 00136 \n\ 00137 # These values give you the observed extents of the plane, along x and y,\n\ 00138 # in the plane's own coordinate system (above)\n\ 00139 # there is no guarantee that the origin of the plane coordinate system is\n\ 00140 # inside the boundary defined by these values. \n\ 00141 geometry_msgs/Point32 top_left\n\ 00142 geometry_msgs/Point32 top_right\n\ 00143 \n\ 00144 geometry_msgs/Point32 bottom_left\n\ 00145 geometry_msgs/Point32 bottom_right\n\ 00146 \n\ 00147 # There is no guarantee that the plane doe NOT extend further than these \n\ 00148 # values; this is just as far as we've observed it.\n\ 00149 \n\ 00150 # Whether the detection has succeeded or failed\n\ 00151 int32 SUCCESS = 1\n\ 00152 int32 FEW_INLIERS = 2\n\ 00153 int32 NO_PLANE = 3\n\ 00154 int32 OTHER_ERROR = 4\n\ 00155 int32 result\n\ 00156 \n\ 00157 # inliers over whole region\n\ 00158 float32 percentage_inliers\n\ 00159 # inliers of valid disparities\n\ 00160 int32 percentage_disp_inliers\n\ 00161 # number of valid disparities\n\ 00162 int32 percentage_valid_disp\n\ 00163 \n\ 00164 # confidence indicators of plane detection\n\ 00165 # mean squared error\n\ 00166 float32 error\n\ 00167 \n\ 00168 ================================================================================\n\ 00169 MSG: geometry_msgs/PoseStamped\n\ 00170 # A Pose with reference coordinate frame and timestamp\n\ 00171 Header header\n\ 00172 Pose pose\n\ 00173 \n\ 00174 ================================================================================\n\ 00175 MSG: std_msgs/Header\n\ 00176 # Standard metadata for higher-level stamped data types.\n\ 00177 # This is generally used to communicate timestamped data \n\ 00178 # in a particular coordinate frame.\n\ 00179 # \n\ 00180 # sequence ID: consecutively increasing ID \n\ 00181 uint32 seq\n\ 00182 #Two-integer timestamp that is expressed as:\n\ 00183 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00184 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00185 # time-handling sugar is provided by the client library\n\ 00186 time stamp\n\ 00187 #Frame this data is associated with\n\ 00188 # 0: no frame\n\ 00189 # 1: global frame\n\ 00190 string frame_id\n\ 00191 \n\ 00192 ================================================================================\n\ 00193 MSG: geometry_msgs/Pose\n\ 00194 # A representation of pose in free space, composed of postion and orientation. \n\ 00195 Point position\n\ 00196 Quaternion orientation\n\ 00197 \n\ 00198 ================================================================================\n\ 00199 MSG: geometry_msgs/Point\n\ 00200 # This contains the position of a point in free space\n\ 00201 float64 x\n\ 00202 float64 y\n\ 00203 float64 z\n\ 00204 \n\ 00205 ================================================================================\n\ 00206 MSG: geometry_msgs/Quaternion\n\ 00207 # This represents an orientation in free space in quaternion form.\n\ 00208 \n\ 00209 float64 x\n\ 00210 float64 y\n\ 00211 float64 z\n\ 00212 float64 w\n\ 00213 \n\ 00214 ================================================================================\n\ 00215 MSG: geometry_msgs/PointStamped\n\ 00216 # This represents a Point with reference coordinate frame and timestamp\n\ 00217 Header header\n\ 00218 Point point\n\ 00219 \n\ 00220 ================================================================================\n\ 00221 MSG: geometry_msgs/Vector3Stamped\n\ 00222 # This represents a Vector3 with reference coordinate frame and timestamp\n\ 00223 Header header\n\ 00224 Vector3 vector\n\ 00225 \n\ 00226 ================================================================================\n\ 00227 MSG: geometry_msgs/Vector3\n\ 00228 # This represents a vector in free space. \n\ 00229 \n\ 00230 float64 x\n\ 00231 float64 y\n\ 00232 float64 z\n\ 00233 ================================================================================\n\ 00234 MSG: geometry_msgs/Point32\n\ 00235 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00236 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00237 # \n\ 00238 # This recommendation is to promote interoperability. \n\ 00239 #\n\ 00240 # This message is designed to take up less space when sending\n\ 00241 # lots of points at once, as in the case of a PointCloud. \n\ 00242 \n\ 00243 float32 x\n\ 00244 float32 y\n\ 00245 float32 z\n\ 00246 "; } 00247 public: 00248 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00249 00250 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00251 00252 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00253 { 00254 ros::serialization::OStream stream(write_ptr, 1000000000); 00255 ros::serialization::serialize(stream, pose); 00256 ros::serialization::serialize(stream, plane_point); 00257 ros::serialization::serialize(stream, normal); 00258 ros::serialization::serialize(stream, slave_point); 00259 ros::serialization::serialize(stream, top_left); 00260 ros::serialization::serialize(stream, top_right); 00261 ros::serialization::serialize(stream, bottom_left); 00262 ros::serialization::serialize(stream, bottom_right); 00263 ros::serialization::serialize(stream, result); 00264 ros::serialization::serialize(stream, percentage_inliers); 00265 ros::serialization::serialize(stream, percentage_disp_inliers); 00266 ros::serialization::serialize(stream, percentage_valid_disp); 00267 ros::serialization::serialize(stream, error); 00268 return stream.getData(); 00269 } 00270 00271 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00272 { 00273 ros::serialization::IStream stream(read_ptr, 1000000000); 00274 ros::serialization::deserialize(stream, pose); 00275 ros::serialization::deserialize(stream, plane_point); 00276 ros::serialization::deserialize(stream, normal); 00277 ros::serialization::deserialize(stream, slave_point); 00278 ros::serialization::deserialize(stream, top_left); 00279 ros::serialization::deserialize(stream, top_right); 00280 ros::serialization::deserialize(stream, bottom_left); 00281 ros::serialization::deserialize(stream, bottom_right); 00282 ros::serialization::deserialize(stream, result); 00283 ros::serialization::deserialize(stream, percentage_inliers); 00284 ros::serialization::deserialize(stream, percentage_disp_inliers); 00285 ros::serialization::deserialize(stream, percentage_valid_disp); 00286 ros::serialization::deserialize(stream, error); 00287 return stream.getData(); 00288 } 00289 00290 ROS_DEPRECATED virtual uint32_t serializationLength() const 00291 { 00292 uint32_t size = 0; 00293 size += ros::serialization::serializationLength(pose); 00294 size += ros::serialization::serializationLength(plane_point); 00295 size += ros::serialization::serializationLength(normal); 00296 size += ros::serialization::serializationLength(slave_point); 00297 size += ros::serialization::serializationLength(top_left); 00298 size += ros::serialization::serializationLength(top_right); 00299 size += ros::serialization::serializationLength(bottom_left); 00300 size += ros::serialization::serializationLength(bottom_right); 00301 size += ros::serialization::serializationLength(result); 00302 size += ros::serialization::serializationLength(percentage_inliers); 00303 size += ros::serialization::serializationLength(percentage_disp_inliers); 00304 size += ros::serialization::serializationLength(percentage_valid_disp); 00305 size += ros::serialization::serializationLength(error); 00306 return size; 00307 } 00308 00309 typedef boost::shared_ptr< ::fast_plane_detection::Plane_<ContainerAllocator> > Ptr; 00310 typedef boost::shared_ptr< ::fast_plane_detection::Plane_<ContainerAllocator> const> ConstPtr; 00311 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00312 }; // struct Plane 00313 typedef ::fast_plane_detection::Plane_<std::allocator<void> > Plane; 00314 00315 typedef boost::shared_ptr< ::fast_plane_detection::Plane> PlanePtr; 00316 typedef boost::shared_ptr< ::fast_plane_detection::Plane const> PlaneConstPtr; 00317 00318 00319 template<typename ContainerAllocator> 00320 std::ostream& operator<<(std::ostream& s, const ::fast_plane_detection::Plane_<ContainerAllocator> & v) 00321 { 00322 ros::message_operations::Printer< ::fast_plane_detection::Plane_<ContainerAllocator> >::stream(s, "", v); 00323 return s;} 00324 00325 } // namespace fast_plane_detection 00326 00327 namespace ros 00328 { 00329 namespace message_traits 00330 { 00331 template<class ContainerAllocator> struct IsMessage< ::fast_plane_detection::Plane_<ContainerAllocator> > : public TrueType {}; 00332 template<class ContainerAllocator> struct IsMessage< ::fast_plane_detection::Plane_<ContainerAllocator> const> : public TrueType {}; 00333 template<class ContainerAllocator> 00334 struct MD5Sum< ::fast_plane_detection::Plane_<ContainerAllocator> > { 00335 static const char* value() 00336 { 00337 return "e876d3c2247eeda0c0207fae33ce01a9"; 00338 } 00339 00340 static const char* value(const ::fast_plane_detection::Plane_<ContainerAllocator> &) { return value(); } 00341 static const uint64_t static_value1 = 0xe876d3c2247eeda0ULL; 00342 static const uint64_t static_value2 = 0xc0207fae33ce01a9ULL; 00343 }; 00344 00345 template<class ContainerAllocator> 00346 struct DataType< ::fast_plane_detection::Plane_<ContainerAllocator> > { 00347 static const char* value() 00348 { 00349 return "fast_plane_detection/Plane"; 00350 } 00351 00352 static const char* value(const ::fast_plane_detection::Plane_<ContainerAllocator> &) { return value(); } 00353 }; 00354 00355 template<class ContainerAllocator> 00356 struct Definition< ::fast_plane_detection::Plane_<ContainerAllocator> > { 00357 static const char* value() 00358 { 00359 return "# Informs that a plane has been detected at a given location\n\ 00360 \n\ 00361 # The pose gives you the transform that take you to the coordinate system\n\ 00362 # of the plane, with the origin somewhere in the plane and the \n\ 00363 # z axis normal to the plane\n\ 00364 geometry_msgs/PoseStamped pose\n\ 00365 \n\ 00366 # Point + normal vector of the plane\n\ 00367 geometry_msgs/PointStamped plane_point\n\ 00368 geometry_msgs/Vector3Stamped normal\n\ 00369 geometry_msgs/PointStamped slave_point\n\ 00370 \n\ 00371 # These values give you the observed extents of the plane, along x and y,\n\ 00372 # in the plane's own coordinate system (above)\n\ 00373 # there is no guarantee that the origin of the plane coordinate system is\n\ 00374 # inside the boundary defined by these values. \n\ 00375 geometry_msgs/Point32 top_left\n\ 00376 geometry_msgs/Point32 top_right\n\ 00377 \n\ 00378 geometry_msgs/Point32 bottom_left\n\ 00379 geometry_msgs/Point32 bottom_right\n\ 00380 \n\ 00381 # There is no guarantee that the plane doe NOT extend further than these \n\ 00382 # values; this is just as far as we've observed it.\n\ 00383 \n\ 00384 # Whether the detection has succeeded or failed\n\ 00385 int32 SUCCESS = 1\n\ 00386 int32 FEW_INLIERS = 2\n\ 00387 int32 NO_PLANE = 3\n\ 00388 int32 OTHER_ERROR = 4\n\ 00389 int32 result\n\ 00390 \n\ 00391 # inliers over whole region\n\ 00392 float32 percentage_inliers\n\ 00393 # inliers of valid disparities\n\ 00394 int32 percentage_disp_inliers\n\ 00395 # number of valid disparities\n\ 00396 int32 percentage_valid_disp\n\ 00397 \n\ 00398 # confidence indicators of plane detection\n\ 00399 # mean squared error\n\ 00400 float32 error\n\ 00401 \n\ 00402 ================================================================================\n\ 00403 MSG: geometry_msgs/PoseStamped\n\ 00404 # A Pose with reference coordinate frame and timestamp\n\ 00405 Header header\n\ 00406 Pose pose\n\ 00407 \n\ 00408 ================================================================================\n\ 00409 MSG: std_msgs/Header\n\ 00410 # Standard metadata for higher-level stamped data types.\n\ 00411 # This is generally used to communicate timestamped data \n\ 00412 # in a particular coordinate frame.\n\ 00413 # \n\ 00414 # sequence ID: consecutively increasing ID \n\ 00415 uint32 seq\n\ 00416 #Two-integer timestamp that is expressed as:\n\ 00417 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00418 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00419 # time-handling sugar is provided by the client library\n\ 00420 time stamp\n\ 00421 #Frame this data is associated with\n\ 00422 # 0: no frame\n\ 00423 # 1: global frame\n\ 00424 string frame_id\n\ 00425 \n\ 00426 ================================================================================\n\ 00427 MSG: geometry_msgs/Pose\n\ 00428 # A representation of pose in free space, composed of postion and orientation. \n\ 00429 Point position\n\ 00430 Quaternion orientation\n\ 00431 \n\ 00432 ================================================================================\n\ 00433 MSG: geometry_msgs/Point\n\ 00434 # This contains the position of a point in free space\n\ 00435 float64 x\n\ 00436 float64 y\n\ 00437 float64 z\n\ 00438 \n\ 00439 ================================================================================\n\ 00440 MSG: geometry_msgs/Quaternion\n\ 00441 # This represents an orientation in free space in quaternion form.\n\ 00442 \n\ 00443 float64 x\n\ 00444 float64 y\n\ 00445 float64 z\n\ 00446 float64 w\n\ 00447 \n\ 00448 ================================================================================\n\ 00449 MSG: geometry_msgs/PointStamped\n\ 00450 # This represents a Point with reference coordinate frame and timestamp\n\ 00451 Header header\n\ 00452 Point point\n\ 00453 \n\ 00454 ================================================================================\n\ 00455 MSG: geometry_msgs/Vector3Stamped\n\ 00456 # This represents a Vector3 with reference coordinate frame and timestamp\n\ 00457 Header header\n\ 00458 Vector3 vector\n\ 00459 \n\ 00460 ================================================================================\n\ 00461 MSG: geometry_msgs/Vector3\n\ 00462 # This represents a vector in free space. \n\ 00463 \n\ 00464 float64 x\n\ 00465 float64 y\n\ 00466 float64 z\n\ 00467 ================================================================================\n\ 00468 MSG: geometry_msgs/Point32\n\ 00469 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00470 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00471 # \n\ 00472 # This recommendation is to promote interoperability. \n\ 00473 #\n\ 00474 # This message is designed to take up less space when sending\n\ 00475 # lots of points at once, as in the case of a PointCloud. \n\ 00476 \n\ 00477 float32 x\n\ 00478 float32 y\n\ 00479 float32 z\n\ 00480 "; 00481 } 00482 00483 static const char* value(const ::fast_plane_detection::Plane_<ContainerAllocator> &) { return value(); } 00484 }; 00485 00486 } // namespace message_traits 00487 } // namespace ros 00488 00489 namespace ros 00490 { 00491 namespace serialization 00492 { 00493 00494 template<class ContainerAllocator> struct Serializer< ::fast_plane_detection::Plane_<ContainerAllocator> > 00495 { 00496 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00497 { 00498 stream.next(m.pose); 00499 stream.next(m.plane_point); 00500 stream.next(m.normal); 00501 stream.next(m.slave_point); 00502 stream.next(m.top_left); 00503 stream.next(m.top_right); 00504 stream.next(m.bottom_left); 00505 stream.next(m.bottom_right); 00506 stream.next(m.result); 00507 stream.next(m.percentage_inliers); 00508 stream.next(m.percentage_disp_inliers); 00509 stream.next(m.percentage_valid_disp); 00510 stream.next(m.error); 00511 } 00512 00513 ROS_DECLARE_ALLINONE_SERIALIZER; 00514 }; // struct Plane_ 00515 } // namespace serialization 00516 } // namespace ros 00517 00518 namespace ros 00519 { 00520 namespace message_operations 00521 { 00522 00523 template<class ContainerAllocator> 00524 struct Printer< ::fast_plane_detection::Plane_<ContainerAllocator> > 00525 { 00526 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::fast_plane_detection::Plane_<ContainerAllocator> & v) 00527 { 00528 s << indent << "pose: "; 00529 s << std::endl; 00530 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.pose); 00531 s << indent << "plane_point: "; 00532 s << std::endl; 00533 Printer< ::geometry_msgs::PointStamped_<ContainerAllocator> >::stream(s, indent + " ", v.plane_point); 00534 s << indent << "normal: "; 00535 s << std::endl; 00536 Printer< ::geometry_msgs::Vector3Stamped_<ContainerAllocator> >::stream(s, indent + " ", v.normal); 00537 s << indent << "slave_point: "; 00538 s << std::endl; 00539 Printer< ::geometry_msgs::PointStamped_<ContainerAllocator> >::stream(s, indent + " ", v.slave_point); 00540 s << indent << "top_left: "; 00541 s << std::endl; 00542 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.top_left); 00543 s << indent << "top_right: "; 00544 s << std::endl; 00545 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.top_right); 00546 s << indent << "bottom_left: "; 00547 s << std::endl; 00548 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.bottom_left); 00549 s << indent << "bottom_right: "; 00550 s << std::endl; 00551 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.bottom_right); 00552 s << indent << "result: "; 00553 Printer<int32_t>::stream(s, indent + " ", v.result); 00554 s << indent << "percentage_inliers: "; 00555 Printer<float>::stream(s, indent + " ", v.percentage_inliers); 00556 s << indent << "percentage_disp_inliers: "; 00557 Printer<int32_t>::stream(s, indent + " ", v.percentage_disp_inliers); 00558 s << indent << "percentage_valid_disp: "; 00559 Printer<int32_t>::stream(s, indent + " ", v.percentage_valid_disp); 00560 s << indent << "error: "; 00561 Printer<float>::stream(s, indent + " ", v.error); 00562 } 00563 }; 00564 00565 00566 } // namespace message_operations 00567 } // namespace ros 00568 00569 #endif // FAST_PLANE_DETECTION_MESSAGE_PLANE_H 00570