00001 /* 00002 * detailedplane.hh 00003 * Mac Mason <mmason@willowgarage.com> 00004 * 00005 * A plane, as a C++ object; plays nice with semanticmodel::Plane and Planes 00006 * types. 00007 */ 00008 00009 #pragma once 00010 #include <boost/utility.hpp> 00011 #include <boost/shared_ptr.hpp> 00012 #include "std_msgs/ColorRGBA.h" 00013 #include "tf/transform_listener.h" 00014 #include "pcl16/point_types.h" 00015 #include "pcl16_ros/point_cloud.h" 00016 #include "sensor_msgs/PointCloud2.h" 00017 #include "semanticmodel/Plane.h" 00018 #include <cstddef> 00019 00020 namespace semanticmodel 00021 { 00022 00023 class DetailedPlane : public boost::noncopyable 00024 { 00025 public: 00026 typedef boost::shared_ptr<DetailedPlane> Ptr; 00027 private: 00028 // Save some _serious_ typing. 00029 typedef pcl16::PointXYZRGB Point; 00030 typedef pcl16::PointCloud<Point> PointCloud; 00031 00032 const static double PLANE_ERROR_TOL = 0.2; 00033 00034 public: 00035 // Build one, using a message. The listener parameter is used to transform 00036 // everything to the /map frame, where we operate. 00037 DetailedPlane(const semanticmodel::Plane& plane, 00038 tf::TransformListener* listener); 00039 00040 // No destructor; thanks, shared_ptr! 00041 00042 // Do these planes overlap, according to our definition? 00043 bool overlaps(const DetailedPlane& rhs) const; 00044 00045 // Compute the area of this plane. 00046 double area() const; 00047 00048 // Bring the contents of rhs into this plane; may change very nearly 00049 // everything. We use the larger of this and rhs to be the "canonical" 00050 // plane here; that might lead to some goofiness. 00051 void mergeFrom(const DetailedPlane& rhs); 00052 00053 // Get a Plane message back out. 00054 semanticmodel::Plane toPlaneMsg(); 00055 00056 // Like toPlaneMsg, but only fill in the equation and hull. 00057 void toHullAndEquationPlaneMsg(semanticmodel::Plane& out); 00058 00059 // The plane equation. 00060 double a, b, c, d; 00061 00062 // The centroid of this plane. 00063 geometry_msgs::Point center; 00064 00065 // Our convex hull, as a pcl16 cloud. 00066 PointCloud::Ptr hull; 00067 00068 // And all the points that belong to me. 00069 PointCloud::Ptr cloud; 00070 00071 // What (false) color am I, for display purposes? 00072 std_msgs::ColorRGBA color; 00073 00074 // Global frame 00075 std::string frame_id; 00076 }; 00077 00078 }