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_MOMENT_INVARIANTS_H_
00039 #define PCL_FEATURES_IMPL_MOMENT_INVARIANTS_H_
00040
00041 #include "pcl/features/moment_invariants.h"
00042
00044 template <typename PointInT, typename PointOutT> void
00045 pcl::MomentInvariantsEstimation<PointInT, PointOutT>::computePointMomentInvariants (
00046 const pcl::PointCloud<PointInT> &cloud, const std::vector<int> &indices,
00047 float &j1, float &j2, float &j3)
00048 {
00049
00050 compute3DCentroid (cloud, indices, xyz_centroid_);
00051
00052
00053 float mu200 = 0, mu020 = 0, mu002 = 0, mu110 = 0, mu101 = 0, mu011 = 0;
00054
00055
00056 for (size_t nn_idx = 0; nn_idx < indices.size (); ++nn_idx)
00057 {
00058
00059 temp_pt_[0] = cloud.points[indices[nn_idx]].x - xyz_centroid_[0];
00060 temp_pt_[1] = cloud.points[indices[nn_idx]].y - xyz_centroid_[1];
00061 temp_pt_[2] = cloud.points[indices[nn_idx]].z - xyz_centroid_[2];
00062
00063 mu200 += temp_pt_[0] * temp_pt_[0];
00064 mu020 += temp_pt_[1] * temp_pt_[1];
00065 mu002 += temp_pt_[2] * temp_pt_[2];
00066 mu110 += temp_pt_[0] * temp_pt_[1];
00067 mu101 += temp_pt_[0] * temp_pt_[2];
00068 mu011 += temp_pt_[1] * temp_pt_[2];
00069 }
00070
00071
00072 j1 = mu200 + mu020 + mu002;
00073 j2 = mu200*mu020 + mu200*mu002 + mu020*mu002 - mu110*mu110 - mu101*mu101 - mu011*mu011;
00074 j3 = mu200*mu020*mu002 + 2*mu110*mu101*mu011 - mu002*mu110*mu110 - mu020*mu101*mu101 - mu200*mu011*mu011;
00075 }
00076
00078 template <typename PointInT, typename PointOutT> void
00079 pcl::MomentInvariantsEstimation<PointInT, PointOutT>::computePointMomentInvariants (
00080 const pcl::PointCloud<PointInT> &cloud, float &j1, float &j2, float &j3)
00081 {
00082
00083 compute3DCentroid (cloud, xyz_centroid_);
00084
00085
00086 float mu200 = 0, mu020 = 0, mu002 = 0, mu110 = 0, mu101 = 0, mu011 = 0;
00087
00088
00089 for (size_t nn_idx = 0; nn_idx < cloud.points.size (); ++nn_idx )
00090 {
00091
00092 temp_pt_[0] = cloud.points[nn_idx].x - xyz_centroid_[0];
00093 temp_pt_[1] = cloud.points[nn_idx].y - xyz_centroid_[1];
00094 temp_pt_[2] = cloud.points[nn_idx].z - xyz_centroid_[2];
00095
00096 mu200 += temp_pt_[0] * temp_pt_[0];
00097 mu020 += temp_pt_[1] * temp_pt_[1];
00098 mu002 += temp_pt_[2] * temp_pt_[2];
00099 mu110 += temp_pt_[0] * temp_pt_[1];
00100 mu101 += temp_pt_[0] * temp_pt_[2];
00101 mu011 += temp_pt_[1] * temp_pt_[2];
00102 }
00103
00104
00105 j1 = mu200 + mu020 + mu002;
00106 j2 = mu200*mu020 + mu200*mu002 + mu020*mu002 - mu110*mu110 - mu101*mu101 - mu011*mu011;
00107 j3 = mu200*mu020*mu002 + 2*mu110*mu101*mu011 - mu002*mu110*mu110 - mu020*mu101*mu101 - mu200*mu011*mu011;
00108 }
00109
00111 template <typename PointInT, typename PointOutT> void
00112 pcl::MomentInvariantsEstimation<PointInT, PointOutT>::computeFeature (PointCloudOut &output)
00113 {
00114
00115
00116 std::vector<int> nn_indices (k_);
00117 std::vector<float> nn_dists (k_);
00118
00119
00120 for (size_t idx = 0; idx < indices_->size (); ++idx)
00121 {
00122 searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists);
00123
00124 computePointMomentInvariants (*surface_, nn_indices,
00125 output.points[idx].j1, output.points[idx].j2, output.points[idx].j3);
00126 }
00127 }
00128
00129 #define PCL_INSTANTIATE_MomentInvariantsEstimation(T,NT) template class pcl::MomentInvariantsEstimation<T,NT>;
00130
00131 #endif // PCL_FEATURES_IMPL_MOMENT_INVARIANTS_H_
00132