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

Fixed normal accumulator vector normalization when there is no normal information (0,0,0). #1728

Conversation

carlosmccosta
Copy link
Contributor

When accumulating points with normal fields but without being initialized (or used yet), the accumulator will fill the normal fields with nan values due to a division by zero (when normalizing the normal vector).

This is a bug that was corrected in recent versions of Eigen (they now check if the divisor is > 0).
https://bitbucket.org/eigen/eigen/commits/12f866a74661131a38c71516007ebf6fc51abd3b
https://bitbucket.org/eigen/eigen/src/e8c837cc9c68df7675b6590e559d1636fb5d8205/Eigen/src/Core/Dot.h?at=default&fileviewer=file-view-default#Dot.h-139

However, even who is using the latest version of Eigen from Ubuntu 16.04 PPA is still affected by this issue.
This can break a typical point cloud processing pipeline in the preprocessing stage, for example:
-> capture Kinect data
-> remove all points with nans
-> voxel grid downsampling
-> more preprocessing stages (such as normal estimation, that might be skipped depending on the runtime user configuration)
-> remove all points with nans
-> cloud registration
-> post processing

After the second removal of points with nans there will be no points left (since they all had nan values in their normals when the user configured the system to skip the normal estimation).

Should this be fixed on the PCL side or should it be added to a warning list for the PCL users?

@taketwo
Copy link
Member

taketwo commented Sep 30, 2016

Well there is a note in the CentroidPoint class saying that we assume that valid points are inserted. However, there might indeed be a situation when the average of valid normals is an all-zero vector. But is returning an all-zero normal in this case better than NaNs? It's not a valid normal anyway, what's the difference?

@carlosmccosta
Copy link
Contributor Author

This is an issue in a runtime configurable pipeline in which the points may have normal information or may remain with an uninitialized value of (0,0,0).
I am the author of the dynamic_robot_localization ROS package which relies heavily on PCL (hats off for this awesome library :) ).
https://github.com/carlosmccosta/dynamic_robot_localization
It's runtime modules are configurable with .yaml files:
https://github.com/carlosmccosta/dynamic_robot_localization/blob/kinetic-devel/yaml/schema/drl_configs.yaml

Since the pipeline may or may not use normal information for computing keypoints, i must compile it with point types that include normal information.
But depending on the user configuration and also if the system is tracking a robot pose using icp / ndt or estimating it's initial position using geometric features, the normal information may or may not be initialized / used.

Assume that the localization system mentioned above is in tracking mode, so there is no need to compute normals for the sensor data.
This will happen:

  1. Convert ROS message with kinect / laser data to PCL point cloud (since the sensor data has no normals, all points will have normals with (0,0,0) value)
  2. Preprocess sensor point cloud (using for example the voxel grid) -> this will cause all points that had an uninitialized normal value of (0,0,0) to now have a value of (nan, nan, nan)
  3. Remove all points that have nan values in xyz and normal data -> this will cause the removal of all points
  4. Other processing modules now have a empty sensor point cloud (causing the system to lose tracking)

Long story short, if the normal fields are uninitialized, they should remain uninitialized.
Otherwise there is no way of knowing if the normal information is not present or if the normals are invalid.

@taketwo
Copy link
Member

taketwo commented Oct 1, 2016

Thanks for the explanation. I agree with what you propose.

Do I understand right that upstream Eigen already has zero check? If so, can we add conditional compilation so that with "new" Eigen we do not do extra work?

@carlosmccosta
Copy link
Contributor Author

Ubuntu 16.04 is currently using eigen3 3.3~beta1, that was published in 2016-01-11
https://launchpad.net/ubuntu/xenial/+package/libeigen3-dev
https://launchpad.net/ubuntu/+source/eigen3/3.3~beta1-2

The commit that added the zero check was done in 2016-01-21
https://bitbucket.org/eigen/eigen/commits/12f866a74661131a38c71516007ebf6fc51abd3b

And is included in the release 3.3-beta2 and 3.3-rc1 of eigen
https://bitbucket.org/eigen/eigen/src/69d418c0699907bcd0bf9e0b3ba0a112ed091d85/Eigen/src/Core/Dot.h?at=3.3-beta2&fileviewer=file-view-default#Dot.h-143
https://bitbucket.org/eigen/eigen/src/bef509908b9da05d0d07ffc0da105e2c8c6d3996/Eigen/src/Core/Dot.h?at=3.3-rc1&fileviewer=file-view-default#Dot.h-143

Assuming that the zero check will remain in the final release of eigen 3.3, it could be added a minimum version check:
https://bitbucket.org/eigen/eigen/src/bef509908b9da05d0d07ffc0da105e2c8c6d3996/Eigen/src/Core/util/Macros.h?at=3.3-rc1&fileviewer=file-view-default#Macros.h-18

For example:

if (EIGEN_VERSION_AT_LEAST (3, 3, 0) || normal.squaredNorm () > 0)
  t.getNormalVector4fMap () = normal.normalized ();
else
  t.getNormalVector4fMap () = Eigen::Vector4f::Zero ();

Should i amend the PR commit with the code above?

@taketwo
Copy link
Member

taketwo commented Oct 1, 2016

Yes, please!

On Oct 1, 2016 13:59, "Carlos Miguel Correia da Costa" <
notifications@github.com> wrote:

Ubuntu 16.04 is currently using eigen3 3.3~beta1, that was published in
2016-01-11
https://launchpad.net/ubuntu/xenial/+package/libeigen3-dev
https://launchpad.net/ubuntu/+source/eigen3/3.3~beta1-2
https://launchpad.net/ubuntu/+source/eigen3/3.3%7Ebeta1-2

The commit that added the zero check was done in 2016-01-21
https://bitbucket.org/eigen/eigen/commits/12f866a74661131a38c71516007ebf
6fc51abd3b

And is included in the release 3.3-beta2 and 3.3-rc1 of eigen
https://bitbucket.org/eigen/eigen/src/69d418c0699907bcd0bf9e0b3ba0a1
12ed091d85/Eigen/src/Core/Dot.h?at=3.3-beta2&fileviewer=
file-view-default#Dot.h-143
https://bitbucket.org/eigen/eigen/src/bef509908b9da05d0d07ffc0da105e
2c8c6d3996/Eigen/src/Core/Dot.h?at=3.3-rc1&fileviewer=file-
view-default#Dot.h-143

Assuming that the zero check will remain in the final release of eigen
3.3, it could be added a minimum version check:
https://bitbucket.org/eigen/eigen/src/bef509908b9da05d0d07ffc0da105e
2c8c6d3996/Eigen/src/Core/util/Macros.h?at=3.3-rc1&
fileviewer=file-view-default#Macros.h-18

For example:

if (EIGEN_VERSION_AT_LEAST (3, 3, 0) || normal.squaredNorm () > 0)
t.getNormalVector4fMap () = normal.normalized ();
else
t.getNormalVector4fMap () = Eigen::Vector4f::Zero ();

Should i amend the PR commit with the code above?


You are receiving this because you commented.
Reply to this email directly, view it on GitHub
#1728 (comment),
or mute the thread
https://github.com/notifications/unsubscribe-auth/ABLyiF9u0JUurt9f2kZljOkefw8SfFp3ks5qvksUgaJpZM4KLZaT
.

@carlosmccosta
Copy link
Contributor Author

I improved the previous code in order to perform the eigen version check at compite time.
This way there is no runtime overhead.

#if EIGEN_VERSION_AT_LEAST (3, 3, 0)
  t.getNormalVector4fMap () = normal.normalized ();
#else
  if (normal.squaredNorm() > 0)
    t.getNormalVector4fMap () = normal.normalized ();
  else
    t.getNormalVector4fMap () = Eigen::Vector4f::Zero ();
#endif

@taketwo
Copy link
Member

taketwo commented Oct 1, 2016

I'm pretty sure every modern compiler will be able to optimize if (EIGEN_VERSION_AT_LEAST (3, 3, 0) || normal.squaredNorm () > 0) since the result of the version check is a compile-time constant. But anyway, nothing wrong if we are explicit.

@taketwo taketwo added this to the pcl-1.8.1 milestone Oct 1, 2016
@SergioRAgostinho SergioRAgostinho merged commit dd532fe into PointCloudLibrary:master Oct 3, 2016
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants