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 
00038 
00039 
00040 
00041 #ifndef PCL_FEATURES_IMPL_RIFT_H_
00042 #define PCL_FEATURES_IMPL_RIFT_H_
00043 
00044 #include <pcl/features/rift.h>
00045 
00047 template <typename PointInT, typename GradientT, typename PointOutT> void
00048 pcl::RIFTEstimation<PointInT, GradientT, PointOutT>::computeRIFT (
00049       const PointCloudIn &cloud, const PointCloudGradient &gradient, 
00050       int p_idx, float radius, const std::vector<int> &indices, 
00051       const std::vector<float> &sqr_distances, Eigen::MatrixXf &rift_descriptor)
00052 {
00053   if (indices.empty ())
00054   {
00055     PCL_ERROR ("[pcl::RIFTEstimation] Null indices points passed!\n");
00056     return;
00057   }
00058 
00059   
00060   int nr_distance_bins = static_cast<int> (rift_descriptor.rows ());
00061   int nr_gradient_bins = static_cast<int> (rift_descriptor.cols ());
00062 
00063   
00064   pcl::Vector3fMapConst p0 = cloud.points[p_idx].getVector3fMap ();
00065 
00066   
00067   rift_descriptor.setZero ();
00068   for (size_t idx = 0; idx < indices.size (); ++idx)
00069   {
00070     
00071     pcl::Vector3fMapConst point = cloud.points[indices[idx]].getVector3fMap ();
00072     Eigen::Map<const Eigen::Vector3f> gradient_vector (& (gradient.points[indices[idx]].gradient[0]));
00073 
00074     float gradient_magnitude = gradient_vector.norm ();
00075     float gradient_angle_from_center = acosf (gradient_vector.dot ((point - p0).normalized ()) / gradient_magnitude);
00076     if (!pcl_isfinite (gradient_angle_from_center))
00077       gradient_angle_from_center = 0.0;
00078 
00079     
00080     const float eps = std::numeric_limits<float>::epsilon ();
00081     float d = static_cast<float> (nr_distance_bins) * sqrtf (sqr_distances[idx]) / (radius + eps);
00082     float g = static_cast<float> (nr_gradient_bins) * gradient_angle_from_center / (static_cast<float> (M_PI) + eps);
00083 
00084     
00085     int d_idx_min = (std::max)(static_cast<int> (ceil (d - 1)), 0);
00086     int d_idx_max = (std::min)(static_cast<int> (floor (d + 1)), nr_distance_bins - 1);
00087     int g_idx_min = static_cast<int> (ceil (g - 1));
00088     int g_idx_max = static_cast<int> (floor (g + 1));
00089 
00090     
00091     for (int g_idx = g_idx_min; g_idx <= g_idx_max; ++g_idx)  
00092     {
00093       
00094       int g_idx_wrapped = ((g_idx + nr_gradient_bins) % nr_gradient_bins); 
00095 
00096       for (int d_idx = d_idx_min; d_idx <= d_idx_max; ++d_idx)
00097       {
00098         
00099         float w = (1.0f - fabsf (d - static_cast<float> (d_idx))) * (1.0f - fabsf (g - static_cast<float> (g_idx)));
00100 
00101         rift_descriptor (d_idx, g_idx_wrapped) += w * gradient_magnitude;
00102       }
00103     }
00104   }
00105 
00106   
00107   rift_descriptor.normalize ();
00108 }
00109 
00110 
00112 template <typename PointInT, typename GradientT, typename PointOutT> void
00113 pcl::RIFTEstimation<PointInT, GradientT, PointOutT>::computeFeature (PointCloudOut &output)
00114 {
00115   
00116   if (search_radius_ == 0.0)
00117   {
00118     PCL_ERROR ("[pcl::%s::computeFeature] The search radius must be set before computing the feature!\n",
00119                getClassName ().c_str ());
00120     output.width = output.height = 0;
00121     output.points.clear ();
00122     return;
00123   }
00124 
00125   
00126   if (nr_gradient_bins_ <= 0)
00127   {
00128     PCL_ERROR ("[pcl::%s::computeFeature] The number of gradient bins must be greater than zero!\n",
00129                getClassName ().c_str ());
00130     output.width = output.height = 0;
00131     output.points.clear ();
00132     return;
00133   }
00134   if (nr_distance_bins_ <= 0)
00135   {
00136     PCL_ERROR ("[pcl::%s::computeFeature] The number of distance bins must be greater than zero!\n",
00137                getClassName ().c_str ());
00138     output.width = output.height = 0;
00139     output.points.clear ();
00140     return;
00141   }
00142 
00143   
00144   if (!gradient_)
00145   {
00146     PCL_ERROR ("[pcl::%s::computeFeature] No input gradient was given!\n", getClassName ().c_str ());
00147     output.width = output.height = 0;
00148     output.points.clear ();
00149     return;
00150   }
00151   if (gradient_->points.size () != surface_->points.size ())
00152   {
00153     PCL_ERROR ("[pcl::%s::computeFeature] ", getClassName ().c_str ());
00154     PCL_ERROR ("The number of points in the input dataset differs from the number of points in the gradient!\n");
00155     output.width = output.height = 0;
00156     output.points.clear ();
00157     return;
00158   }
00159 
00160   Eigen::MatrixXf rift_descriptor (nr_distance_bins_, nr_gradient_bins_);
00161   std::vector<int> nn_indices;
00162   std::vector<float> nn_dist_sqr;
00163  
00164   
00165   for (size_t idx = 0; idx < indices_->size (); ++idx)
00166   {
00167     
00168     tree_->radiusSearch ((*indices_)[idx], search_radius_, nn_indices, nn_dist_sqr);
00169 
00170     
00171     computeRIFT (*surface_, *gradient_, (*indices_)[idx], static_cast<float> (search_radius_), nn_indices, nn_dist_sqr, rift_descriptor);
00172 
00173     
00174     int bin = 0;
00175     for (int g_bin = 0; g_bin < rift_descriptor.cols (); ++g_bin)
00176       for (int d_bin = 0; d_bin < rift_descriptor.rows (); ++d_bin)
00177         output.points[idx].histogram[bin++] = rift_descriptor (d_bin, g_bin);
00178   }
00179 }
00180 
00181 #define PCL_INSTANTIATE_RIFTEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::RIFTEstimation<T,NT,OutT>;
00182 
00183 #endif    // PCL_FEATURES_IMPL_RIFT_H_ 
00184