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

[autoware.auto] ray_ground_filter parameter limits

asked 2020-06-08 03:58:57 -0500

Andreas Lebherz gravatar image

Hello everyone,

I'm working on a lidar driver project (implement ros2 driver for an Ouster OS0 sensor) similar to the autoware.auto velodyne driver or SteveMacenski Ouster driver for ROS 2( https://github.com/SteveMacenski/ros2...).

The visualized Pointcloud does not look bad and I'm now trying to pass it downstream to the ray_ground_filter of the autoware.auto perception stack. As far as I understood this filter generates horizontal "rays" which look like circles around the vehicle to then separate the ground from the non-ground points/rays.

The sensor I use (Ouster OS0) outputs with a horizontal resolution of (512,1024,2048) points, which is more than the velodyne sensor as far as I understood.

Is it possible to use the ray_ground_filter (and in the following the rest of the perception stack) with a higher resoluting lidar than the one used in the autoware stack? Is there a way to change the limits of the received Pointcloud in order to work with a higher resoluting lidar?

When I try to use it I receive an error complaining about a ray becoming too long - which totally makes sense for me. (I tilted the sensor afterwards and the ground-filter worked as expected.)

Thanks a lot!

(setup: Ubuntu 18.04, ROS2 dashing diademata, autoware.auto ade container, Ouster OS0 sensor)

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-06-09 10:16:08 -0500

Josh Whitley gravatar image

It should work just fine with a higher-resolution lidar, but possibly not out-of-the-box. Like most nodes in Autoware.AUTO, the ray_ground_classifierhas a handful of parameters to configure and we currently do that through a YAML file. You can see an example here: https://gitlab.com/autowarefoundation...

Since the node is designed to avoid dynamic memory allocation, you can set a max size for each of the output point clouds in the pcl_size parameter. You'll also want to set the classifier set of parameters to match your sensor mounting configuration for proper segmentation. Hope this helps.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-06-08 03:58:57 -0500

Seen: 673 times

Last updated: Jun 09 '20