correspondence_rejection_features.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  *
00037  */
00038 #ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_FEATURES_HPP_
00039 #define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_FEATURES_HPP_
00040 
00042 void
00043 pcl::registration::CorrespondenceRejectorFeatures::getRemainingCorrespondences (
00044     const pcl::Correspondences& original_correspondences, 
00045     pcl::Correspondences& remaining_correspondences)
00046 {
00047   unsigned int number_valid_correspondences = 0;
00048   remaining_correspondences.resize (original_correspondences.size ());
00049   // For each set of features, go over each correspondence from input_correspondences_
00050   for (size_t i = 0; i < input_correspondences_->size (); ++i)
00051   {
00052     // Go over the map of features
00053     for (FeaturesMap::const_iterator it = features_map_.begin (); it != features_map_.end (); ++it)
00054     {
00055       // Check if the score in feature space is above the given threshold
00056       // (assume that the number of feature correspondenecs is the same as the number of point correspondences)
00057       if (!it->second->isCorrespondenceValid (static_cast<int> (i)))
00058         break;
00059 
00060       remaining_correspondences[number_valid_correspondences] = original_correspondences[i];
00061       ++number_valid_correspondences;
00062     }
00063   }
00064   remaining_correspondences.resize (number_valid_correspondences);
00065 }
00066 
00068 template <typename FeatureT> inline void 
00069 pcl::registration::CorrespondenceRejectorFeatures::setSourceFeature (
00070     const typename pcl::PointCloud<FeatureT>::ConstPtr &source_feature, const std::string &key)
00071 {
00072   if (features_map_.count (key) == 0)
00073     features_map_[key].reset (new FeatureContainer<FeatureT>);
00074   boost::static_pointer_cast<FeatureContainer<FeatureT> > (features_map_[key])->setSourceFeature (source_feature);
00075 }
00076 
00078 template <typename FeatureT> inline typename pcl::PointCloud<FeatureT>::ConstPtr 
00079 pcl::registration::CorrespondenceRejectorFeatures::getSourceFeature (const std::string &key)
00080 {
00081   if (features_map_.count (key) == 0)
00082     return (boost::shared_ptr<pcl::PointCloud<const FeatureT> > ());
00083   else
00084     return (boost::static_pointer_cast<FeatureContainer<FeatureT> > (features_map_[key])->getSourceFeature ());
00085 }
00086 
00088 template <typename FeatureT> inline void 
00089 pcl::registration::CorrespondenceRejectorFeatures::setTargetFeature (
00090     const typename pcl::PointCloud<FeatureT>::ConstPtr &target_feature, const std::string &key)
00091 {
00092   if (features_map_.count (key) == 0)
00093     features_map_[key].reset (new FeatureContainer<FeatureT>);
00094   boost::static_pointer_cast<FeatureContainer<FeatureT> > (features_map_[key])->setTargetFeature (target_feature);
00095 }
00096 
00098 template <typename FeatureT> inline typename pcl::PointCloud<FeatureT>::ConstPtr 
00099 pcl::registration::CorrespondenceRejectorFeatures::getTargetFeature (const std::string &key)
00100 {
00101   typedef pcl::PointCloud<FeatureT> FeatureCloud;
00102   typedef typename FeatureCloud::ConstPtr FeatureCloudConstPtr;
00103 
00104   if (features_map_.count (key) == 0)
00105     return (boost::shared_ptr<const pcl::PointCloud<FeatureT> > ());
00106   else
00107     return (boost::static_pointer_cast<FeatureContainer<FeatureT> > (features_map_[key])->getTargetFeature ());
00108 }
00109 
00111 template <typename FeatureT> inline void 
00112 pcl::registration::CorrespondenceRejectorFeatures::setDistanceThreshold (
00113     double thresh, const std::string &key)
00114 {
00115   if (features_map_.count (key) == 0)
00116     features_map_[key].reset (new FeatureContainer<FeatureT>);
00117   boost::static_pointer_cast<FeatureContainer<FeatureT> > (features_map_[key])->setDistanceThreshold (thresh);
00118 }
00119 
00121 inline bool
00122 pcl::registration::CorrespondenceRejectorFeatures::hasValidFeatures ()
00123 {
00124   if (features_map_.empty ())
00125     return (false);
00126   FeaturesMap::const_iterator feature_itr;
00127   for (feature_itr = features_map_.begin (); feature_itr != features_map_.end (); ++feature_itr)
00128     if (!feature_itr->second->isValid ())
00129       return (false);
00130   return (true);
00131 }
00132 
00134 template <typename FeatureT> inline void 
00135 pcl::registration::CorrespondenceRejectorFeatures::setFeatureRepresentation (
00136   const typename pcl::PointRepresentation<FeatureT>::ConstPtr &fr,
00137   const std::string &key)
00138 {
00139   if (features_map_.count (key) == 0)
00140     features_map_[key].reset (new FeatureContainer<FeatureT>);
00141   boost::static_pointer_cast<FeatureContainer<FeatureT> > (features_map_[key])->setFeatureRepresentation (fr);
00142 }
00143 
00144 
00145 #endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_FEATURES_HPP_ */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:14:44