Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Off-by-one error in constructing/populating LaserScan message ? #14

Open
moooeeeep opened this issue Mar 27, 2018 · 6 comments
Open

Off-by-one error in constructing/populating LaserScan message ? #14

moooeeeep opened this issue Mar 27, 2018 · 6 comments
Assignees

Comments

@moooeeeep
Copy link

moooeeeep commented Mar 27, 2018

It seems that either you should also skip angles that equal the value of angle_max here:

Or make the number of range readings one item larger here:

Otherwise you'll have an out-of-bounds array element access when one day there is an angle of the value angle_max.

Note that I have posted a question here about how many values the sensor_msgs::LaserScan should actually contain, because I'm not sure if angle_max really is supposed to be excluded from the range of values.

@paulbovbel paulbovbel self-assigned this Mar 27, 2018
@paulbovbel
Copy link
Member

Thanks, this is interesting and I'll try to investigate sometime soon. If you have a suggested fix, a PR would be very welcome!

@paulbovbel
Copy link
Member

paulbovbel commented Mar 27, 2018

Reading your RA question, I think angle_max being inclusive should be the standard assumption, however it may help to clarify that in the message definition with a PR to sensor_msgs. Making the number of readings one larger would follow as the solution.

@moooeeeep
Copy link
Author

moooeeeep commented Mar 28, 2018

I think this is not so straight-forward, as you are dealing with some sort of histogram here (non-zero width bins), instead of actual rays.

Obviously you could just add one to the calculated size. But then you'd have a mostly useless top bin, when you have angle_min = -PI, angle_max = PI because std::atan2 wraps to the negative range for anything above angle_max itself, so its bin would likely be empty all the time.

Also you'd probably want to perform the check whether or not to skip a point based on the calculated bin index, instead of the actual angle, to take into account the non-zero bin width. For the same reason it might make sense to "correct" the angles that are assigned to the message after using them to set up the bin ranges from the user configuration. On the one hand to fix the case where the angle range is not divisible by the bin width, but also to let the "rays" point to the center of each bin (e.g., size = (angle_max - angle_min) / angle_increment + 1, angle_min = angle_min + angle_increment/2, angle_max = angle_min + (size - 1) * angle_increment).

In conclusion, this seems not so straight-forward and unfortunately I don't have a PR I could submit right now.

angle_max being inclusive indeed seems sensible but I don't want to imagine how many applications would break if one changed the message definition now.

@moooeeeep
Copy link
Author

moooeeeep commented Apr 6, 2018

I added a PR to address this issue.

@paulbovbel
Copy link
Member

paulbovbel commented Jun 27, 2018

I've turned this every which way and I'm not sure I've come up with a consistently good answer to this problem. The current behaviour of pointcloud_to_laserscan is definitely naive when it comes to range and bucket assignments.

I think we have to fallback to how the LaserScan is defined in relation to a 'real' LIDAR sensor. If the FOV of a hardware LIDAR is 2pi, I would expect [min, max] angle to be [-pi, pi], and I would expect there to be a ray return at [min, max] inclusive. So that means we have size = (angle_max - angle_min) / angle_increment + 1.

Now, how should pointcloud_to_laserscan translate a pointcloud into this format? The tricky thing is that for a hardware LIDAR, each return has a negligible FOV, and therefore a small obstacle could actually 'slip' through the cracks between rays. This is not what we try to do here, since I believe users generally want to capture all information in a pointcloud regardless of size. In the practical case, this probably leads to all sorts of questionable behaviour when this 'laserscan' is then used in say, the navigation stack. A user probably wants to make sure that angle_increment * range_max ~= costmap_cell_width, otherwise you'll get weird aliasing issues. Moving on...

If we assume each bucket captures an equal angle_increment, the min and max bucket will capture obstacles angle_increment / 2 outside of the defined FOV, which won't do. I believe this means that the min and max buckets should have a a half-increment so that we don't violate the defined FOV.


So this brings us to:

@moooeeeep
Copy link
Author

moooeeeep commented Sep 11, 2019

The way I addressed this in my PR, is by maintaining separately the valid angle range (currently with an exclusive upper bound: [angle_lower_bound, angle_upper_bound)) and the ray angles that belong to each of the buckets (inclusive max: [angle_min, angle_max]). The former can be specified directly by the user config, the latter are then calculated based on either the number of buckets or the desired angle increment here.

For example, when we configure an angle range of [-180°, 180°) and an angle increment of 90°, we receive four buckets. In the LaserScan message, the corresponding angles will then point to the center of each bin: -135°, -45°, 45°, 135°. Similarly, when we configure an angle range of [-180°, 180°) and a ranges_size of four, we receive an angle increment of 90° and the same angles in the output message.

So far, I did not add an option to directly configure the output angles and the increment that will appear in the LaserScan message and expand the valid angle range from that. Not sure if anyone would need this.

Also, as already indicated, in my implementation, the upper bound of the angle range is currently exclusive, for not having to check that edge case in the index calculation here. While this shouldn't make a difference for a 360° scan, this might become a problem when an entire column of the input cloud is ignored because the user specified the exact maximum angle of their sensor as an upper bound in the value range. Not sure how floating point accuracy (transforming spherical to Cartesian to polar coordinates) will mess up this exact boundary anyways though.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants