Giter Club home page Giter Club logo

Comments (6)

SteveMacenski avatar SteveMacenski commented on August 29, 2024

That appears to be the case! I think adding a mutex lock should square that up. The laser scan sub is in a different callback group on another executor https://github.com/ros-navigation/navigation2/blob/main/nav2_amcl/src/amcl_node.cpp#L1510-L1513 so they're not synchronized

from navigation2.

GoesM avatar GoesM commented on August 29, 2024

well, I think there's a better way to fix it but not adding a mutex lock, because of following facts:

Let's notice that:

} else if (param_name == "z_rand") {
z_rand_ = parameter.as_double();
reinit_laser = true;

some dynamic parameter setting could let reinit_laser = true, and then do following code lines:

// Re-initialize the lasers and it's filters
if (reinit_laser) {
lasers_.clear();
lasers_update_.clear();
frame_to_laser_.clear();
laser_scan_connection_.disconnect();
laser_scan_sub_.reset();
initMessageFilters();
}

However, we could find here's a lack of laser_scan_filter_ .reset() before initMessageFilters().

As we know, the callback functions called by lase_scan_filter_ would access the memory , which would be freed during initMessageFilters() , so that a use-after-free bug occurs.

from navigation2.

GoesM avatar GoesM commented on August 29, 2024

In summary

similar to z_rand , I have found many other dynamic parameters could lead to such UAF bug, I'd share them here as tickets for this ISSUE and I changed the title of this ISSUE:

  1. ros2 param set /amcl beam_skip_distance 0.5
  2. ros2 param set /amcl beam_skip_error_threshold 0.9
  3. ros2 param set /amcl beam_skip_threshold 0.3
  4. ros2 param set /amcl lambda_short 0.1
  5. ros2 param set /amcl laser_likelihood_max_dist 2.0
  6. ros2 param set /amcl laser_max_range 100.0
  7. ros2 param set /amcl laser_min_range -1.0
  8. ros2 param set /amcl sigma_hit 0.2
  9. ros2 param set /amcl transform_tolerance 1.0
  10. ros2 param set /amcl z_hit 0.5
  11. ros2 param set /amcl z_max 0.05
  12. ros2 param set /amcl z_rand 0.5
  13. ros2 param set /amcl z_short 0.05
  14. ros2 param set /amcl laser_model_type likelihood_field
  15. ros2 param set /amcl odom_frame_id odom
  16. ros2 param set /amcl scan_topic scan
  17. ros2 param set /amcl do_beamskip False
  18. ros2 param set /amcl max_beams 60

from navigation2.

SteveMacenski avatar SteveMacenski commented on August 29, 2024

So you're suggesting that we reset the message filter at the start of the dynamic parameter callback and then re-initialize it at the end to kill the extra thread? I think that would work in practice, but I think the mutex is a bit cleaner and in line with what we've done elsewhere in the stack for consistency.

Also constantly creating / destroying the data reader could uncover some DDS vendor implementation issues since that's really exercising the stability of their solution. I don't know that we'd find any bugs, but that would certainly be a good way to trigger them if there was some memory leaks. So in the back of my mind I'd rather not test it if we have an alternative that seems reasonable. The dynamic parameter callbacks are quick so I think this should be fine to mutex lock them :-)

from navigation2.

GoesM avatar GoesM commented on August 29, 2024

So you're suggesting that we reset the message filter at the start of the dynamic parameter callback and then re-initialize it at the end to kill the extra thread?

Because I'm considering that the current design approach of nav2_amcl seems to work indeed in this way.

After amcl receiving the instruction to change dynamic parameters, the related threads are closed :

// Re-initialize the lasers and it's filters
if (reinit_laser) {
lasers_.clear();
lasers_update_.clear();
frame_to_laser_.clear();
laser_scan_connection_.disconnect();
laser_scan_sub_.reset();
initMessageFilters();
}

and then these threads would be restarted within the new configuration by initMessageFilters();

void
AmclNode::initMessageFilters()
{
auto sub_opt = rclcpp::SubscriptionOptions();
sub_opt.callback_group = callback_group_;
laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
rclcpp_lifecycle::LifecycleNode>>(
shared_from_this(), scan_topic_, rmw_qos_profile_sensor_data, sub_opt);
laser_scan_filter_ = std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
*laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10,
get_node_logging_interface(),
get_node_clock_interface(),
transform_tolerance_);
laser_scan_connection_ = laser_scan_filter_->registerCallback(
std::bind(
&AmclNode::laserReceived,
this, std::placeholders::_1));
}


Additionally, I've had a try on it , by adding the code laser_scan_filter_.reset(); as following:

  // Re-initialize the lasers and it's filters
  if (reinit_laser) {
    lasers_.clear();
    lasers_update_.clear();
    frame_to_laser_.clear();
    laser_scan_connection_.disconnect();
    laser_scan_filter_.reset();
    laser_scan_sub_.reset();

    initMessageFilters();
  }

And then these 18 commands for changing dynamic parameters would work correctly.


So in the back of my mind I'd rather not test it if we have an alternative that seems reasonable. The dynamic parameter callbacks are quick so I think this should be fine to mutex lock them :-)

Sorry, I might not fully understand this method. Do you mean changing the current design, removing all the code that closes the threads, and instead using a locking method?

I feel that I need to understand your suggestion more clearly, and then proceed with my future work based on your recommendation. ^_^

from navigation2.

SteveMacenski avatar SteveMacenski commented on August 29, 2024

On further thought, what you say makes sense, lets do that!

from navigation2.

Related Issues (20)

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.