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 #ifndef PCL_RECOGNITION_HYPOTHESIS_VERIFICATION_H_
00038 #define PCL_RECOGNITION_HYPOTHESIS_VERIFICATION_H_
00039
00040 #include <pcl/pcl_macros.h>
00041 #include "pcl/recognition/hv/occlusion_reasoning.h"
00042 #include "pcl/recognition/impl/hv/occlusion_reasoning.hpp"
00043 #include <pcl/common/common.h>
00044 #include <pcl/search/kdtree.h>
00045 #include <pcl/filters/voxel_grid.h>
00046
00047 namespace pcl
00048 {
00049
00055 template<typename ModelT, typename SceneT>
00056 class PCL_EXPORTS HypothesisVerification
00057 {
00058
00059 protected:
00060
00061
00062
00063 std::vector<bool> mask_;
00064
00065
00066
00067 typename pcl::PointCloud<SceneT>::ConstPtr scene_cloud_;
00068
00069
00070
00071
00072 typename pcl::PointCloud<SceneT>::ConstPtr occlusion_cloud_;
00073
00074 bool occlusion_cloud_set_;
00075
00076
00077
00078
00079 typename pcl::PointCloud<SceneT>::Ptr scene_cloud_downsampled_;
00080
00081
00082
00083
00084 typename pcl::search::KdTree<SceneT>::Ptr scene_downsampled_tree_;
00085
00086
00087
00088
00089
00090
00091 typename std::vector<typename pcl::PointCloud<ModelT>::ConstPtr> visible_models_;
00092
00093 std::vector<typename pcl::PointCloud<pcl::Normal>::ConstPtr> visible_normal_models_;
00094
00095
00096
00097 typename std::vector<typename pcl::PointCloud<ModelT>::ConstPtr> complete_models_;
00098
00099 std::vector<typename pcl::PointCloud<pcl::Normal>::ConstPtr> complete_normal_models_;
00100
00101
00102
00103 int zbuffer_scene_resolution_;
00104
00105
00106
00107 int zbuffer_self_occlusion_resolution_;
00108
00109
00110
00111 float resolution_;
00112
00113
00114
00115
00116 float inliers_threshold_;
00117
00118
00119
00120
00121 float occlusion_thres_;
00122
00123
00124
00125
00126 bool requires_normals_;
00127
00128
00129
00130
00131 bool normals_set_;
00132 public:
00133
00134 HypothesisVerification ()
00135 {
00136 zbuffer_scene_resolution_ = 100;
00137 zbuffer_self_occlusion_resolution_ = 150;
00138 resolution_ = 0.005f;
00139 inliers_threshold_ = static_cast<float>(resolution_);
00140 occlusion_cloud_set_ = false;
00141 occlusion_thres_ = 0.005f;
00142 normals_set_ = false;
00143 requires_normals_ = false;
00144 }
00145
00146 bool getRequiresNormals() {
00147 return requires_normals_;
00148 }
00149
00150
00151
00152
00153
00154 void
00155 setResolution(float r) {
00156 resolution_ = r;
00157 }
00158
00159
00160
00161
00162
00163 void
00164 setOcclusionThreshold(float t) {
00165 occlusion_thres_ = t;
00166 }
00167
00168
00169
00170
00171
00172 void
00173 setInlierThreshold(float r) {
00174 inliers_threshold_ = r;
00175 }
00176
00177
00178
00179
00180
00181
00182 void
00183 getMask (std::vector<bool> & mask)
00184 {
00185 mask = mask_;
00186 }
00187
00188
00189
00190
00191
00192
00193
00194 void
00195 addCompleteModels (std::vector<typename pcl::PointCloud<ModelT>::ConstPtr> & complete_models)
00196 {
00197 complete_models_ = complete_models;
00198 }
00199
00200
00201
00202
00203
00204
00205 void
00206 addNormalsClouds (std::vector<pcl::PointCloud<pcl::Normal>::ConstPtr> & complete_models)
00207 {
00208 complete_normal_models_ = complete_models;
00209 normals_set_ = true;
00210 }
00211
00212
00213
00214
00215
00216 void
00217 addModels (std::vector<typename pcl::PointCloud<ModelT>::ConstPtr> & models, bool occlusion_reasoning = false)
00218 {
00219
00220 mask_.clear();
00221 if(!occlusion_cloud_set_) {
00222 PCL_WARN("Occlusion cloud not set, using scene_cloud instead...\n");
00223 occlusion_cloud_ = scene_cloud_;
00224 }
00225
00226 if (!occlusion_reasoning)
00227 visible_models_ = models;
00228 else
00229 {
00230
00231 if (scene_cloud_ == 0)
00232 {
00233 PCL_ERROR("setSceneCloud should be called before adding the model if reasoning about occlusions...");
00234 }
00235
00236 if (!occlusion_cloud_->isOrganized ())
00237 {
00238 PCL_WARN("Scene not organized... filtering using computed depth buffer\n");
00239 }
00240
00241 pcl::occlusion_reasoning::ZBuffering<ModelT, SceneT> zbuffer_scene (zbuffer_scene_resolution_, zbuffer_scene_resolution_, 1.f);
00242 if (!occlusion_cloud_->isOrganized ())
00243 {
00244 zbuffer_scene.computeDepthMap (occlusion_cloud_, true);
00245 }
00246
00247 for (size_t i = 0; i < models.size (); i++)
00248 {
00249
00250
00251 typename pcl::PointCloud<ModelT>::Ptr filtered (new pcl::PointCloud<ModelT> ());
00252 typename pcl::occlusion_reasoning::ZBuffering<ModelT, SceneT> zbuffer_self_occlusion (75, 75, 1.f);
00253 zbuffer_self_occlusion.computeDepthMap (models[i], true);
00254 std::vector<int> indices;
00255 zbuffer_self_occlusion.filter (models[i], indices, 0.005f);
00256 pcl::copyPointCloud (*models[i], indices, *filtered);
00257
00258 if(normals_set_ && requires_normals_) {
00259 pcl::PointCloud<pcl::Normal>::Ptr filtered_normals (new pcl::PointCloud<pcl::Normal> ());
00260 pcl::copyPointCloud(*complete_normal_models_[i], indices, *filtered_normals);
00261 visible_normal_models_.push_back(filtered_normals);
00262 }
00263
00264 typename pcl::PointCloud<ModelT>::ConstPtr const_filtered(new pcl::PointCloud<ModelT> (*filtered));
00265
00266
00267 if (occlusion_cloud_->isOrganized ())
00268 {
00269 filtered = pcl::occlusion_reasoning::filter<ModelT,SceneT> (occlusion_cloud_, const_filtered, 525.f, occlusion_thres_);
00270 }
00271 else
00272 {
00273 zbuffer_scene.filter (const_filtered, filtered, occlusion_thres_);
00274 }
00275
00276 visible_models_.push_back (filtered);
00277 }
00278
00279 complete_models_ = models;
00280 }
00281
00282 occlusion_cloud_set_ = false;
00283 normals_set_ = false;
00284 }
00285
00286
00287
00288
00289
00290
00291 void
00292 setSceneCloud (const typename pcl::PointCloud<SceneT>::Ptr & scene_cloud)
00293 {
00294
00295 complete_models_.clear();
00296 visible_models_.clear();
00297 visible_normal_models_.clear();
00298
00299 scene_cloud_ = scene_cloud;
00300 scene_cloud_downsampled_.reset(new pcl::PointCloud<SceneT>());
00301
00302 pcl::VoxelGrid<SceneT> voxel_grid;
00303 voxel_grid.setInputCloud (scene_cloud);
00304 voxel_grid.setLeafSize (resolution_, resolution_, resolution_);
00305 voxel_grid.setDownsampleAllData(true);
00306 voxel_grid.filter (*scene_cloud_downsampled_);
00307
00308
00309 scene_downsampled_tree_.reset (new pcl::search::KdTree<SceneT>);
00310 scene_downsampled_tree_->setInputCloud(scene_cloud_downsampled_);
00311 }
00312
00313 void setOcclusionCloud (const typename pcl::PointCloud<SceneT>::Ptr & occ_cloud)
00314 {
00315 occlusion_cloud_ = occ_cloud;
00316 occlusion_cloud_set_ = true;
00317 }
00318
00319
00320
00321
00322
00323
00324 virtual void
00325 verify ()=0;
00326 };
00327
00328 }
00329
00330 #endif