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

Normals at edges all go trough origin #3269

Open
Kaju-Bubanja opened this issue Aug 5, 2019 · 10 comments
Open

Normals at edges all go trough origin #3269

Kaju-Bubanja opened this issue Aug 5, 2019 · 10 comments

Comments

@Kaju-Bubanja
Copy link
Contributor

Kaju-Bubanja commented Aug 5, 2019

The issue is best illustrated in an image:
Screenshot from 2019-08-05 17-24-16

Your Environment

  • Operating System and version: Ubuntu 18.04
  • Compiler: Used Ubuntu pre built binaries
  • PCL Version: 1.8.1

Context

I try to estimate the normals of some bricks lying on the floor. But as seen in the image all the normals at edges connect to the origin.

Expected Behavior

Proper normals estimation

Current Behavior

Code to Reproduce

void compute_normals(pcl::IntegralImageNormalEstimation<pcl::PointXYZRGB, pcl::Normal>& ne, pcl::visualization::PCLVisualizer& viewer,
                     pcl::PointCloud<pcl::PointXYZRGB>::Ptr& input_cloud, pcl::PointCloud<pcl::Normal>::Ptr& output_cloud, float normal_smoothing_size,
                     int normal_cloud_visualization_densitiy){
  ros::WallTime start = ros::WallTime::now();
  ne.setNormalSmoothingSize(normal_smoothing_size);
  ne.setInputCloud(input_cloud);
  ne.compute(*output_cloud);
  viewer.removeAllPointClouds();
  viewer.addPointCloudNormals<pcl::PointXYZRGB, pcl::Normal>(input_cloud, output_cloud, normal_cloud_visualization_densitiy);
  viewer.spinOnce ();
  stop(start, "Normals");
}

I could upload a rosbag if needed.

Possible Solution

I have no clue, but I saw that the neighborhoud search radius makes the problem worse the bigger it is. The above image uses a radius of 15. The one below uses a radius of 5:
Screenshot from 2019-08-05 17-24-30

@SergioRAgostinho
Copy link
Member

Nice image. Let's try some cheap tricks first: can you try the fix in #3169 and see if it solves your problem?

@Kaju-Bubanja
Copy link
Contributor Author

I tried the patch, but it makes no difference. But for me that makes sense, because the pointcloud is very close to the origin.

@Kaju-Bubanja
Copy link
Contributor Author

I was hoping this issue might have been fixed in 1.9.1, but it both happens in 1.8.1 and 1.9.1

@Kaju-Bubanja
Copy link
Contributor Author

I wrote an mvce and would be glad if somebody could confirm this. It uses ros melodic, a realsense d415 and pcl 1.9.1:

#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <pcl/features/integral_image_normal.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/visualization/cloud_viewer.h>

class test {
public:
    pcl::IntegralImageNormalEstimation<pcl::PointXYZRGB, pcl::Normal> ne;
    pcl::visualization::PCLVisualizer viewer;
    ros::NodeHandle nh_;
    ros::Subscriber points_sub_;
    test(){
        points_sub_ = nh_.subscribe("/camera/depth_registered/points", 1, &test::point_cloud_cb, this);
    }

    void point_cloud_cb(const sensor_msgs::PointCloud2::Ptr &msg) {
        pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
        pcl::PointCloud<pcl::Normal>::Ptr cloud_normals(new pcl::PointCloud<pcl::Normal>);
        pcl::fromROSMsg(*msg, *cloud);
        ne.setNormalEstimationMethod (ne.AVERAGE_DEPTH_CHANGE);
        ne.setNormalSmoothingSize(15.0);
        ne.setInputCloud(cloud);
        ne.compute(*cloud_normals);
        viewer.removeAllPointClouds();
        viewer.addPointCloudNormals<pcl::PointXYZRGB, pcl::Normal>(cloud, cloud_normals, 30.0);
        viewer.spinOnce ();
    }
};


int main(int argc, char **argv) {
    ros::init(argc, argv, "mytest");
    test t;
    ros::spin();
    return 0;
}

CMakeLists.cmake

cmake_minimum_required(VERSION 3.5.0)
project(test_project)

find_package(catkin REQUIRED COMPONENTS
    roscpp
    rospy
    std_msgs
    tf2
    tf2_ros
    tf2_msgs
    tf2_geometry_msgs
    tf2_sensor_msgs
)
find_package( PCL 1.9.1 REQUIRED )

include_directories(
        include
        ${catkin_INCLUDE_DIRS}
        ${PCL_INCLUDE_DIRS}
)
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})

add_executable(mytest src/test.cpp)
target_link_libraries(mytest ${PCL_LIBRARIES} ${catkin_LIBRARIES})

@Kaju-Bubanja
Copy link
Contributor Author

I tried it with the other normal estimation method from here and I don't get this strange artefacts, but it takes 30s so this is not really an option.

@Kaju-Bubanja
Copy link
Contributor Author

I could confirm that this is happening with another camera and another rosbag aswell, so it seems to be really a thing in pcl.
Screenshot from 2019-08-08 09-29-25

@Kaju-Bubanja
Copy link
Contributor Author

So looking at the data, all the points that connect to the origin have nan values. If this new behavior of visualizing nans like this is normal, somebody can close this. Otherwise some advice would be appreciated.

@SergioRAgostinho
Copy link
Member

Hey. I see your mvce still requires ros, so it can be further reduced. Can you save your test pointcloud as a pcd file and upload it somewhere. Make your mvce load that pcd and render it as you're currently already doing.

@Kaju-Bubanja
Copy link
Contributor Author

Ok, I got around to make the example smaller:
CmakeLists.txt

cmake_minimum_required(VERSION 3.9.6)
project(cuboid_detection)

find_package( PCL 1.9.1 REQUIRED )

link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})

add_executable(mytest src/test.cpp)
target_link_libraries(mytest ${PCL_LIBRARIES})

test.cpp

#include <pcl/features/integral_image_normal.h>
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/io/pcd_io.h>


int main(int argc, char **argv) {
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
  pcl::io::loadPCDFile<pcl::PointXYZ> ("test_pcd.pcd", *cloud);
  pcl::IntegralImageNormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
  pcl::PointCloud<pcl::Normal>::Ptr cloud_normals(new pcl::PointCloud<pcl::Normal>);
  ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT);
  ne.setNormalSmoothingSize(10.0);
  ne.setInputCloud(cloud);
  ne.compute(*cloud_normals);
  pcl::visualization::PCLVisualizer viewer;
  viewer.removeAllPointClouds();
//        viewer.addPointCloudNormals<pcl::PointXYZ, pcl::Normal>(cloud, cloud_normals, 30.0);
  viewer.addPointCloudNormals<pcl::PointXYZ, pcl::Normal>(cloud, cloud_normals, 30.0);
  viewer.spin();
    return 0;
}

PCD file
https://gofile.io/?c=9MtwAG

@stale
Copy link

stale bot commented May 19, 2020

Marking this as stale due to 30 days of inactivity. It will be closed in 7 days if no further activity occurs.

@stale stale bot added the status: stale label May 19, 2020
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

2 participants