-
Notifications
You must be signed in to change notification settings - Fork 1.3k
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
Validate messages in subscription callbacks for critical error in population #4177
Comments
some suggestions to avoid such buffer-overflow:
|
It is usually expected that inputs are well formed - but even in writing this answer I find myself disagreeing with myself that maybe we should do some basic message validation to prevent and/or expose potential problems before users run into them. My suggestion would be to audit the input information to Nav2 (occupancy grid messages, pointclouds, laser scans, etc) to get a list of all message types that come in. Then, we can look at them to see what places we need to do validation checks to make sure the message won't bring down the system (ie map size and actual data don't match; pointcloud strides and its data size don't match; unimplemented or invalid values in LaserScan angles, etc). At that point, we can make a new Basically change all callbacks to first thing do
Or, even more interestingly, we could use the topic tools in ROS 2 to create a message filter that the filter does this action so that all callbacks when triggered have already been pre-validated. There's examples of this using TF transforms, but we can make arbitrary filters. |
Interesting suggestion! ^_^ I agree that basic message validation is in need, especially considering the exposure of ros2-topics within the local network, where they are susceptible to both intentional and unintentional interference (in my opinion. Your proposed solution indeed sounds great, while I must admit that direct implementation of nav2_util/validate_messages.hpp might be challenging for me. However, if there's already a basic framework of |
It should just be a set of header files
It should be very straight forward. I won't have time for this and since this is something important to you, I suggest taking the lead on it. The checks are simple: sizes match necessary sizes, no INF or NAN in key fields. It doesn't need to check quality, just anything that would cause a segfault or NAN where it isn't expected |
May I open a long-term PR after implementing a basic framework, to continually update it whenever I come across new tickets? Alternatively, should I open a PR dedicated solely to fixing this issue after implementing the framework, and then open new PRs to address any new input validation issues that arise? I want to choose one of them that minimizes disruption to you while still being effective. ^_^ |
That sounds like a plan:
The only thing I'd ask is that you make sure to setup for all subscriptions of a given type when you add it in one place (ie all occ grid subscribers) so that we don't have some where its done and some where its not. But, I think that perfectly aligns with your intent / need so I don't think you'd have an issue with that :-) |
nav2_amcl
Bug report
Required Info:
Steps to reproduce issue
Launch the navigation2 normally, as following steps:
Curious about how nav2 face to topic-interception, i keep sending demaged
/map
msg onto topic/map
, which is like this:[notice] the real length of data is less than width*height
then, the asan report would occur.
Expected behavior
Actual behavior
The ASAN reporting a buffer-overflow bug to me, as following:
Additional information
code analysis:
in function
AmclNode::convertMap()
thefor
use thesize_x*size_y
as the boundary of the vectormap_msg.data
however, the real length of the vector
map_msg.data
is up to the user's command which may be less thansize_x*size_y
thus, it would bring a buffer-overflow because out of the boundary of the vector.
The text was updated successfully, but these errors were encountered: