ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

issue of ground filter in octomap_server

asked 2012-02-21 14:18:05 -0500

clark gravatar image

updated 2012-02-22 00:47:30 -0500

AHornung gravatar image

I am testing the octomap_server and I used the sample data from http://vimeo.com/1451349?pg=embed&sec=1451349, which is a pcap file collected from a velodyne 64 laser.

Judged from the video and the pointcloud display in rviz, the ground surface is obviously contained in the data set. In my testing, the base_frame_id is set to "base_footprint" which is exactly located at the ground surface; filter_ground is also set to "true". But the generated octomap never filters the ground... and this is the output from the node.

[INFO] [1329732147.087671086] class OctomapServer starts

[INFO] [1329732147.103789973] filter_ground 1

[WARN][1329732208.260183596] No plane found in cloud.

[WARN][1329732208.260282727] No ground plane found in scan

Thanks for any help.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
4

answered 2012-02-23 00:35:10 -0500

clark gravatar image

hi, Hornung,

After some debugging, I found the reason for the above filtering issue.

Check the sequence of the following lines in the function OctomapServer::insertCloudCallback of OctomapServer.cpp,

pass.setInputCloud(pc.makeShared());
......

pcl::transformPointCloud(pc, pc, sensorToBase);
pass.filter(pc);
filterGroundPlane(pc, pc_ground, pc_nonground);
......

Since the inputcloud for pass is allocated at the very beginning, so the actual "pc" passed to filterGroundPlane is the old one before transformPointCloud.

So I moved pass.setInputCloud(pc.makeShared()) to right after the line of transformPointCloud, and the ground filtering now works as expected.

The same change should also apply to the case when m_filterGroundPlane=false.

regards

edit flag offensive delete link more

Comments

Thanks a lot! That must have sneaked in during some recent refactoring. I had assumed makeShared simply returns a Ptr to the cloud, while the docs clearly state: "Copy the cloud to the heap and return a smart pointer. [...] The changes of the returned cloud are not mirrored back to this one"

AHornung gravatar image AHornung  ( 2012-02-24 04:49:42 -0500 )edit

Fixed in trunk of octomap_mapping

AHornung gravatar image AHornung  ( 2012-02-24 04:53:42 -0500 )edit
0

answered 2012-02-22 00:54:04 -0500

AHornung gravatar image

octomap_server uses PCL with pcl::SACMODEL_PERPENDICULAR_PLANE to detect and segment the ground plane, which has quite a few parameters to tune. Right now it should work best with stereo data from the PR2, laser data from the Velodyne might need different parameters.

Best have a look at OctomapServer::filterGroundPlane and the PCL documentation on which parameters to tune, ground_filter/distance and ground_filter/angle should be the first ones to try. You can also do a rough filterung just based on height with ground_filter/plane_distance.

Otherwise run rxconsole with setting octomap_server's log level to debug to see what is going on.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2012-02-21 14:18:05 -0500

Seen: 1,692 times

Last updated: Feb 23 '12