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 #ifndef PCL_FEATURES_IMPL_RSD_H_
00039 #define PCL_FEATURES_IMPL_RSD_H_
00040
00041 #include <cfloat>
00042 #include "pcl/features/rsd.h"
00043
00045 template <typename PointInT, typename PointNT, typename PointOutT> inline void
00046 pcl::computeRSD (const pcl::PointCloud<PointInT> &surface, const pcl::PointCloud<PointNT> &normals,
00047 const std::vector<int> &indices, double max_dist,
00048 int nr_subdiv, double plane_radius, PointOutT &radii)
00049 {
00050
00051 std::vector<std::vector<double> > min_max_angle_by_dist (nr_subdiv);
00052 min_max_angle_by_dist[0].resize (2);
00053 min_max_angle_by_dist[0][0] = min_max_angle_by_dist[0][1] = 0.0;
00054 for (int di=1; di<nr_subdiv; di++)
00055 {
00056 min_max_angle_by_dist[di].resize (2);
00057 min_max_angle_by_dist[di][0] = +DBL_MAX;
00058 min_max_angle_by_dist[di][1] = -DBL_MAX;
00059 }
00060
00061
00062 std::vector<int>::const_iterator i, begin (indices.begin()), end (indices.end());
00063 for(i = begin+1; i != end; ++i)
00064 {
00065
00066 double cosine = normals.points[*i].normal[0] * normals.points[*begin].normal[0] +
00067 normals.points[*i].normal[1] * normals.points[*begin].normal[1] +
00068 normals.points[*i].normal[2] * normals.points[*begin].normal[2];
00069 if (cosine > 1) cosine = 1;
00070 if (cosine < -1) cosine = -1;
00071 double angle = acos (cosine);
00072 if (angle > M_PI/2) angle = M_PI - angle;
00073
00074
00075 double dist = sqrt ((surface.points[*i].x - surface.points[*begin].x) * (surface.points[*i].x - surface.points[*begin].x) +
00076 (surface.points[*i].y - surface.points[*begin].y) * (surface.points[*i].y - surface.points[*begin].y) +
00077 (surface.points[*i].z - surface.points[*begin].z) * (surface.points[*i].z - surface.points[*begin].z));
00078
00079 if (dist > max_dist)
00080 continue;
00081
00082
00083 int bin_d = (int) floor (nr_subdiv * dist / max_dist);
00084
00085
00086 if (min_max_angle_by_dist[bin_d][0] > angle) min_max_angle_by_dist[bin_d][0] = angle;
00087 if (min_max_angle_by_dist[bin_d][1] < angle) min_max_angle_by_dist[bin_d][1] = angle;
00088 }
00089
00090
00091 double Amint_Amin = 0, Amint_d = 0;
00092 double Amaxt_Amax = 0, Amaxt_d = 0;
00093 for (int di=0; di<nr_subdiv; di++)
00094 {
00095
00096 if (min_max_angle_by_dist[di][1] >= 0)
00097 {
00098 double p_min = min_max_angle_by_dist[di][0];
00099 double p_max = min_max_angle_by_dist[di][1];
00100
00101 double f = (di+0.5)*max_dist/nr_subdiv;
00102
00103 Amint_Amin += p_min * p_min;
00104 Amint_d += p_min * f;
00105 Amaxt_Amax += p_max * p_max;
00106 Amaxt_d += p_max * f;
00107 }
00108 }
00109 radii.r_max = Amint_Amin == 0 ? plane_radius : std::min (Amint_d/Amint_Amin, plane_radius);
00110 radii.r_min = Amaxt_Amax == 0 ? plane_radius : std::min (Amaxt_d/Amaxt_Amax, plane_radius);
00111 }
00112
00114 template <typename PointInT, typename PointNT, typename PointOutT> void
00115 pcl::RSDEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
00116 {
00117
00118 if (!normals_)
00119 {
00120 ROS_ERROR ("[pcl::%s::computeFeature] No input dataset containing normals was given!", getClassName ().c_str ());
00121 output.width = output.height = 0;
00122 output.points.clear ();
00123 return;
00124 }
00125 if (normals_->points.size () != surface_->points.size ())
00126 {
00127 ROS_ERROR ("[pcl::%s::computeFeature] The number of points in the input dataset differs from the number of points in the dataset containing the normals!", getClassName ().c_str ());
00128 output.width = output.height = 0;
00129 output.points.clear ();
00130 return;
00131 }
00132
00133
00134 if (search_radius_ < 0)
00135 {
00136 ROS_ERROR ("[pcl::%s::computeFeature] A search radius needs to be set!", getClassName ().c_str ());
00137 output.width = output.height = 0;
00138 output.points.clear ();
00139 return;
00140 }
00141
00142
00143
00144 std::vector<int> nn_indices;
00145 std::vector<float> nn_sqr_dists;
00146
00147
00148 for (size_t idx = 0; idx < indices_->size (); ++idx)
00149 {
00150
00151 searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_sqr_dists);
00152 computeRSD (*surface_, *normals_, nn_indices, search_radius_, nr_subdiv_, plane_radius_, output.points[idx]);
00153 }
00154 }
00155
00156 #define PCL_INSTANTIATE_RSDEstimation(T,NT,OutT) template class pcl::RSDEstimation<T,NT,OutT>;
00157
00158 #endif // PCL_FEATURES_IMPL_VFH_H_