cluster_types.h
Go to the documentation of this file.
00001 
00063 #ifndef __COB_3D_SEGMENTATION_CLUSTER_TYPES_H__
00064 #define __COB_3D_SEGMENTATION_CLUSTER_TYPES_H__
00065 
00066 #include <pcl/common/eigen.h>
00067 #include <set>
00068 #include <cob_3d_mapping_common/dominant_color.h>
00069 #include <cob_3d_segmentation/polygon_extraction/polygon_types.h>
00070 
00071 namespace cob_3d_segmentation
00072 {
00073 
00074   class ClusterBase
00075   {
00076   public:
00077     typedef std::vector<int>::iterator iterator;
00078     typedef std::vector<int>::size_type size_type;
00079     typedef std::vector<int>::value_type value_type;
00080 
00081   public:
00082     explicit ClusterBase(int id)
00083       : indices_()
00084       , id_(id)
00085     { };
00086     virtual ~ClusterBase() { }
00087 
00088     inline const int id() const { return id_; }
00089 
00090     inline value_type& operator[](size_type idx) { return indices_.at(idx); }
00091     inline iterator begin() { return indices_.begin(); }
00092     inline iterator end() { return indices_.end(); }
00093     inline size_type size() const { return indices_.size(); }
00094 
00095     inline void addIndex(int idx) { indices_.push_back(idx); }
00096 
00097     std::vector<int> indices_;
00098   protected:
00099     int id_;
00100 
00101   };
00102 
00103   class DepthCluster : public ClusterBase
00104   {
00105     template <typename LabelT, typename PointT, typename PointNT> friend class DepthClusterHandler;
00106 
00107   public:
00108     DepthCluster(int id)
00109       : ClusterBase(id)
00110       , type(I_UNDEF)
00111       , type_probability(1.0)
00112       , is_planar_(false)
00113       , max_curvature(0.0)
00114       , min_curvature(0.0)
00115       , pca_point_comp1(0.0, 0.0, 0.0)
00116       , pca_point_comp2(0.0, 0.0, 0.0)
00117       , pca_point_comp3(0.0, 0.0, 0.0)
00118       , pca_point_values(0.0, 0.0, 0.0)
00119       , pca_inter_centroid(0.0, 0.0, 0.0)
00120       , pca_inter_comp1(0.0, 0.0, 0.0)
00121       , pca_inter_comp2(0.0, 0.0, 0.0)
00122       , pca_inter_comp3(0.0, 0.0, 0.0)
00123       , pca_inter_values(0.0, 0.0, 0.0)
00124       , border_points()
00125       , sum_points_(0.0, 0.0, 0.0)
00126       , sum_orientations_(0.0, 0.0, 0.0)
00127       , sum_rgb_(0,0,0)
00128     { }
00129 
00130     inline Eigen::Vector3f getCentroid() const { return sum_points_ / (float)indices_.size(); }
00131     inline Eigen::Vector3f getOrientation() const { return sum_orientations_ / (float)indices_.size(); }
00132     inline Eigen::Vector3i getMeanColorVector() const { return sum_rgb_ / indices_.size(); }
00133     inline int getMeanColorValue() const { Eigen::Vector3i c = getMeanColorVector(); return (c(0) << 16 | c(1) << 8 | c(2)); }
00134     inline Eigen::Vector3i computeDominantColorVector() const
00135     { uint8_t r,g,b; color_.getColor(r,g,b); return Eigen::Vector3i(r,g,b); }
00136 
00137   public:
00138     int type, label_color;
00139     float type_probability;
00140     bool is_planar_;
00141     float max_curvature;
00142     float min_curvature;
00143 
00144     Eigen::Vector3f pca_point_comp1;
00145     Eigen::Vector3f pca_point_comp2;
00146     Eigen::Vector3f pca_point_comp3;
00147     Eigen::Vector3f pca_point_values;
00148 
00149     Eigen::Vector3f pca_inter_centroid;
00150     Eigen::Vector3f pca_inter_comp1;
00151     Eigen::Vector3f pca_inter_comp2;
00152     Eigen::Vector3f pca_inter_comp3;
00153     Eigen::Vector3f pca_inter_values;
00154 
00155     std::vector<PolygonPoint> border_points;
00156 
00157   private:
00158     Eigen::Vector3f sum_points_;
00159     Eigen::Vector3f sum_orientations_;
00160     Eigen::Vector3i sum_rgb_;
00161     cob_3d_mapping::DominantColor color_;
00162   };
00163 
00164   inline const bool operator< (const ClusterBase& lhs, const ClusterBase& rhs){
00165     return lhs.size() < rhs.size();}
00166   inline const bool operator> (const ClusterBase& lhs, const ClusterBase& rhs){
00167     return  operator< (rhs, lhs);}
00168   inline const bool operator<=(const ClusterBase& lhs, const ClusterBase& rhs){
00169     return !operator> (lhs, rhs);}
00170   inline const bool operator>=(const ClusterBase& lhs, const ClusterBase& rhs){
00171     return !operator< (lhs, rhs);}
00172 }
00173 
00174 #endif


cob_3d_segmentation
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:03:03