Go to the documentation of this file.00001
00002
00003 #ifndef PCL_OBJECT_RECOGNITION_HELPER_H
00004 #define PCL_OBJECT_RECOGNITION_HELPER_H
00005
00006 #include <vector>
00007 #include <iostream>
00008
00009 #include "pcl/common/angles.h"
00010 #include "pcl/io/pcd_io.h"
00011 #include "object_model_list.h"
00012 #include "pcl/range_image/range_image_planar.h"
00013 #include "pcl/features/range_image_border_extractor.h"
00014 #include "pcl/keypoints/narf_keypoint.h"
00015 #include "pcl/common/poses_from_matches.h"
00016 #include <narf_recognition/false_positives_filter.h>
00017
00018 namespace pcl {
00019
00023 class ObjectRecognitionHelper
00024 {
00025 public:
00026
00027
00028
00029
00030 struct Parameters
00031 {
00032 Parameters() : verbose(true), max_no_of_threads(1), angular_resolution(deg2rad(0.5f)),
00033 coordinate_frame(RangeImage::CAMERA_FRAME), set_unseen_to_max_range(false),
00034 single_view_model(false), no_of_model_views(10),
00035 no_of_surface_validation_points(50), no_of_border_validation_points(25),
00036 feature_descriptor_size(36), use_rotation_invariance(false),
00037 support_size(0.3), noise_level(0.05), max_descriptor_distance(0.07), use_kdtree(false),
00038 max_validation_point_error_factor(0.15),
00039 icp_max_distance_start_factor(0.15), icp_max_distance_end_factor(0.05),
00040 view_sampling_first_layer(0), view_sampling_last_layer(0),
00041 sample_views_3d(false), view_sampling_3D_resolution(deg2rad(50.0f))
00042 {}
00043 bool verbose;
00044 int max_no_of_threads;
00045 float angular_resolution;
00046 RangeImage::CoordinateFrame coordinate_frame;
00047 bool set_unseen_to_max_range;
00048 bool single_view_model;
00049 int no_of_model_views;
00050 int no_of_surface_validation_points;
00051 int no_of_border_validation_points;
00052 int feature_descriptor_size;
00053 bool use_rotation_invariance;
00054 float support_size;
00055 float noise_level;
00056 float max_descriptor_distance;
00057 bool use_kdtree;
00058 float max_validation_point_error_factor;
00059 float icp_max_distance_start_factor;
00060 float icp_max_distance_end_factor;
00061 int view_sampling_first_layer;
00062 int view_sampling_last_layer;
00063 bool sample_views_3d;
00064 float view_sampling_3D_resolution;
00065 };
00066 struct Timings
00067 {
00068 double scene_range_image_creation;
00069 double scene_interest_point_extraction;
00070 double scene_feature_extraction;
00071 double feature_matching;
00072 double initial_pose_estimation;
00073 double false_positives_filtering;
00074 };
00075 struct IntermediateElements {
00076 IntermediateElements() : spherical_scene_range_image_ptr(new RangeImage),
00077 planar_scene_range_image_ptr(new RangeImagePlanar),
00078 scene_range_image_ptr(spherical_scene_range_image_ptr)
00079 {
00080 interest_point_detector_model.setRangeImageBorderExtractor(&border_extractor_model);
00081 interest_point_detector_scene.setRangeImageBorderExtractor(&border_extractor_scene);
00082 }
00083
00084 ObjectModelList object_models;
00085 std::vector<Narf*> database_features;
00086 std::vector<ObjectModelList::FeatureSource> database_feature_sources;
00087 KdTreeFLANN<Narf*> database_features_kdtree;
00088 RangeImageBorderExtractor border_extractor_model;
00089 NarfKeypoint interest_point_detector_model;
00090 boost::shared_ptr<RangeImage> spherical_scene_range_image_ptr;
00091 boost::shared_ptr<RangeImagePlanar> planar_scene_range_image_ptr;
00092 boost::shared_ptr<RangeImage> scene_range_image_ptr;
00093 Eigen::Affine3f transformation_into_original_coordinate_frame;
00094 RangeImageBorderExtractor border_extractor_scene;
00095 NarfKeypoint interest_point_detector_scene;
00096 std::vector<Narf*> scene_features;
00097 std::vector<std::vector<PointCorrespondences6DVector > > feature_matches;
00098 std::vector<PosesFromMatches::PoseEstimatesVector> pose_estimates_per_model;
00099 };
00100
00101
00103 ObjectRecognitionHelper();
00105 ~ObjectRecognitionHelper();
00106
00107
00109 bool
00110 addObjectModelsFromPcdFiles(std::vector<std::string>& file_names);
00111
00113 bool
00114 extractModelFeatures();
00115
00117 bool
00118 createRangeImageFromPcdFile(const std::string& file_name);
00119
00120
00121
00122
00123
00125 bool
00126 createRangeImageFromPointCloud(const PointCloud<PointXYZ>& point_cloud,
00127 const PointCloud<PointWithViewpoint>* far_ranges=NULL);
00128
00130 bool
00131 extractSceneFeatures();
00132
00134 void
00135 extractPoseEstimates();
00136
00138 std::vector<PosesFromMatches::PoseEstimatesVector>&
00139 filterFalsePositives();
00140
00142 void
00143 printTimings() const;
00144
00145
00147 Parameters&
00148 getParameters() { return parameters_;}
00149
00151 Timings&
00152 getTimings () { return timings_;}
00153
00155 IntermediateElements&
00156 getIntermediateElements () { return intermediate_elements_;}
00157
00159 FalsePositivesFilter&
00160 getFalsePositivesFilter () { return false_positives_filter_;}
00161
00162
00163
00164 protected:
00165
00167 void
00168 clearSceneFeatures();
00169
00171 void
00172 clearObjectModels();
00173
00175 void
00176 clearModelFeatures();
00177
00178
00179 Parameters parameters_;
00180 Timings timings_;
00181 IntermediateElements intermediate_elements_;
00182 FalsePositivesFilter false_positives_filter_;
00183
00184
00185
00186 };
00187
00188 }
00189
00190 #endif
00191