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 #ifndef PCL_SURFACE_IMPL_MARCHING_CUBES_RBF_H_
00037 #define PCL_SURFACE_IMPL_MARCHING_CUBES_RBF_H_
00038
00039 #include <pcl/surface/marching_cubes_rbf.h>
00040 #include <pcl/common/common.h>
00041 #include <pcl/common/vector_average.h>
00042 #include <pcl/Vertices.h>
00043 #include <pcl/kdtree/kdtree_flann.h>
00044
00046 template <typename PointNT>
00047 pcl::MarchingCubesRBF<PointNT>::MarchingCubesRBF ()
00048 : MarchingCubes<PointNT> (),
00049 off_surface_epsilon_ (0.1f)
00050 {
00051 }
00052
00054 template <typename PointNT>
00055 pcl::MarchingCubesRBF<PointNT>::~MarchingCubesRBF ()
00056 {
00057 }
00058
00059
00061 template <typename PointNT> void
00062 pcl::MarchingCubesRBF<PointNT>::voxelizeData ()
00063 {
00064
00065 unsigned int N = static_cast<unsigned int> (input_->size ());
00066 Eigen::MatrixXd M (2*N, 2*N),
00067 d (2*N, 1);
00068
00069
00070 for (unsigned int row_i = 0; row_i < 2*N; ++row_i)
00071 {
00072
00073 bool row_off = (row_i >= N) ? 1 : 0;
00074 for (unsigned int col_i = 0; col_i < 2*N; ++col_i)
00075 {
00076
00077 bool col_off = (col_i >= N) ? 1 : 0;
00078 M (row_i, col_i) = kernel (Eigen::Vector3f (input_->points[col_i%N].getVector3fMap ()).cast<double> () + Eigen::Vector3f (input_->points[col_i%N].getNormalVector3fMap ()).cast<double> () * col_off * off_surface_epsilon_,
00079 Eigen::Vector3f (input_->points[row_i%N].getVector3fMap ()).cast<double> () + Eigen::Vector3f (input_->points[row_i%N].getNormalVector3fMap ()).cast<double> () * row_off * off_surface_epsilon_);
00080 }
00081
00082 d (row_i, 0) = row_off * off_surface_epsilon_;
00083 }
00084
00085
00086 Eigen::MatrixXd w (2*N, 1);
00087
00088
00089 w = M.fullPivLu ().solve (d);
00090
00091 std::vector<double> weights (2*N);
00092 std::vector<Eigen::Vector3d> centers (2*N);
00093 for (unsigned int i = 0; i < N; ++i)
00094 {
00095 centers[i] = Eigen::Vector3f (input_->points[i].getVector3fMap ()).cast<double> ();
00096 centers[i + N] = Eigen::Vector3f (input_->points[i].getVector3fMap ()).cast<double> () + Eigen::Vector3f (input_->points[i].getNormalVector3fMap ()).cast<double> () * off_surface_epsilon_;
00097 weights[i] = w (i, 0);
00098 weights[i + N] = w (i + N, 0);
00099 }
00100
00101
00102
00103 for (int x = 0; x < res_x_; ++x)
00104 for (int y = 0; y < res_y_; ++y)
00105 for (int z = 0; z < res_z_; ++z)
00106 {
00107 Eigen::Vector3d point;
00108 point[0] = min_p_[0] + (max_p_[0] - min_p_[0]) * x / res_x_;
00109 point[1] = min_p_[1] + (max_p_[1] - min_p_[1]) * y / res_y_;
00110 point[2] = min_p_[2] + (max_p_[2] - min_p_[2]) * z / res_z_;
00111
00112 double f = 0.0f;
00113 std::vector<double>::const_iterator w_it (weights.begin());
00114 for (std::vector<Eigen::Vector3d>::const_iterator c_it = centers.begin ();
00115 c_it != centers.end (); ++c_it, ++w_it)
00116 f += *w_it * kernel (*c_it, point);
00117
00118 grid_[x * res_y_*res_z_ + y * res_z_ + z] = f;
00119 }
00120 }
00121
00123 template <typename PointNT> double
00124 pcl::MarchingCubesRBF<PointNT>::kernel (Eigen::Vector3d c, Eigen::Vector3d x)
00125 {
00126 double r = (x - c).norm();
00127 return r*r*r;
00128 }
00129
00130
00131
00132 #define PCL_INSTANTIATE_MarchingCubesRBF(T) template class PCL_EXPORTS pcl::MarchingCubesRBF<T>;
00133
00134 #endif // PCL_SURFACE_IMPL_MARCHING_CUBES_HOPPE_H_
00135