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

ground plane filtering in uneven terrain in a pointcloud?

asked 2019-11-07 22:25:13 -0500

PapaG gravatar image

Hi.

I am using the Velodyne Puck for obstacle detection in a robot that needs to traverse uneven terrain. I was wondering what the best way to filter the ground is? I have looked at rtabmap in simulation which was able to filter the ground using a kinect. In practice however, it is not filtering my ground plane. I suspect it is because as we move further away, the distance between scans gets larger (since its just a 3D representation of 2D scans).

Thanks, Grant.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-11-16 20:42:21 -0500

matlabbe gravatar image

rtabmap_ros/obstacles_detection may not work out-of-the-box with 3D lidar scans like the velodyne. The approach assumes the cloud is relatively uniformly dense and close to the robot, like stereo or rgb-d clouds. The velodyne creates 16 lines or rays that are far from the others on a flat ground, which make the normals estimation difficult of the point cloud. Normals (looking up) are used to detect the ground, then points are clustered to a maximum distance.

Filtering parameters can be shown with:

$ rtabmap --params | grep Grid/

Example with kitti2bag sample bag:

$ roscore
$ rosparam set use_sim_time true
$ rosrun nodelet nodelet standalone rtabmap_ros/obstacles_detection cloud:=/kitti/velo/pointcloud _Grid/PreVelFiltering:=true _Grid/CellSize:=0.5 _Grid/ClusterRadius:=1 _Grid/FlatObstacleDetected:=false  _Grid/NormalK:=20 _Grid/RangeMax:=0  _wait_for_transform:=true _Grid/MaxGroundAngle:=15
$ rosbag play --clock --pause kitti_2011_09_26_drive_0002_synced.bag

image description

Note the 2 red lines on the road far ahead, the normal estimation could not get enough neighbors to correctly estimate the normals of those points. Grid/NormalK (search K neighbors) and/or Grid/CellSize could be tuned to include them.

Warning: the input cloud should be dense if there is only one row, otherwise the output obstacle and ground clouds will be empty. There is an issue with the bag created from kitti2bag, the cloud has height 1 but is not dense (but it should). Either set the following in kitti2bag.py:

pcl_msg.is_dense = True

or update rtabmap_ros, I've made a fix detecting this issue.

cheers,
Mathieu

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2019-11-07 22:25:13 -0500

Seen: 1,659 times

Last updated: Nov 16 '19