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_OBJECT_MODEL_H
00040 #define PCL_OBJECT_MODEL_H
00041
00042 #include <vector>
00043
00044 #include <Eigen/Geometry>
00045
00046 #include <pcl/point_types.h>
00047 #include <pcl/point_cloud.h>
00048 #include <pcl/range_image/range_image.h>
00049 #include <pcl/pcl_macros.h>
00050 #include <pcl/features/narf.h>
00051
00052
00053 namespace pcl {
00054
00055
00056 class Narf;
00057 class NarfKeypoint;
00058
00062 class ObjectModel
00063 {
00064 public:
00065
00066 typedef PointXYZ PointType;
00067 typedef PointCloud<PointType> PointCloudType;
00068
00069
00070 struct ValidationPoints
00071 {
00072 std::vector<Eigen::Vector3f> surface;
00073 std::vector<Eigen::Vector3f> border;
00074 };
00075
00076
00078 ObjectModel();
00080 virtual ~ObjectModel();
00081
00082
00084 template <typename FeatureType>
00085 inline static void freeFeatureListMemory(std::vector<std::vector<FeatureType*>*>& feature_list);
00086
00087
00089 void clear(bool keep_point_cloud=false);
00090
00092 void clearViews();
00093
00095 void updateCenterAndRadius();
00096
00098 float getMaxAngleSize(const Eigen::Affine3f& viewer_pose) const;
00099
00101 void createView(const Eigen::Affine3f& viewer_pose, float angular_resolution, RangeImage& view) const;
00102
00104 void addView(const Eigen::Affine3f& viewer_pose, float angular_resolution);
00105
00118 void sampleViews2D(int no_of_views=10, int first_layer=0, int last_layer=0,
00119 float angular_resolution=deg2rad(0.5f), float distance=-1.0f,
00120 std::vector<RangeImage, Eigen::aligned_allocator<RangeImage> >* views=NULL);
00121
00128 void sampleViews3D(float sample_angular_resolution=deg2rad(40.0f), float angular_resolution=deg2rad(0.4f),
00129 float distance=-1.0f, std::vector<RangeImage, Eigen::aligned_allocator<RangeImage> >* views=NULL);
00130
00133 void addNoise(float max_noise);
00134
00141 void addSimulatedView(const Eigen::Vector3f& direction, float angular_resolution=deg2rad(0.5f), float distance=-1.0,
00142 std::vector<RangeImage, Eigen::aligned_allocator<RangeImage> >* views=NULL);
00143
00149 void extractNARFsForCompleteSurface(unsigned int descriptor_size, float size_in_world, bool rotation_invariant, std::vector<std::vector<Narf*>*>& features) const;
00150
00156 void extractNARFsForInterestPoints(unsigned int descriptor_size, float size_in_world, bool rotation_invariant,
00157 NarfKeypoint& interest_point_detector, std::vector<std::vector<Narf*>*>& features) const;
00158
00160 void getTransformedPointCloud(const Eigen::Affine3f& transformation, PointCloudType& output) const;
00161
00168 void
00169 updateValidationPoints(unsigned int no_of_surface_points=50, unsigned int no_of_border_points=25,
00170 float sample_resolution=deg2rad(20.0f), NarfKeypoint* interest_point_detector=NULL,
00171 float support_size=-1.0f);
00172
00174 inline int getClosestValidationPointViewIdx(const Eigen::Affine3f& pose) const;
00175
00177 Eigen::Affine3f doFastICP(const Eigen::Affine3f& initial_guess, const RangeImage& range_image,
00178 int search_radius=3, int no_of_surface_points_to_use = 25,
00179 int no_of_border_points_to_use = 10, int num_iterations = 10,
00180 float max_distance_start=-1.0f, float max_distance_end=-1.0f) const;
00181
00183 Eigen::Affine3f
00184 doSlowICP(const Eigen::Affine3f& initial_guess, const RangeImage& range_image, int search_radius,
00185 int num_iterations, float max_distance_start, float max_distance_end) const;
00186
00188 void extractInterestPoints(int view_ix, float support_size, NarfKeypoint& interest_point_detector,
00189 PointCloud<InterestPoint>& interest_points) const;
00190
00192 Eigen::Affine3f getViewerPose(const Eigen::Vector3f& viewpoint) const;
00193
00195 float getMaximumPlaneSize (float initial_max_plane_error) const;
00196
00197
00199 inline int getId() const { return id_; }
00201 inline const std::string& getName() const { return name_; }
00203 inline const PointCloudType& getPointCloud() const { return point_cloud_; }
00205 inline PointCloudType& getPointCloud() { return point_cloud_; }
00207 inline const std::vector<RangeImage, Eigen::aligned_allocator<RangeImage> >& getViews() const { return views_; }
00209 inline const RangeImage& getView(int index) const { return views_[index]; }
00211 inline float getRadius() const { return radius_; }
00213 inline const Eigen::Vector3f& getCenter() const { return center_; }
00215 inline const std::vector<ValidationPoints>& getValidationPoints() const { return validation_points_;}
00217 bool isSingleViewModel() const { return is_single_view_model_;}
00218
00219
00220
00221
00223 void setId(int id) { id_=id; }
00225 void setName(const std::string name) { name_=name; }
00227 void setIsSingleViewModel(bool is_single_view_model) { is_single_view_model_=is_single_view_model;}
00228
00229 protected:
00230
00234 static void getUniformlyDistributedPoints(const std::vector<Eigen::Vector3f>& points, int no_of_points, std::vector<Eigen::Vector3f>& result);
00235
00236
00237 int id_;
00238 std::string name_;
00239 PointCloudType point_cloud_;
00240 std::vector<RangeImage, Eigen::aligned_allocator<RangeImage> > views_;
00241 std::vector<RangeImage, Eigen::aligned_allocator<RangeImage> > views_for_validation_points_;
00242 std::vector<ValidationPoints> validation_points_;
00243 Eigen::Vector3f center_;
00244 float radius_;
00245 bool is_single_view_model_;
00246
00247 public:
00248 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00249 };
00250
00251 }
00252
00253 #include "object_model.hpp"
00254
00255 #endif
00256