Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Avoid phantom surfces in marching cubes hoppe #1874

Merged
merged 12 commits into from
Aug 27, 2017

Conversation

t-lou
Copy link
Contributor

@t-lou t-lou commented May 30, 2017

… in complex point clouds.

For indoor reconstruction, the MC Hoppe algorithm tends to form significant phantom surfaces where it should be concave. It is likely to be caused by signed distance functions(SDF) generated by far away points. Thus a spatial threshold is added in my branch to ignore SDFs which are far from points. The structure of marching cube is also optimized(separate common parts)

… in complex point clouds. basically only build surface in cubes near points.
@SergioRAgostinho
Copy link
Member

Can you add some images exemplifying the visual differences of the method before your changes and after?

Thanks for contributing.

@t-lou
Copy link
Contributor Author

t-lou commented Jun 2, 2017

snapshot00
Point cloud

snapshot01
Reconstruction with pcl-1.8

snapshot02
Reconstruction also with spatial restriction

@SergioRAgostinho SergioRAgostinho added this to the pcl-1.9.0 milestone Jun 29, 2017
// Create grid
grid_ = std::vector<float> (res_x_*res_y_*res_z_, 0.0f);
// grid_ = std::vector<float> (res_x_*res_y_*res_z_, 0.0f);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Don't submit commented lines

v.vertices[j] = static_cast<int> (i) * 3 + j;
polygons[i] = v;
}
}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This section can also be refactored into performReconstructionProc. It will required you to change the signature of that method to include the pointcloud and the polygon vector.

}

template <typename PointNT> void
pcl::MarchingCubes<PointNT>::performReconstructionProc ()
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

See comment above regarding the signature for this one.

voxelizeData ();

// real part of marching cube
performReconstructionProc();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

See my comment below regarding the signature change for this block and the code that can also be included inside.

for (int j = 0; j < 3; ++j)
v.vertices[j] = static_cast<int> (i) * 3 + j;
polygons[i] = v;
}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In conjunction with my other comments, leave this here.

std::vector<int> nn_indices(1, 0);
std::vector<float> nn_sqr_dists(1, 0.0f);
Eigen::Vector3f point;
PointNT p;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Comment regarding the two lines above: I'm an apologist of RAII. Does this grant you a super duper performance increase to justify declaring it here?

std::vector<float> nn_sqr_dists(1, 0.0f);
Eigen::Vector3f point;
PointNT p;
const Eigen::Vector4f delta = ( max_p_ - min_p_ ).cwiseQuotient( Eigen::Vector4f(
Copy link
Member

@SergioRAgostinho SergioRAgostinho Jun 29, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't really understand the reason behind declaring this as Vector4f. Was it to make it aligned or something? Note that if you declare it Vector3f (use actually Array3f to use element wise operations later on) you can reduce the expression below, inside the nested for blocks.

Edit: Now I'm definitely sure use you want to perform element wise operations. Read on Eigen about Arrays and block. Create delta as an Array3f for the three top element block of max_p_ min_p_.

point - input_->points[nn_indices[0]].getVector3fMap ());
if( !is_far_ignored || nn_sqr_dists[0] < dist_ignore_ )
{
normal = input_->points[nn_indices[0]].getNormalVector3fMap ();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

const


/** \brief the point cloud really generated from Marching Cubes
*/
pcl::PointCloud<PointNT> intermediate_cloud_;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

With the changes requested I think this member can be removed and just exist in a temporary scope inside the methods.

@taketwo taketwo added the needs: author reply Specify why not closed/merged yet label Jun 29, 2017
@t-lou
Copy link
Contributor Author

t-lou commented Jun 29, 2017

Hello, thank you for the review. Should I correct in another commit or collide to this one? Would further commits be added automatically in this pull-request? Thank you

@taketwo
Copy link
Member

taketwo commented Jun 29, 2017

Yes, add more commits to the same branch and push it again, this PR will be updated automatically. In the end, when the review is done, we will squash everything and write a single clean commit to the main repository.

@t-lou
Copy link
Contributor Author

t-lou commented Jul 3, 2017

How about now?

Copy link
Member

@taketwo taketwo left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

General comment: please follow the PCL style guide with respect to the spaces before braces.

{
const Eigen::Vector3f normal = input_->points[nn_indices[0]].getNormalVector3fMap ();

if(normal.norm() > 0.5f)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this necessary? I thought PCL maintains the invariant normal.norm() == 1.0.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In some point clouds I used (maybe not generated with pcl, but with quite fine normal), some points have normal vector with length 0. Would the normal be [0] if the neighborhood is not consistent?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hm, at least in NormalEstimation class invalid normals are set to NaN (see here). I wonder how norm() function reacts to that.


const Eigen::Vector3f min_p = min_p_.segment(0, 3);
const Eigen::Vector3f delta = ( max_p_ - min_p_ ).segment(0, 3).cwiseQuotient(
Eigen::Vector3f((float)res_x_, (float)res_y_, (float)res_z_) );
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is explicit cast necessary?

intermediate_cloud.clear();

// preallocate memory assuming a hull. suppose 6 point per voxel
intermediate_cloud.reserve((size_t)(res_y_*res_z_ + res_x_*res_z_ + res_x_*res_y_) * 2 * 6);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is potentially a huge number. Do we have a check for overflow somewhere?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I wanted to avoid massive copy of vector. How to check overflow? Could you show me a file with this function? (in voxel grid I have seen similar output, but for overflow of uint32 or int32)

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I meant that this product may exceed what size_t can represent. In this case we can actually get some small number as a result and reserve too less. I'd propose to perform this multiplication in double, then clamp to intermediate_cloud.max_size(), and finally reserve.

@@ -45,7 +45,7 @@
//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointNT>
pcl::MarchingCubes<PointNT>::MarchingCubes ()
: min_p_ (), max_p_ (), percentage_extend_grid_ (), iso_level_ ()
: min_p_ (), max_p_ (), percentage_extend_grid_ (), iso_level_ (), dist_ignore_ (-1.0f)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Actually, in PCL we often have such simple constructor definitions right in the header file, motivation being that it's easier to see the default values. While we are at it, would you mind to transfer this to the header and also fill in the values of min_p_, max_p_, etc for clarity?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Move the whole constructor into header file? Maybe I could move min_p_ and max_p_ to local variable and change to vector3f, it looks a bit stateful to have them as class members. How do you say?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I had a brief look and they are used in different functions both in parent and deriving class. If you have an idea how to make them local without need to recompute several times, please go ahead!

Eigen::Vector3f size3_extend = 0.5f * percentage_extend_grid_ * (upper_boundary - lower_boundary);

lower_boundary -= size3_extend;
upper_boundary += size3_extend;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Everything below this line has no effect, right? Should we delete these lines?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I have deleted. Is the constructor now what you want?

Copy link
Member

@SergioRAgostinho SergioRAgostinho left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good work. Now it's just really some minor things and some questions regarding your thoughts.

@@ -45,7 +45,7 @@
//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointNT>
pcl::MarchingCubes<PointNT>::MarchingCubes ()
: min_p_ (), max_p_ (), percentage_extend_grid_ (), iso_level_ ()
: percentage_extend_grid_ (), iso_level_ (), dist_ignore_ (-1.0f)
{
}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Wasn't this supposed to be moved to the .h file?

{
pcl::getMinMax3D (*input_, min_p_, max_p_);
PointNT max_pt, min_pt;
pcl::getMinMax3D (*input_, min_pt, max_pt);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It doesn't make much difference in this case but this looks like the overload you were actually looking for
http://docs.pointclouds.org/trunk/group__common.html#gafd9010977f5e52b35b484be7624df3f8


// Run the actual marching cubes algorithm, store it into a point cloud,
// and copy the point cloud + connectivity into output
points.clear ();
intermediate_cloud.clear ();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Unnecessary. Intermediate_cloud is always initialized empty.

// the point cloud really generated from Marching Cubes, prev intermediate_cloud_
pcl::PointCloud<PointNT> intermediate_cloud;

Eigen::Vector3f upper_boundary, lower_boundary;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I noticed that every operation on these guys is coefficient wise. You should replace their type to Eigen::Array. Have a look at https://eigen.tuxfamily.org/dox/group__TutorialArrayClass.html

point[0] = min_p_[0] + (max_p_[0] - min_p_[0]) * float (x) / float (res_x_);
point[1] = min_p_[1] + (max_p_[1] - min_p_[1]) * float (y) / float (res_y_);
point[2] = min_p_[2] + (max_p_[2] - min_p_[2]) * float (z) / float (res_z_);
Eigen::Vector3d point = base + delta.cwiseProduct (Eigen::Vector3d (x, y, z));
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Const qualifier

protected:
/** \brief The data structure storing the 3D grid */
std::vector<float> grid_;

/** \brief The grid resolution */
int res_x_, res_y_, res_z_;

/** \brief Min and max data points. */
Eigen::Vector4f min_p_, max_p_;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Was this (or the bound named equivalent) worth removing? I saw you compute it only once and then have to pass it around to a number of methods. Its lifetime is equivalent to input_, grid_, res_x_, etc... I really don't understand why you felt they were "stateful", or to be more clear, that they shouldn't belong to the state of the Class. Can you explain a little bit the reasoning?

I also question if delta should not follow the same.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I just have another compelling argument: There's not a single time you invoke the methods (the ones which now have the bounds on the signature) and that these bounds actually change. You don't invoke the method changing the bounds ever. As the long as the input cloud is the same, the bounds will always be the same.

Copy link
Contributor Author

@t-lou t-lou Jul 3, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Because I think it's not the property of the class, but of the data. And using them as parameter doesn't make the program too complicated or slow.

Sorry, what do you mean by "if delta should not follow the same"?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do you mean to do marching cube meshing on the same input cloud for several times with different parameters? But the old code would also invoke "getBoundingBox ()" each time we execute "performReconstruction"

center[0] = min_p_[0] + (max_p_[0] - min_p_[0]) * float (index_3d[0]) / float (res_x_);
center[1] = min_p_[1] + (max_p_[1] - min_p_[1]) * float (index_3d[1]) / float (res_y_);
center[2] = min_p_[2] + (max_p_[2] - min_p_[2]) * float (index_3d[2]) / float (res_z_);
const Eigen::Vector3f size_voxel = (upper_boundary - lower_boundary).cwiseQuotient (
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is similar to delta right? Increases the time you compute this to three time.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

excuse me, what do you mean?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would prefer to calculate once and use them as parameters, as they are data-related, not algorithm related. In this way the functions would be more stateless.
Do you think I should put delta (voxel_size), min_p_ and max_p_ all to class definition?

Copy link
Member

@SergioRAgostinho SergioRAgostinho Jul 3, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes. I'm just trying to understand what are the advantages of your approach and the avantages of mine.

The class has data members (i.e. input_ and grid_) so it's only natural to have other members related to this data.

Currently your protected methods have a parameters in the signature that never changes, as long as the input cloud (which is a member) doesn't change, and they're only invoked following a public call to performReconstruction.

If we add the members to the class definition and simply don't expose setters and getter functions to them we have:

  • More member which are data related but not accessible to the outside
  • You don't have them in the signature because you don't need them, since you're anyway you're alway invoking the methods with the same bound data.
  • You prevent have to recompute delta, because it persists valid throughout a call to performReconstruction

Opinion @taketwo

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

PCL classes are by design stateful. We use separate function calls to set parameters, input point cloud, input indices. After that we call a compute method, passing a single argument: storage for the output. Therefore I agree with @SergioRAgostinho, there is no reason to pretend there is no state and pass around variables that are computed from the input point cloud, which in fact is the state.

@@ -90,15 +96,17 @@ pcl::MarchingCubes<PointNT>::interpolateEdge (Eigen::Vector3f &p1,
float val_p2,
Eigen::Vector3f &output)
{
float mu = (iso_level_ - val_p1) / (val_p2-val_p1);
float mu = (iso_level_ - val_p1) / (val_p2 - val_p1);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

const

const float dist_ignore)
: percentage_extend_grid_ (percentage_extend_grid),
iso_level_ (iso_level),
dist_ignore_ (dist_ignore)
{
}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Move this entire constructor to the .h

Copy link
Member

@SergioRAgostinho SergioRAgostinho left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Really minor comments. Thanks for all the effort and thanks for contributing this.

pcl::getMinMax3D (*input_, min_pt, max_pt);

lower_boundary_ = min_pt.getVector3fMap ().array ();
upper_boundary_ = max_pt.getVector3fMap ().array ();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You should use getArray3fMap() instead.

min_p_.x (), min_p_.y (), min_p_.z ());
PCL_DEBUG ("[pcl::MarchingCubesHoppe::getBoundingBox] Upper left point is [%f, %f, %f]\n",
max_p_.x (), max_p_.y (), max_p_.z ());
PointNT max_pt, min_pt;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You're just interested in the coordinates so this should be PointXYZ.

MarchingCubesRBF ();
MarchingCubesRBF (const float percentage_extend_grid = 0.0f,
const float iso_level = 0.0f,
const float off_surface_epsilon = 0.1f) :
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Since you're more knowledgeable about this algorithm than I am, does the order in which these parameters appear respect the convention of "more likely to be changed" to "less likely to be changed" (from the default values)?

MarchingCubesHoppe (const float percentage_extend_grid = 0.0f,
const float iso_level = 0.0f,
const float dist_ignore = -1.0f) :
MarchingCubes<PointNT> (percentage_extend_grid, iso_level),
Copy link
Member

@SergioRAgostinho SergioRAgostinho Jul 4, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Since you're more knowledgeable about this algorithm than I am, does the order in which these parameters appear respect the convention of "more likely to be changed" to "less likely to be changed" (from the default values)?

@taketwo
Copy link
Member

taketwo commented Jul 4, 2017

Beside from the latest comments from Sergio, I think everything is fine. Well, actually there are still some problems with spaces between braces, would be nice to fix them before we merge. Thanks for the effort!

Edit: oh, and I'm afraid that the unit test is failing now.

@t-lou
Copy link
Contributor Author

t-lou commented Jul 4, 2017

@taketwo
How should I get the information about unit tests? I only did tests in my project, and tried to compile on my computer.
could you give some examples where the spacing is wrong? http://pointclouds.org/documentation/advanced/pcl_style_guide.php#spacing doesn't give a complete description of where to add/delete spaces. Thanks

@SergioRAgostinho
actually I'm not familiar with MC RBF. The author didn't use parameters for constructor, and instead used constant values in initial list. Should I do that too?

@taketwo
Copy link
Member

taketwo commented Jul 4, 2017

Here is a complete log of the failing test (comes from here):

16: Test command: /home/travis/build/PointCloudLibrary/pcl/build/test/surface/test_marching_cubes "/home/travis/build/PointCloudLibrary/pcl/test/bun0.pcd"
16: Test timeout computed to be: 9.99988e+06
16: [==========] Running 1 test from 1 test case.
16: [----------] Global test environment set-up.
16: [----------] 1 test from PCL
16: [ RUN      ] PCL.MarchingCubesTest
16: /home/travis/build/PointCloudLibrary/pcl/test/surface/test_marching_cubes.cpp:79: Failure
16: The difference between points.points[points.size()/2].x and -0.042528 is 0.0053850042550563845, which exceeds 1e-3, where
16: points.points[points.size()/2].x evaluates to -0.037142995744943619,
16: -0.042528 evaluates to -0.042528000000000003, and
16: 1e-3 evaluates to 0.001.
16: /home/travis/build/PointCloudLibrary/pcl/test/surface/test_marching_cubes.cpp:80: Failure
16: The difference between points.points[points.size()/2].y and 0.080196 is 0.018017069140911099, which exceeds 1e-3, where
16: points.points[points.size()/2].y evaluates to 0.098213069140911102,
16: 0.080196 evaluates to 0.080196000000000003, and
16: 1e-3 evaluates to 0.001.
16: /home/travis/build/PointCloudLibrary/pcl/test/surface/test_marching_cubes.cpp:81: Failure
16: The difference between points.points[points.size()/2].z and 0.043159 is 0.088069751283168796, which exceeds 1e-3, where
16: points.points[points.size()/2].z evaluates to -0.044910751283168793,
16: 0.043159 evaluates to 0.043159000000000003, and
16: 1e-3 evaluates to 0.001.
16: /home/travis/build/PointCloudLibrary/pcl/test/surface/test_marching_cubes.cpp:82: Failure
16: Value of: 10854
16: Expected: vertices[vertices.size ()/2].vertices[0]
16: Which is: 11202
16: /home/travis/build/PointCloudLibrary/pcl/test/surface/test_marching_cubes.cpp:83: Failure
16: Value of: 10855
16: Expected: vertices[vertices.size ()/2].vertices[1]
16: Which is: 11203
16: /home/travis/build/PointCloudLibrary/pcl/test/surface/test_marching_cubes.cpp:84: Failure
16: Value of: 10856
16: Expected: vertices[vertices.size ()/2].vertices[2]
16: Which is: 11204
16: /home/travis/build/PointCloudLibrary/pcl/test/surface/test_marching_cubes.cpp:95: Failure
16: The difference between points.points[points.size()/2].x and -0.033919 is 0.0082885054203271843, which exceeds 1e-3, where
16: points.points[points.size()/2].x evaluates to -0.025630494579672813,
16: -0.033919 evaluates to -0.033918999999999998, and
16: 1e-3 evaluates to 0.001.
16: /home/travis/build/PointCloudLibrary/pcl/test/surface/test_marching_cubes.cpp:96: Failure
16: The difference between points.points[points.size()/2].y and 0.151683 is 0.016454813154220593, which exceeds 1e-3, where
16: points.points[points.size()/2].y evaluates to 0.13522818684577942,
16: 0.151683 evaluates to 0.15168300000000001, and
16: 1e-3 evaluates to 0.001.
16: /home/travis/build/PointCloudLibrary/pcl/test/surface/test_marching_cubes.cpp:97: Failure
16: The difference between points.points[points.size()/2].z and -0.000086 is 0.035851919834375384, which exceeds 1e-3, where
16: points.points[points.size()/2].z evaluates to 0.035765919834375381,
16: -0.000086 evaluates to -8.6000000000000003e-05, and
16: 1e-3 evaluates to 0.001.
16: /home/travis/build/PointCloudLibrary/pcl/test/surface/test_marching_cubes.cpp:98: Failure
16: Value of: 4284
16: Expected: vertices[vertices.size ()/2].vertices[0]
16: Which is: 4275
16: /home/travis/build/PointCloudLibrary/pcl/test/surface/test_marching_cubes.cpp:99: Failure
16: Value of: 4285
16: Expected: vertices[vertices.size ()/2].vertices[1]
16: Which is: 4276
16: /home/travis/build/PointCloudLibrary/pcl/test/surface/test_marching_cubes.cpp:100: Failure
16: Value of: 4286
16: Expected: vertices[vertices.size ()/2].vertices[2]
16: Which is: 4277
16: [  FAILED  ] PCL.MarchingCubesTest (331 ms)
16: [----------] 1 test from PCL (331 ms total)
16: 
16: [----------] Global test environment tear-down
16: [==========] 1 test from 1 test case ran. (331 ms total)
16: [  PASSED  ] 0 tests.
16: [  FAILED  ] 1 test, listed below:
16: [  FAILED  ] PCL.MarchingCubesTest
16: 
16:  1 FAILED TEST
16/23 Test #16: surface_marching_cubes ...........***Failed    0.36 sec

@@ -191,7 +171,7 @@ template <typename PointNT> void
pcl::MarchingCubes<PointNT>::getNeighborList1D (std::vector<float> &leaf,
Eigen::Vector3i &index3d)
{
leaf = std::vector<float> (8, 0.0f);
leaf.resize(8);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Space between resize and (8)

@@ -201,6 +181,15 @@ pcl::MarchingCubes<PointNT>::getNeighborList1D (std::vector<float> &leaf,
leaf[5] = getGridValue (index3d + Eigen::Vector3i (1, 1, 0));
leaf[6] = getGridValue (index3d + Eigen::Vector3i (1, 1, 1));
leaf[7] = getGridValue (index3d + Eigen::Vector3i (0, 1, 1));

for(int i = 0; i < 8; ++i)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Space after for


for(int i = 0; i < 8; ++i)
{
if(std::isnan(leaf[i]))
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Space after if and isnan

{
if(std::isnan(leaf[i]))
{
leaf.clear();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Space after clear

for (int x = 1; x < res_x_-1; ++x)
for (int y = 1; y < res_y_-1; ++y)
for (int z = 1; z < res_z_-1; ++z)
{
Eigen::Vector3i index_3d (x, y, z);
std::vector<float> leaf_node;
getNeighborList1D (leaf_node, index_3d);
createSurface (leaf_node, index_3d, points);
if(!leaf_node.empty())
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Space after if and empty

p.getVector3fMap () = point;

tree_->nearestKSearch (p, 1, nn_indices, nn_sqr_dists);

grid_[x * res_y_*res_z_ + y * res_z_ + z] = input_->points[nn_indices[0]].getNormalVector3fMap ().dot (
point - input_->points[nn_indices[0]].getVector3fMap ());
if( !is_far_ignored || nn_sqr_dists[0] < dist_ignore_ )
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Space after if, no space inside braces

{
const Eigen::Vector3f normal = input_->points[nn_indices[0]].getNormalVector3fMap ();

if(!std::isnan (normal(0)) && normal.norm () > 0.5f)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Space after if and normal

@SergioRAgostinho
Copy link
Member

actually I'm not familiar with MC RBF. The author didn't use parameters for constructor, and instead used constant values in initial list. Should I do that too?

Not at all. It's good that you expose those parameters in the constructor. Given the lack of insight then let's always put parameters of the child class first followed by parameters of the base class. For instance, for Hoppe

MarchingCubesHoppe (const float dist_ignore = -1.0f,
                    const float percentage_extend_grid = 0.0f,
                    const float iso_level = 0.0f)
    : [...]

@taketwo
Copy link
Member

taketwo commented Jul 4, 2017

let's always put parameters of the child class first followed by parameters of the base class

What is the motivation, why not the other way round?

@SergioRAgostinho
Copy link
Member

SergioRAgostinho commented Jul 4, 2017

So keeping in mind that we're not really aware which parameter is actually changed more often, when invoking a child class I normally tend tweak parameters of the child class more often, then the base class. The child class normally tends to set good default values for its Base class constructor.

But then again. Only because we lack experience with the class to have an educated guess.

@t-lou
Copy link
Contributor Author

t-lou commented Jul 4, 2017

@taketwo
very likely this is caused by checking whether the normal is correct, which leads to different size of output polygon. Will the unit test be executed each time I push commit?

@taketwo
Copy link
Member

taketwo commented Jul 4, 2017

Yes, tests run after every push on the last commit, but it takes up to 3 hours on Travis :(
It probably makes sense to experiment with them locally. Simply enable BUILD_global_tests option in CMake and then compile and run the test in question.

@t-lou
Copy link
Contributor Author

t-lou commented Jul 4, 2017

@taketwo
I have found the problem. The old version expended(the one used for unit test) the bounding box like

lower_boundary_ -= 0.5f * percentage_extend_grid_ * (upper_boundary_ - lower_boundary_);
upper_boundary_ += 0.5f * percentage_extend_grid_ * (upper_boundary_ - lower_boundary_);

while I changed it to
const Eigen::Array3f size3_extend = 0.5f * percentage_extend_grid_ * (upper_boundary_ - lower_boundary_);
lower_boundary_ -= size3_extend;
upper_boundary_ += size3_extend;

When I switched to older way, this module is successful. I think my way is correct. What is your suggestion? Change the code or unit test?

@SergioRAgostinho
Copy link
Member

Good catch! Change the unit tests!

In the old one the resultant expansion would not correspond to the requested by the user.

@t-lou
Copy link
Contributor Author

t-lou commented Jul 4, 2017

Should be no problem now :)

*/
inline void
Copy link
Member

@taketwo taketwo Jul 4, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What happened to inline? Also, getDistanceIgnore can be inline.

@t-lou
Copy link
Contributor Author

t-lou commented Jul 4, 2017

I remember too many inline keywords could make other inline functions less optimized. Is it right? I think getter and setter don't need to be inline. Is it a tradition to make smaller functions inline?

@t-lou
Copy link
Contributor Author

t-lou commented Jul 5, 2017

Hi, where should I ask before adding new features? I rewrote the implementation of ball pivoting. Does pcl need it? maybe I can fit it as a pcl class. One part of one function was from another repo https://github.com/t-lou/bpa_remake

@taketwo
Copy link
Member

taketwo commented Jul 5, 2017

Is it a tradition to make smaller functions inline?

Yes, this is common in PCL to make all one-liner getter/setter functions inline and put their implementation in the header file. Over time, I've seen multiple discussions of the inline keyword with people claiming that modern compilers ignore it, that it is an implementation detail and should go into cpp file, etc. I'm not a compiler writer and not an expert in compiler optimization. So unless some one comes up with compelling evidence that inlined getter/setter functions in PCL have any negative effect, I'd prefer to just stick with this "convention".

Hi, where should I ask before adding new features? I rewrote the implementation of ball pivoting. Does pcl need it? maybe I can fit it as a pcl class. One part of one function was from another repo

In principle, you can create an issue describing what you want to do. But in this case I think it is an easy "yes". Such an algorithm will nicely fit in the surface module of PCL. One thing we need to be careful is that if you will be re-using some third-party code, it's license should be permissive enough. Even better, get explicit agreement from the original author.

@SergioRAgostinho
Copy link
Member

I remember too many inline keywords could make other inline functions less optimized. Is it right? I think getter and setter don't need to be inline. Is it a tradition to make smaller functions inline?

That's a very cheap accessor. It won't be an issue.

Hi, where should I ask before adding new features? I rewrote the implementation of ball pivoting. Does pcl need it? maybe I can fit it as a pcl class. One part of one function was from another repo https://github.com/t-lou/bpa_remake

I would say the place for that is the developer mailing list. I have no idea of what ball pivoting is, so I'll need to get acquainted with the topic. What general benefits did your implementation bring?

@t-lou
Copy link
Contributor Author

t-lou commented Jul 5, 2017

It is quite like greedy_projection, but slower and in my test case more robust(leaving fewer holes). Is it only necessary to mention the paper where the algorithm was proposed and avoid code from others?

Copy link
Member

@taketwo taketwo left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Note to self: will need to squash on merge.

@taketwo
Copy link
Member

taketwo commented Jul 5, 2017

Is it only necessary to mention the paper where the algorithm was proposed and avoid code from others?

Reference to the paper is very helpful to have. Code from others is fine as long as it is BSD or MIT I'd say.

Copy link
Member

@SergioRAgostinho SergioRAgostinho left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks good. Thank you all for your efforts

Final curiosity: from what I can tell the method just makes use of xyz and normal data. Why are actually using PointNT here and there?

p3.x = vertex_list[triTable[cubeindex][i+2]][0];
p3.y = vertex_list[triTable[cubeindex][i+2]][1];
p3.z = vertex_list[triTable[cubeindex][i+2]][2];
p3.getVector3fMap () = vertex_list[triTable[cubeindex][i+2]];
cloud.push_back (p3);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I just noticed that this cloud is only being populated with XYZ info. Why exactly are we using PointNT?

Copy link
Member

@SergioRAgostinho SergioRAgostinho left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Well ignore that... I think I have an idea now why.

Second reminder squash merge

@SergioRAgostinho SergioRAgostinho added status: ready to merge and removed needs: author reply Specify why not closed/merged yet labels Jul 5, 2017
@t-lou
Copy link
Contributor Author

t-lou commented Jul 5, 2017

Thank you for your help! I use this library a lot and I'm glad to be able to do something for it :D

@taketwo taketwo merged commit 04fa347 into PointCloudLibrary:master Aug 27, 2017
UnaNancyOwen pushed a commit to UnaNancyOwen/pcl that referenced this pull request Nov 24, 2017
PointCloudLibrary#1874)

Add spatial restriction for marching cube hoppe to avoid phantom surfaces in complex point clouds
@t-lou t-lou deleted the hoppe_phantom branch January 16, 2018 21:06
@taketwo taketwo changed the title spatial restriction for marching cube hoppe to avoid phantom surfaces… Avoid phantom surfces in marching cubes hoppe Sep 2, 2018
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants