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_MOMENT_INVARIANTS_H_
00042 #define PCL_FEATURES_IMPL_MOMENT_INVARIANTS_H_
00043
00044 #include <pcl/features/moment_invariants.h>
00045 #include <pcl/common/centroid.h>
00046
00048 template <typename PointInT, typename PointOutT> void
00049 pcl::MomentInvariantsEstimation<PointInT, PointOutT>::computePointMomentInvariants (
00050 const pcl::PointCloud<PointInT> &cloud, const std::vector<int> &indices,
00051 float &j1, float &j2, float &j3)
00052 {
00053
00054 compute3DCentroid (cloud, indices, xyz_centroid_);
00055
00056
00057 float mu200 = 0, mu020 = 0, mu002 = 0, mu110 = 0, mu101 = 0, mu011 = 0;
00058
00059
00060 for (size_t nn_idx = 0; nn_idx < indices.size (); ++nn_idx)
00061 {
00062
00063 temp_pt_[0] = cloud.points[indices[nn_idx]].x - xyz_centroid_[0];
00064 temp_pt_[1] = cloud.points[indices[nn_idx]].y - xyz_centroid_[1];
00065 temp_pt_[2] = cloud.points[indices[nn_idx]].z - xyz_centroid_[2];
00066
00067 mu200 += temp_pt_[0] * temp_pt_[0];
00068 mu020 += temp_pt_[1] * temp_pt_[1];
00069 mu002 += temp_pt_[2] * temp_pt_[2];
00070 mu110 += temp_pt_[0] * temp_pt_[1];
00071 mu101 += temp_pt_[0] * temp_pt_[2];
00072 mu011 += temp_pt_[1] * temp_pt_[2];
00073 }
00074
00075
00076 j1 = mu200 + mu020 + mu002;
00077 j2 = mu200*mu020 + mu200*mu002 + mu020*mu002 - mu110*mu110 - mu101*mu101 - mu011*mu011;
00078 j3 = mu200*mu020*mu002 + 2*mu110*mu101*mu011 - mu002*mu110*mu110 - mu020*mu101*mu101 - mu200*mu011*mu011;
00079 }
00080
00082 template <typename PointInT, typename PointOutT> void
00083 pcl::MomentInvariantsEstimation<PointInT, PointOutT>::computePointMomentInvariants (
00084 const pcl::PointCloud<PointInT> &cloud, float &j1, float &j2, float &j3)
00085 {
00086
00087 compute3DCentroid (cloud, xyz_centroid_);
00088
00089
00090 float mu200 = 0, mu020 = 0, mu002 = 0, mu110 = 0, mu101 = 0, mu011 = 0;
00091
00092
00093 for (size_t nn_idx = 0; nn_idx < cloud.points.size (); ++nn_idx )
00094 {
00095
00096 temp_pt_[0] = cloud.points[nn_idx].x - xyz_centroid_[0];
00097 temp_pt_[1] = cloud.points[nn_idx].y - xyz_centroid_[1];
00098 temp_pt_[2] = cloud.points[nn_idx].z - xyz_centroid_[2];
00099
00100 mu200 += temp_pt_[0] * temp_pt_[0];
00101 mu020 += temp_pt_[1] * temp_pt_[1];
00102 mu002 += temp_pt_[2] * temp_pt_[2];
00103 mu110 += temp_pt_[0] * temp_pt_[1];
00104 mu101 += temp_pt_[0] * temp_pt_[2];
00105 mu011 += temp_pt_[1] * temp_pt_[2];
00106 }
00107
00108
00109 j1 = mu200 + mu020 + mu002;
00110 j2 = mu200*mu020 + mu200*mu002 + mu020*mu002 - mu110*mu110 - mu101*mu101 - mu011*mu011;
00111 j3 = mu200*mu020*mu002 + 2*mu110*mu101*mu011 - mu002*mu110*mu110 - mu020*mu101*mu101 - mu200*mu011*mu011;
00112 }
00113
00115 template <typename PointInT, typename PointOutT> void
00116 pcl::MomentInvariantsEstimation<PointInT, PointOutT>::computeFeature (PointCloudOut &output)
00117 {
00118
00119
00120 std::vector<int> nn_indices (k_);
00121 std::vector<float> nn_dists (k_);
00122
00123 output.is_dense = true;
00124
00125 if (input_->is_dense)
00126 {
00127
00128 for (size_t idx = 0; idx < indices_->size (); ++idx)
00129 {
00130 if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
00131 {
00132 output.points[idx].j1 = output.points[idx].j2 = output.points[idx].j3 = std::numeric_limits<float>::quiet_NaN ();
00133 output.is_dense = false;
00134 continue;
00135 }
00136
00137 computePointMomentInvariants (*surface_, nn_indices,
00138 output.points[idx].j1, output.points[idx].j2, output.points[idx].j3);
00139 }
00140 }
00141 else
00142 {
00143
00144 for (size_t idx = 0; idx < indices_->size (); ++idx)
00145 {
00146 if (!isFinite ((*input_)[(*indices_)[idx]]) ||
00147 this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
00148 {
00149 output.points[idx].j1 = output.points[idx].j2 = output.points[idx].j3 = std::numeric_limits<float>::quiet_NaN ();
00150 output.is_dense = false;
00151 continue;
00152 }
00153
00154 computePointMomentInvariants (*surface_, nn_indices,
00155 output.points[idx].j1, output.points[idx].j2, output.points[idx].j3);
00156 }
00157 }
00158 }
00159
00160 #define PCL_INSTANTIATE_MomentInvariantsEstimation(T,NT) template class PCL_EXPORTS pcl::MomentInvariantsEstimation<T,NT>;
00161
00162 #endif // PCL_FEATURES_IMPL_MOMENT_INVARIANTS_H_
00163