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_PFH_H_
00039 #define PCL_FEATURES_IMPL_PFH_H_
00040
00041 #include "pcl/features/pfh.h"
00042
00044 template <typename PointInT, typename PointNT, typename PointOutT> bool
00045 pcl::PFHEstimation<PointInT, PointNT, PointOutT>::computePairFeatures (
00046 const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
00047 int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4)
00048 {
00049
00050 Eigen::Vector4f delta = cloud.points[q_idx].getVector4fMap () - cloud.points[p_idx].getVector4fMap ();
00051 delta[3] = 0;
00052
00053
00054 float distance_sqr = delta.squaredNorm ();
00055
00056 if (distance_sqr == 0)
00057 {
00058 ROS_ERROR ("Euclidean distance between points %d and %d is 0!", p_idx, q_idx);
00059 f1 = f2 = f3 = f4 = 0;
00060 return (false);
00061 }
00062
00063
00064 f4 = sqrt (distance_sqr);
00065
00066
00067
00068 pcl::Vector4fMapConst u = normals.points[p_idx].getNormalVector4fMap ();
00069
00070
00071
00072 f3 = u.dot (delta) / f4;
00073
00074
00075 Eigen::Vector4f v = Eigen::Vector4f::Zero ();
00076 v = delta.cross3 (u);
00077
00078 distance_sqr = v.squaredNorm ();
00079 if (distance_sqr == 0)
00080 {
00081 ROS_ERROR ("Norm of Delta x U is 0 for point %d and %d!", p_idx, q_idx);
00082 f1 = f2 = f3 = f4 = 0;
00083 return (false);
00084 }
00085
00086
00087 Eigen::Vector4f nq (normals.points[q_idx].normal_x,
00088 normals.points[q_idx].normal_y,
00089 normals.points[q_idx].normal_z,
00090 0);
00091
00092
00093 v /= sqrt (distance_sqr);
00094
00095
00096 delta = u.cross3 (v);
00097
00098
00099
00100 f2 = v.dot (nq);
00101
00102
00103
00104 f1 = atan2f (delta.dot (nq), u.dot (nq));
00105
00106 return (true);
00107 }
00108
00110 template <typename PointInT, typename PointNT, typename PointOutT> void
00111 pcl::PFHEstimation<PointInT, PointNT, PointOutT>::computePointPFHSignature (
00112 const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
00113 const std::vector<int> &indices, int nr_split, Eigen::VectorXf &pfh_histogram)
00114 {
00115 int h_index, h_p;
00116
00117
00118 pfh_histogram.setZero ();
00119
00120
00121 float hist_incr = 100.0 / (indices.size () * indices.size () - 1);
00122
00123
00124 for (size_t i_idx = 0; i_idx < indices.size (); ++i_idx)
00125 {
00126 for (size_t j_idx = 0; j_idx < indices.size (); ++j_idx)
00127 {
00128
00129 if (i_idx == j_idx)
00130 continue;
00131
00132
00133 if (!computePairFeatures (cloud, normals, indices[i_idx], indices[j_idx],
00134 pfh_tuple_[0], pfh_tuple_[1], pfh_tuple_[2], pfh_tuple_[3]))
00135 continue;
00136
00137
00138 f_index_[0] = floor (nr_split * ((pfh_tuple_[0] + M_PI) * d_pi_));
00139 if (f_index_[0] < 0) f_index_[0] = 0;
00140 if (f_index_[0] >= nr_split) f_index_[0] = nr_split - 1;
00141
00142 f_index_[1] = floor (nr_split * ((pfh_tuple_[1] + 1.0) * 0.5));
00143 if (f_index_[1] < 0) f_index_[1] = 0;
00144 if (f_index_[1] >= nr_split) f_index_[1] = nr_split - 1;
00145
00146 f_index_[2] = floor (nr_split * ((pfh_tuple_[2] + 1.0) * 0.5));
00147 if (f_index_[2] < 0) f_index_[2] = 0;
00148 if (f_index_[2] >= nr_split) f_index_[2] = nr_split - 1;
00149
00150
00151 h_index = 0;
00152 h_p = 1;
00153 for (int d = 0; d < 3; ++d)
00154 {
00155 h_index += h_p * f_index_[d];
00156 h_p *= nr_split;
00157 }
00158 pfh_histogram[h_index] += hist_incr;
00159 }
00160 }
00161 }
00162
00164 template <typename PointInT, typename PointNT, typename PointOutT> void
00165 pcl::PFHEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
00166 {
00167
00168 if (!normals_)
00169 {
00170 ROS_ERROR ("[pcl::%s::computeFeature] No input dataset containing normals was given!", getClassName ().c_str ());
00171 output.width = output.height = 0;
00172 output.points.clear ();
00173 return;
00174 }
00175 if (normals_->points.size () != surface_->points.size ())
00176 {
00177 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 ());
00178 output.width = output.height = 0;
00179 output.points.clear ();
00180 return;
00181 }
00182
00183 pfh_histogram_.setZero (nr_subdiv_ * nr_subdiv_ * nr_subdiv_);
00184
00185
00186
00187 std::vector<int> nn_indices (k_);
00188 std::vector<float> nn_dists (k_);
00189
00190
00191 for (size_t idx = 0; idx < indices_->size (); ++idx)
00192 {
00193 searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists);
00194
00195
00196 computePointPFHSignature (*surface_, *normals_, nn_indices, nr_subdiv_, pfh_histogram_);
00197
00198
00199 for (int d = 0; d < pfh_histogram_.size (); ++d)
00200 output.points[idx].histogram[d] = pfh_histogram_[d];
00201 }
00202 }
00203
00204 #define PCL_INSTANTIATE_PFHEstimation(T,NT,OutT) template class pcl::PFHEstimation<T,NT,OutT>;
00205
00206 #endif // PCL_FEATURES_IMPL_PFH_H_
00207