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

ray_ground_filter differing from specification?

asked 2020-08-17 09:17:52 -0500

pedroexe gravatar image

updated 2020-08-18 04:57:31 -0500

I'm looking at the implementation for the ray_ground_filter for Autoware.AI, while also reading the documentation (from Autoware.Auto, referred by the Autoware.AI repo).

From the documentation, if the current point is not within the local cone it will only be set as 'ground' if it is distant by a minimum threshold and, at the same time, is within the global cone.

However, the code is comparing the current height with the local cone height instead of the global cone height. I believe this comparison is in line 197 of the code (commit 4bf37a8).

Shouldn't it be comparing:

(current_height <= general_height_threshold && current_height >= -general_height_threshold)

instead of the current:

(current_height <= height_threshold && current_height >= -height_threshold)?

Otherwise, am I missing something on how this is compliant with the documentation?

Thank you.

edit retag flag offensive close merge delete

Comments

@TakaHoribe can you comment on this?

Josh Whitley gravatar image Josh Whitley  ( 2020-08-20 19:57:22 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2020-11-17 22:38:47 -0500

TakaHoribe gravatar image

I asked my colleague who is familiar with this algorithm and compared the original paper. Yes, it is a bug. As you say, this line should be fixed to replace height_threshold with general_height_threshold.

Our team is taking this issue, so will be fixed soon.

Thank you very much for your report and sorry for the late response.

edit flag offensive delete link more

Comments

Great! Thanks for confirming.

pedroexe gravatar image pedroexe  ( 2020-11-20 08:43:40 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-08-17 09:17:52 -0500

Seen: 248 times

Last updated: Nov 17 '20