false_positives_filter.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  */
00035 
00036 /* \author Bastian Steder */
00037 
00038 
00039 #ifndef PCL_FALSE_POSITIVES_FILTER_H
00040 #define PCL_FALSE_POSITIVES_FILTER_H
00041 
00042 #include <pcl/common/poses_from_matches.h>
00043 #include <pcl/range_image/range_image.h>
00044 #include <narf_recognition/object_model.h>
00045 #include <Eigen/Geometry>
00046 
00047 namespace pcl {
00048 
00052 class FalsePositivesFilter
00053 {
00054   public:
00055     //-----TYPEDEFS-----
00056     typedef PosesFromMatches::PoseEstimate PoseEstimate;
00057     typedef PosesFromMatches::PoseEstimatesVector PoseEstimates;
00058     
00059     //-----CLASSES/STRUCTS-----
00060     struct Parameters
00061     {
00062       Parameters () : max_no_of_threads (1), maximum_range_for_found_objects (-1.0), do_validation_point_filtering (true),
00063                      check_borders_for_validation_points (true), weight_for_see_through_points (5.0),
00064                      pixel_search_radius_for_validation_points_score (2), max_validation_point_error (0.1f),
00065                      do_pose_similarity_filtering (true),
00066                      do_icp (true),
00067                      icp_pixel_search_radius (3), icp_num_iterations (10), 
00068                      icp_max_distance_start (0.2), icp_max_distance_end (0.05),
00069                      //icp_min_num_points (20), icp_max_num_points (200),
00070                      fast_icp_no_of_surface_points_to_use (50), fast_icp_no_of_border_points_to_use (50),
00071                      max_no_of_remaining_pose_estimates_for_icp (25),
00072                      max_validation_point_error_before_icp_factor (2.0f),
00073                      min_validation_point_score (0.4f), min_validation_point_score_to_go_on_factor (0.75),
00074                      min_no_of_tested_validation_points (30), max_no_of_validation_points_before_icp (50),
00075                      min_validation_point_score_before_icp_factor (0.5),
00076                      do_view_simulation_filtering (false),
00077                      min_view_simulation_score (0.5), pixel_search_radius_for_view_simulation_score (2),
00078                      check_borders_for_view_simulation (true), check_normals_for_view_simulation (true)
00079                      //weightForSeeThroughValidationPoint (25.0), weightForKnownObstacleValidationPoint (0.5),
00080                      //weightForUnknownObstacleValidationPoint (15.0), weightForFarRangeValidationPoint (5.0),
00081       {}
00082       
00083       int max_no_of_threads;
00084       float maximum_range_for_found_objects;
00085       bool do_validation_point_filtering;
00086       bool check_borders_for_validation_points;
00087       float weight_for_see_through_points;
00088       bool do_pose_similarity_filtering;
00089       bool do_icp;
00090       int icp_pixel_search_radius;
00091       float icp_num_iterations;
00092       float icp_max_distance_start;
00093       float icp_max_distance_end;
00094       //int icp_min_num_points;
00095       //int icp_max_num_points;
00096       int fast_icp_no_of_surface_points_to_use;
00097       int fast_icp_no_of_border_points_to_use;
00098       int max_no_of_remaining_pose_estimates_for_icp;
00099       int pixel_search_radius_for_validation_points_score;
00100       float max_validation_point_error;
00101       float max_validation_point_error_before_icp_factor;
00102       float min_validation_point_score;
00103       float min_validation_point_score_to_go_on_factor;
00104       int min_no_of_tested_validation_points;
00105       int max_no_of_validation_points_before_icp;
00106       float min_validation_point_score_before_icp_factor;
00107       bool do_view_simulation_filtering;
00108       float min_view_simulation_score;
00109       int pixel_search_radius_for_view_simulation_score;
00110       bool check_borders_for_view_simulation,
00111            check_normals_for_view_simulation;
00112       //float weightForSeeThroughValidationPoint;
00113       //float weightForKnownObstacleValidationPoint;
00114       //float weightForUnknownObstacleValidationPoint;
00115       //float weightForFarRangeValidationPoint;
00116     };
00117     
00118     //-----CONSTRUCTOR&DESTRUCTOR-----
00120     FalsePositivesFilter ();
00122     virtual ~FalsePositivesFilter ();
00123     
00124     //-----STATIC METHODS-----
00125 
00126     //-----METHODS-----
00130     void
00131       viewSimulation (const RangeImage& scene, const ObjectModel& model, PoseEstimates& pose_estimates,
00132                       float min_score, float max_dist_error=-1.0f, std::vector<RangeImage>* results=NULL) const;
00133 
00135     void
00136       maximumRange (const RangeImage& scene, const ObjectModel& model,
00137                     PoseEstimates& pose_estimates, float maximum_range) const;
00138 
00140     void
00141       similarPoses (const ObjectModel& model, PoseEstimates& pose_estimates) const;
00142     
00144     void
00145       validationPoints (const RangeImage& scene, const ObjectModel& model, PoseEstimates& pose_estimates,
00146                        float min_score, float max_dist_error=-1.0f) const;
00147     
00149     void
00150       sortAndApplyMinScore (PoseEstimates& pose_estimates, float min_score) const;
00151     
00153     void
00154       keepBest (PoseEstimates& pose_estimates, int max_no_of_results) const;
00155     
00157     void
00158       filterResults (const RangeImage& scene, const ObjectModel& model, PoseEstimates& pose_estimates) const;
00159     
00161     void
00162       doIcp (const RangeImage& scene, const ObjectModel& model, PoseEstimates& pose_estimates, bool fast_icp) const;
00163     
00165     Parameters&
00166       getParameters () { return parameters_;}
00167     
00169     void
00170       setViewSimulationImagesPtr (std::vector<RangeImage>* vsi_ptr) { view_simulation_images_ = vsi_ptr;}
00171     
00172   protected:
00173     //-----PROTECTED METHODS-----
00176     void
00177       getRangeImagesForComparison (const RangeImage& scene, const ObjectModel& model,
00178                                   const PoseEstimate& pose_estimate,
00179                                   RangeImage& object_image, RangeImage& scene_sub_image) const;
00180     float
00181       getViewSimulationScore (const RangeImage& object_image, const RangeImage& scene_sub_image,
00182                              float max_dist_error, float& border_score, RangeImage* score_image=NULL) const;
00183     float
00184       getViewSimulationNormalsScore (const RangeImage& object_image, const RangeImage& scene_sub_image,
00185                                     RangeImage* score_image=NULL) const;
00186     float
00187       getSurfaceValidationPointScore (const std::vector<Eigen::Vector3f>& surface_points,
00188                                      const Eigen::Affine3f& pose, const RangeImage& scene, float max_dist_error,
00189                                      float min_score) const;
00190     float
00191       getBorderValidationPointScore (const std::vector<Eigen::Vector3f>& border_points, const Eigen::Affine3f& pose,
00192                                     const RangeImage& scene, float max_dist_error, float min_score) const;
00193     
00194     //-----PROTECTED VARIABLES-----
00195     Parameters parameters_;
00196     std::vector<RangeImage>* view_simulation_images_;
00197 };
00198 
00199 } // namespace end
00200 
00201 #endif
00202 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


chair_recognition
Author(s): Jan Metzger
autogenerated on Wed Dec 26 2012 15:54:47