ros-navigation / navigation2

ROS 2 Navigation Framework and System
https://nav2.org/
Other
2.51k stars 1.27k forks source link

Obstacle layer min_height does not get applied #4512

Closed anath93 closed 3 months ago

anath93 commented 3 months ago

Bug report

Required Info:

Steps to reproduce issue

In the obstacle layer, changing obstacle_layer.min_obstacle_height to any value other than 0.0 makes global/local costmaps not get observance data and publish.

with 0.0 as min_height (its long trash can) image

with 0.1 as min_height (its long trash can) image

Expected behavior

Range filtering should work for observance layers.

SteveMacenski commented 3 months ago

These are the only two places that the min height is used:

Can you point out where you think the issue lies? I don't see any different handling than max height, min/max ranges, invalid coordinates, etc. What happens if you change it in a param file and not via dynamic parameters?

Do you see any errors in the terminal?

anath93 commented 3 months ago

The issue looks like its in observation buffer, once min_height is set the loop never gets executed to copy the result. The set values look good in print statements but otherwise if 0.0 the loop gets executed. image

Question, for Laserscan messages, this parameter still applies right ? ( As I was looking into code and documentation ) https://docs.nav2.org/configuration/packages/costmap-plugins/obstacle.html

SteveMacenski commented 3 months ago

once min_height is set the loop never gets executed to copy the result. The set values look good in print statements but otherwise if 0.0 the loop gets executed.

Sorry, I don't quite understand what you said there to respond meaningfully with thoughts! That's an if statement that's already in the data iteration loop. How is this different from the max height?

Question, for Laserscan messages, this parameter still applies right ? ( As I was looking into code and documentation )

Yeah, technically the laser scans don't need to be planar, but functionally they are used that way most of the time (except when the robot is tilted and 6DOF odometry is provided from an IMU or similar)

anath93 commented 3 months ago

Apologies on my end, what I was getting at is the issue is in observance buffer side as when the min_obstacle_height is changed to any value other than 0.0 the if loop below never gets executed , which to your point it does not make sense to me as what is different than max_obstacle_height. To be honest, I am not quite sure how to debug this issue further.

SteveMacenski commented 3 months ago

What is the value of (*iter_z), min_obstacle_height_, and max_obstacle_height_, printing that might be informative.

What happens if you set the max height to something different? Have you done this with the parameter file like I suggested instead of RQT reconfigure? It could just be an issue with how the reconfiguration is being processed.

This code is very old, so I'm a bit suspicious that there's a problem here admittedly. You also haven't shown me your data (only the costmaps), is the data above 0.1m? Are there values of min_obstacle_height_ that work (0.01, 0.001)?

anath93 commented 3 months ago

What is the value of (*iter_z), min_obstacle_height_, and max_obstacle_height_, printing that might be informative.

the iter_z coming in small fraction value which is around e^15 which is why the "if" loop is not getting triggered as the data is at zero datum plane. min_obstacle_height and max_obstacle_height were at 0.05 and 2.0 set in params file which reflected the same.

Looks like there is issue on my data end coming in.

SteveMacenski commented 3 months ago

OK, I think the same thing from that description :+1: Have a look over at that instead :-) I think we can close this then?