Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef PCL_RECOGNITION_MODEL_LIBRARY_H_
00040 #define PCL_RECOGNITION_MODEL_LIBRARY_H_
00041
00042 #include "auxiliary.h"
00043 #include <pcl/recognition/ransac_based/voxel_structure.h>
00044 #include <pcl/recognition/ransac_based/orr_octree.h>
00045 #include <pcl/common/random.h>
00046 #include <pcl/pcl_exports.h>
00047 #include <pcl/point_cloud.h>
00048 #include <pcl/point_types.h>
00049 #include <ctime>
00050 #include <string>
00051 #include <list>
00052 #include <set>
00053 #include <map>
00054
00055 namespace pcl
00056 {
00057 namespace recognition
00058 {
00059 class PCL_EXPORTS ModelLibrary
00060 {
00061 public:
00062 typedef pcl::PointCloud<pcl::PointXYZ> PointCloudIn;
00063 typedef pcl::PointCloud<pcl::Normal> PointCloudN;
00064
00066 class Model
00067 {
00068 public:
00069 Model (const PointCloudIn& points, const PointCloudN& normals, float voxel_size, const std::string& object_name,
00070 float frac_of_points_for_registration, void* user_data = NULL)
00071 : obj_name_(object_name),
00072 user_data_ (user_data)
00073 {
00074 octree_.build (points, voxel_size, &normals);
00075
00076 const std::vector<ORROctree::Node*>& full_leaves = octree_.getFullLeaves ();
00077 if ( full_leaves.empty () )
00078 return;
00079
00080
00081 std::vector<ORROctree::Node*>::const_iterator it = full_leaves.begin ();
00082 const float *p = (*it)->getData ()->getPoint ();
00083 aux::copy3 (p, octree_center_of_mass_);
00084 bounds_of_octree_points_[0] = bounds_of_octree_points_[1] = p[0];
00085 bounds_of_octree_points_[2] = bounds_of_octree_points_[3] = p[1];
00086 bounds_of_octree_points_[4] = bounds_of_octree_points_[5] = p[2];
00087
00088
00089 for ( ++it ; it != full_leaves.end () ; ++it )
00090 {
00091 aux::add3 (octree_center_of_mass_, (*it)->getData ()->getPoint ());
00092 aux::expandBoundingBoxToContainPoint (bounds_of_octree_points_, (*it)->getData ()->getPoint ());
00093 }
00094
00095 int num_octree_points = static_cast<int> (full_leaves.size ());
00096
00097 aux::mult3 (octree_center_of_mass_, 1.0f/static_cast<float> (num_octree_points));
00098
00099 int num_points_for_registration = static_cast<int> (static_cast<float> (num_octree_points)*frac_of_points_for_registration);
00100 points_for_registration_.resize (static_cast<size_t> (num_points_for_registration));
00101
00102
00103 std::vector<int> ids (num_octree_points);
00104 for ( int i = 0 ; i < num_octree_points ; ++i )
00105 ids[i] = i;
00106
00107
00108 pcl::common::UniformGenerator<int> randgen (0, num_octree_points - 1, static_cast<uint32_t> (time (NULL)));
00109
00110
00111 for ( int i = 0 ; i < num_points_for_registration ; ++i )
00112 {
00113
00114 randgen.setParameters (0, static_cast<int> (ids.size ()) - 1);
00115 int rand_pos = randgen.run ();
00116
00117
00118 aux::copy3 (octree_.getFullLeaves ()[ids[rand_pos]]->getData ()->getPoint (), points_for_registration_[i]);
00119
00120
00121 ids.erase (ids.begin() + rand_pos);
00122 }
00123 }
00124
00125 virtual ~Model ()
00126 {
00127 }
00128
00129 inline const std::string&
00130 getObjectName () const
00131 {
00132 return (obj_name_);
00133 }
00134
00135 inline const ORROctree&
00136 getOctree () const
00137 {
00138 return (octree_);
00139 }
00140
00141 inline void*
00142 getUserData () const
00143 {
00144 return (user_data_);
00145 }
00146
00147 inline const float*
00148 getOctreeCenterOfMass () const
00149 {
00150 return (octree_center_of_mass_);
00151 }
00152
00153 inline const float*
00154 getBoundsOfOctreePoints () const
00155 {
00156 return (bounds_of_octree_points_);
00157 }
00158
00159 inline const PointCloudIn&
00160 getPointsForRegistration () const
00161 {
00162 return (points_for_registration_);
00163 }
00164
00165 protected:
00166 const std::string obj_name_;
00167 ORROctree octree_;
00168 float octree_center_of_mass_[3];
00169 float bounds_of_octree_points_[6];
00170 PointCloudIn points_for_registration_;
00171 void* user_data_;
00172 };
00173
00174 typedef std::list<std::pair<const ORROctree::Node::Data*, const ORROctree::Node::Data*> > node_data_pair_list;
00175 typedef std::map<const Model*, node_data_pair_list> HashTableCell;
00176 typedef VoxelStructure<HashTableCell, float> HashTable;
00177
00178 public:
00181 ModelLibrary (float pair_width, float voxel_size, float max_coplanarity_angle = 3.0f*AUX_DEG_TO_RADIANS);
00182 virtual ~ModelLibrary ()
00183 {
00184 this->clear();
00185 }
00186
00188 void
00189 removeAllModels ();
00190
00194 inline void
00195 setMaxCoplanarityAngleDegrees (float max_coplanarity_angle_degrees)
00196 {
00197 max_coplanarity_angle_ = max_coplanarity_angle_degrees*AUX_DEG_TO_RADIANS;
00198 }
00199
00202 inline void
00203 ignoreCoplanarPointPairsOn ()
00204 {
00205 ignore_coplanar_opps_ = true;
00206 }
00207
00210 inline void
00211 ignoreCoplanarPointPairsOff ()
00212 {
00213 ignore_coplanar_opps_ = false;
00214 }
00215
00225 bool
00226 addModel (const PointCloudIn& points, const PointCloudN& normals, const std::string& object_name,
00227 float frac_of_points_for_registration, void* user_data = NULL);
00228
00230 inline const HashTable&
00231 getHashTable () const
00232 {
00233 return (hash_table_);
00234 }
00235
00236 inline const Model*
00237 getModel (const std::string& name) const
00238 {
00239 std::map<std::string,Model*>::const_iterator it = models_.find (name);
00240 if ( it != models_.end () )
00241 return (it->second);
00242
00243 return (NULL);
00244 }
00245
00246 inline const std::map<std::string,Model*>&
00247 getModels () const
00248 {
00249 return (models_);
00250 }
00251
00252 protected:
00254 void
00255 clear ();
00256
00258 bool
00259 addToHashTable (Model* model, const ORROctree::Node::Data* data1, const ORROctree::Node::Data* data2);
00260
00261 protected:
00262 float pair_width_;
00263 float voxel_size_;
00264 float max_coplanarity_angle_;
00265 bool ignore_coplanar_opps_;
00266
00267 std::map<std::string,Model*> models_;
00268 HashTable hash_table_;
00269 int num_of_cells_[3];
00270 };
00271 }
00272 }
00273
00274 #endif // PCL_RECOGNITION_MODEL_LIBRARY_H_