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_NORMAL_3D_H_
00039 #define PCL_NORMAL_3D_H_
00040
00041 #include <pcl/features/feature.h>
00042
00043 namespace pcl
00044 {
00054 template <typename PointT> inline void
00055 computePointNormal (const pcl::PointCloud<PointT> &cloud,
00056 Eigen::Vector4f &plane_parameters, float &curvature)
00057 {
00058 if (cloud.points.empty ())
00059 {
00060 plane_parameters.setConstant (std::numeric_limits<float>::quiet_NaN ());
00061 curvature = std::numeric_limits<float>::quiet_NaN ();
00062 return;
00063 }
00064
00065 EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00066
00067 Eigen::Vector4f xyz_centroid;
00068
00069
00070 compute3DCentroid (cloud, xyz_centroid);
00071
00072
00073 computeCovarianceMatrix (cloud, xyz_centroid, covariance_matrix);
00074
00075
00076 solvePlaneParameters (covariance_matrix, xyz_centroid, plane_parameters, curvature);
00077 }
00078
00089 template <typename PointT> inline void
00090 computePointNormal (const pcl::PointCloud<PointT> &cloud, const std::vector<int> &indices,
00091 Eigen::Vector4f &plane_parameters, float &curvature)
00092 {
00093 if (indices.empty ())
00094 {
00095 plane_parameters.setConstant (std::numeric_limits<float>::quiet_NaN ());
00096 curvature = std::numeric_limits<float>::quiet_NaN ();
00097 return;
00098 }
00099
00100 EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00101
00102 Eigen::Vector4f xyz_centroid;
00103
00104
00105 compute3DCentroid (cloud, indices, xyz_centroid);
00106
00107
00108 computeCovarianceMatrix (cloud, indices, xyz_centroid, covariance_matrix);
00109
00110
00111 solvePlaneParameters (covariance_matrix, xyz_centroid, plane_parameters, curvature);
00112 }
00113
00121 template <typename PointT> inline void
00122 flipNormalTowardsViewpoint (const PointT &point, float vp_x, float vp_y, float vp_z,
00123 Eigen::Vector4f &normal)
00124 {
00125
00126 vp_x -= point.x;
00127 vp_y -= point.y;
00128 vp_z -= point.z;
00129
00130
00131 float cos_theta = (vp_x * normal[0] + vp_y * normal[1] + vp_z * normal[2]);
00132
00133
00134 if (cos_theta < 0)
00135 {
00136 normal *= -1;
00137
00138 normal[3] = -1 * (normal[0] * point.x + normal[1] * point.y + normal[2] * point.z);
00139 }
00140 }
00141
00151 template <typename PointT> inline void
00152 flipNormalTowardsViewpoint (const PointT &point, float vp_x, float vp_y, float vp_z,
00153 float &nx, float &ny, float &nz)
00154 {
00155
00156 vp_x -= point.x;
00157 vp_y -= point.y;
00158 vp_z -= point.z;
00159
00160
00161 float cos_theta = (vp_x * nx + vp_y * ny + vp_z * nz);
00162
00163
00164 if (cos_theta < 0)
00165 {
00166 nx *= -1;
00167 ny *= -1;
00168 nz *= -1;
00169 }
00170 }
00171
00179 template <typename PointInT, typename PointOutT>
00180 class NormalEstimation: public Feature<PointInT, PointOutT>
00181 {
00182 public:
00183 using Feature<PointInT, PointOutT>::feature_name_;
00184 using Feature<PointInT, PointOutT>::getClassName;
00185 using Feature<PointInT, PointOutT>::indices_;
00186 using Feature<PointInT, PointOutT>::surface_;
00187 using Feature<PointInT, PointOutT>::k_;
00188 using Feature<PointInT, PointOutT>::search_radius_;
00189 using Feature<PointInT, PointOutT>::search_parameter_;
00190
00191 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00192
00194 NormalEstimation () : vpx_ (0), vpy_ (0), vpz_ (0)
00195 {
00196 feature_name_ = "NormalEstimation";
00197 };
00198
00209 inline void
00210 computePointNormal (const pcl::PointCloud<PointInT> &cloud, const std::vector<int> &indices, Eigen::Vector4f &plane_parameters, float &curvature)
00211 {
00212 if (indices.empty ())
00213 {
00214 plane_parameters.setConstant (std::numeric_limits<float>::quiet_NaN ());
00215 curvature = std::numeric_limits<float>::quiet_NaN ();
00216 return;
00217 }
00218
00219 compute3DCentroid (cloud, indices, xyz_centroid_);
00220
00221
00222 computeCovarianceMatrix (cloud, indices, xyz_centroid_, covariance_matrix_);
00223
00224
00225 solvePlaneParameters (covariance_matrix_, xyz_centroid_, plane_parameters, curvature);
00226 }
00227
00240 inline void
00241 computePointNormal (const pcl::PointCloud<PointInT> &cloud, const std::vector<int> &indices, float &nx, float &ny, float &nz, float &curvature)
00242 {
00243 if (indices.empty ())
00244 {
00245 nx = ny = nz = curvature = std::numeric_limits<float>::quiet_NaN ();
00246 return;
00247 }
00248
00249 compute3DCentroid (cloud, indices, xyz_centroid_);
00250
00251
00252 computeCovarianceMatrix (cloud, indices, xyz_centroid_, covariance_matrix_);
00253
00254
00255 solvePlaneParameters (covariance_matrix_, nx, ny, nz, curvature);
00256 }
00257
00263 inline void
00264 setViewPoint (float vpx, float vpy, float vpz)
00265 {
00266 vpx_ = vpx;
00267 vpy_ = vpy;
00268 vpz_ = vpz;
00269 }
00270
00272 inline void
00273 getViewPoint (float &vpx, float &vpy, float &vpz)
00274 {
00275 vpx = vpx_;
00276 vpy = vpy_;
00277 vpz = vpz_;
00278 }
00279
00280 protected:
00286 void computeFeature (PointCloudOut &output);
00287
00288 private:
00291 float vpx_, vpy_, vpz_;
00292
00294 EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix_;
00295
00297 Eigen::Vector4f xyz_centroid_;
00298 };
00299 }
00300
00301 #endif //#ifndef PCL_NORMAL_3D_H_
00302
00303