$search
00001 00060 #ifndef POLYGON_H_ 00061 #define POLYGON_H_ 00062 00063 #include "cob_3d_mapping_common/shape.h" 00064 #include <boost/shared_ptr.hpp> 00065 #include <boost/enable_shared_from_this.hpp> 00066 extern "C" { 00067 #include "cob_3d_mapping_common/gpc.h" 00068 } 00069 #include <fstream> 00070 00071 //#include "cob_3d_mapping_common/stop_watch.h" 00072 00073 namespace cob_3d_mapping 00074 { 00080 struct merge_config 00081 { 00087 double angle_thresh; 00093 float d_thresh; 00100 std::string weighting_method; 00101 }; 00102 00103 00108 class Polygon : public Shape 00109 { 00110 public: 00114 typedef boost::shared_ptr<Polygon> Ptr; 00119 typedef boost::shared_ptr<const Polygon> ConstPtr; 00120 public: 00121 00125 Polygon() 00126 : normal(Eigen::Vector3f::Zero()) 00127 , d(0.0) 00128 , transform_from_world_to_plane(Eigen::Affine3f::Identity()) 00129 , merge_weight_(1.0) 00130 { } 00131 00132 00137 inline size_t outerContourIndex() const 00138 { 00139 for(size_t i=0;i<contours.size();++i) { if(!holes[i]) { return i; } }; 00140 return 0; 00141 } 00142 00143 //##########methods for instantiation############## 00144 00152 virtual void computeAttributes(const Eigen::Vector3f &new_normal, const Eigen::Vector4f & new_centroid); 00153 00154 00162 virtual void transform2tf(const Eigen::Affine3f& trafo); 00163 00164 00171 void smoothPolygon(); 00172 00173 00174 //###########methods for merging################## 00181 virtual void getMergeCandidates(const std::vector<Polygon::Ptr>& poly_vec, std::vector<int>& intersections) const; 00182 00183 00189 virtual bool isIntersectedWith(const Polygon::Ptr& poly) const; 00190 00191 00198 void getIntersection(const Polygon::Ptr& poly, gpc_polygon* gpc_intersection) const; 00199 00200 00210 bool getContourOverlap(const Polygon::Ptr& poly, float& rel_overlap, int& abs_overlap) const; 00211 00212 00220 float computeSimilarity(const Polygon::Ptr& poly) const; 00221 00222 00230 virtual void merge(std::vector<Polygon::Ptr>& poly_vec); 00231 00232 00242 void merge_union(std::vector<Polygon::Ptr>& poly_vec, Polygon::Ptr& p_average); 00243 00244 00252 void assignWeight(); 00253 00254 00261 void assignID(const std::vector<Polygon::Ptr>& poly_vec); 00262 00263 00273 virtual void applyWeighting(const std::vector<Polygon::Ptr>& poly_vec, Polygon::Ptr& p_average); 00274 00275 00283 void getGpcStructure(const Eigen::Affine3f& external_trafo, gpc_polygon* gpc_p) const; 00284 00285 00293 void applyGpcStructure(const Eigen::Affine3f& external_trafo, const gpc_polygon* gpc_p); 00294 00295 00302 inline bool hasSimilarParametersWith(const Polygon::Ptr& poly) const 00303 { 00304 Eigen::Vector3f d = (this->centroid - poly->centroid).head(3); 00305 return ( fabs(poly->normal.dot(this->normal)) > this->merge_settings_.angle_thresh && 00306 fabs( d.dot(this->normal) ) < this->merge_settings_.d_thresh && 00307 fabs( d.dot(poly->normal) ) < this->merge_settings_.d_thresh ); 00308 } 00309 00310 //#######methods for calculation##################### 00311 00315 void computeCentroid(); 00316 00317 00324 double computeArea() const; // http://paulbourke.net/geometry/polyarea/ 00325 00326 00332 double computeArea3d() const; 00333 00334 00344 void getTransformationFromPlaneToWorld(const Eigen::Vector3f &normal,const Eigen::Vector3f &origin, 00345 Eigen::Affine3f &transformation) const; 00346 00347 00357 void getTransformationFromPlaneToWorld(const Eigen::Vector3f z_axis,const Eigen::Vector3f &normal, 00358 const Eigen::Vector3f &origin, Eigen::Affine3f &transformation); 00359 00360 00366 void getTransformedContours(const Eigen::Affine3f& trafo, std::vector<std::vector<Eigen::Vector3f> >& new_contours ) const; 00367 00368 00373 void TransformContours(const Eigen::Affine3f& trafo); 00374 00375 00382 void computePoseAndBoundingBox(Eigen::Affine3f& pose, Eigen::Vector4f& min_pt, Eigen::Vector4f& max_pt); 00383 00384 00385 00386 //#############debugging methods####################### 00387 00388 00394 void debug_output(std::string name); 00395 00396 00397 //########## member variables################# 00398 //needed for 32-bit systems: see http://eigen.tuxfamily.org/dox/TopicStructHavingEigenMembers.html 00399 EIGEN_MAKE_ALIGNED_OPERATOR_NEW 00400 std::vector<std::vector<Eigen::Vector3f> > contours; 00401 Eigen::Vector3f normal; 00402 double d; 00403 Eigen::Affine3f transform_from_world_to_plane; 00404 std::vector<bool> holes; 00405 double merge_weight_; 00406 merge_config merge_settings_; 00408 }; 00409 } 00410 #endif /* POLYGON_H_ */