ros-navigation / navigation2

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

[nav2_costmap] UAF bug caused by incomplete closed `dynamicParametersCallback` thread in `Inflation_layer_` #4497

Closed GoesM closed 5 days ago

GoesM commented 6 days ago

Bug report

Required Info:

Steps to reproduce issue

Bug happened in my normal usage.

Launch the navigation2 as following steps:

#!/bin/bash
export ASAN_OPTIONS=halt_on_error=0:new_delete_type_mismatch=0:detect_leaks=0:log_pah=asan
source install/setup.bash
export TURTLEBOT3_MODEL=waffle
export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:/opt/ros/humble/share/turtlebot3_gazebo/models
ros2 launch nav2_bringup tb3_simulation_launch.py headless:=True use_rviz:=False use_composition:=False 

Expected behavior

no bug occured.

Actual behavior

the Asan report of this bug is as following:

=================================================================
==171389==ERROR: AddressSanitizer: heap-use-after-free on address 0x6150000bb620 at pc 0x55a6b60ee814 bp 0x7fdffeffb0e0 sp 0x7fdffeffa8a8
    #1 0x7fe00c983cb5 in nav2_costmap_2d::InflationLayer::dynamicParametersCallback(std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> >) (/home/*****/nav2_humble/install/nav2_costmap_2d/lib/liblayers.so+0x183cb5) (BuildId: 5b6a8053951b59c23ea7f461b781c5a72a39a6dd)
    #2 0x7fe00c9899cb in rcl_interfaces::msg::SetParametersResult_<std::allocator<void> > std::__invoke_impl<rcl_interfaces::msg::SetParametersResult_<std::allocator<void> >, rcl_interfaces::msg::SetParametersResult_<std::allocator<void> > (nav2_costmap_2d::InflationLayer::*&)(std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> >), nav2_costmap_2d::InflationLayer*&, std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> > const&>(std::__invoke_memfun_deref, rcl_interfaces::msg::SetParametersResult_<std::allocator<void> > (nav2_costmap_2d::InflationLayer::*&)(std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> >), nav2_costmap_2d::InflationLayer*&, std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> > const&) (/home/*****/nav2_humble/install/nav2_costmap_2d/lib/liblayers.so+0x1899cb) (BuildId: 5b6a8053951b59c23ea7f461b781c5a72a39a6dd)
    #3 0x7fe00c9898a2 in std::_Function_handler<rcl_interfaces::msg::SetParametersResult_<std::allocator<void> > (std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> > const&), std::_Bind<rcl_interfaces::msg::SetParametersResult_<std::allocator<void> > (nav2_costmap_2d::InflationLayer::* (nav2_costmap_2d::InflationLayer*, std::_Placeholder<1>))(std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> >)> >::_M_invoke(std::_Any_data const&, std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> > const&) (/home/*****/nav2_humble/install/nav2_costmap_2d/lib/liblayers.so+0x1898a2) (BuildId: 5b6a8053951b59c23ea7f461b781c5a72a39a6dd)
    #4 0x7fe00befc401  (/opt/ros/humble/lib/librclcpp.so+0x10d401) (BuildId: bd69d2a87470f6b9fdc0534ef05dc334083a0b6c)
    #5 0x7fe00bf00f31 in rclcpp::node_interfaces::NodeParameters::set_parameters_atomically(std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> > const&) (/opt/ros/humble/lib/librclcpp.so+0x111f31) (BuildId: bd69d2a87470f6b9fdc0534ef05dc334083a0b6c)
    #6 0x7fe00bf7a16c  (/opt/ros/humble/lib/librclcpp.so+0x18b16c) (BuildId: bd69d2a87470f6b9fdc0534ef05dc334083a0b6c)
    #7 0x7fe00bf37757  (/opt/ros/humble/lib/librclcpp.so+0x148757) (BuildId: bd69d2a87470f6b9fdc0534ef05dc334083a0b6c)
    #8 0x7fe00bf45cfe  (/opt/ros/humble/lib/librclcpp.so+0x156cfe) (BuildId: bd69d2a87470f6b9fdc0534ef05dc334083a0b6c)
    #9 0x7fe00bed8375  (/opt/ros/humble/lib/librclcpp.so+0xe9375) (BuildId: bd69d2a87470f6b9fdc0534ef05dc334083a0b6c)
    #10 0x7fe00bed5d59 in rclcpp::Executor::execute_service(std::shared_ptr<rclcpp::ServiceBase>) (/opt/ros/humble/lib/librclcpp.so+0xe6d59) (BuildId: bd69d2a87470f6b9fdc0534ef05dc334083a0b6c)
    #11 0x7fe00bed60c5 in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&) (/opt/ros/humble/lib/librclcpp.so+0xe70c5) (BuildId: bd69d2a87470f6b9fdc0534ef05dc334083a0b6c)
    #12 0x7fe00bedd97f in rclcpp::executors::SingleThreadedExecutor::spin() (/opt/ros/humble/lib/librclcpp.so+0xee97f) (BuildId: bd69d2a87470f6b9fdc0534ef05dc334083a0b6c)
    #13 0x7fe00c5fb4e1 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<nav2_util::NodeThread::NodeThread(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>)::$_0> > >::_M_run() node_thread.cpp
    #14 0x7fe00b0dc252  (/lib/x86_64-linux-gnu/libstdc++.so.6+0xdc252) (BuildId: e37fe1a879783838de78cbc8c80621fa685d58a2)
    #15 0x7fe00ac94ac2 in start_thread nptl/./nptl/pthread_create.c:442:8
    #16 0x7fe00ad2684f  misc/../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

0x6150000bb620 is located 32 bytes inside of 464-byte region [0x6150000bb600,0x6150000bb7d0)
freed by thread T1 here:
    #0 0x55a6b6192a3d in operator delete(void*) (/home/*****/nav2_humble/install/nav2_planner/lib/nav2_planner/planner_server+0xeaa3d) (BuildId: 0d01382f47fffafcf72baea8200635e7f56bf31c)
    #1 0x7fe00c75ca77 in void class_loader::ClassLoader::onPluginDeletion<nav2_costmap_2d::Layer>(nav2_costmap_2d::Layer*) (/home/*****/nav2_humble/install/nav2_costmap_2d/lib/libnav2_costmap_2d_core.so+0x110a77) (BuildId: b7ddb351c48c8395862235fbf34b497039a1931a)

previously allocated by thread T0 here:
    #0 0x55a6b61921dd in operator new(unsigned long) (/home/*****/nav2_humble/install/nav2_planner/lib/nav2_planner/planner_server+0xea1dd) (BuildId: 0d01382f47fffafcf72baea8200635e7f56bf31c)
    #1 0x7fe00c9879fd in class_loader::impl::MetaObject<nav2_costmap_2d::InflationLayer, nav2_costmap_2d::Layer>::create() const (/home/*****/nav2_humble/install/nav2_costmap_2d/lib/liblayers.so+0x1879fd) (BuildId: 5b6a8053951b59c23ea7f461b781c5a72a39a6dd)

Thread T14 created by T0 here:
    #0 0x55a6b614088c in __interceptor_pthread_create (/home/*****/nav2_humble/install/nav2_planner/lib/nav2_planner/planner_server+0x9888c) (BuildId: 0d01382f47fffafcf72baea8200635e7f56bf31c)
    #1 0x7fe00b0dc328 in std::thread::_M_start_thread(std::unique_ptr<std::thread::_State, std::default_delete<std::thread::_State> >, void (*)()) (/lib/x86_64-linux-gnu/libstdc++.so.6+0xdc328) (BuildId: e37fe1a879783838de78cbc8c80621fa685d58a2)

Thread T1 created by T0 here:
    #0 0x55a6b614088c in __interceptor_pthread_create (/home/*****/nav2_humble/install/nav2_planner/lib/nav2_planner/planner_server+0x9888c) (BuildId: 0d01382f47fffafcf72baea8200635e7f56bf31c)
    #1 0x7fe00b0dc328 in std::thread::_M_start_thread(std::unique_ptr<std::thread::_State, std::default_delete<std::thread::_State> >, void (*)()) (/lib/x86_64-linux-gnu/libstdc++.so.6+0xdc328) (BuildId: e37fe1a879783838de78cbc8c80621fa685d58a2)

SUMMARY: AddressSanitizer: heap-use-after-free (/home/*****/nav2_humble/install/nav2_planner/lib/nav2_planner/planner_server+0x46813) (BuildId: 0d01382f47fffafcf72baea8200635e7f56bf31c) in __interceptor_memcpy
Shadow bytes around the buggy address:
  0x0c2a8000f670: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2a8000f680: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2a8000f690: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2a8000f6a0: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2a8000f6b0: fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa
=>0x0c2a8000f6c0: fd fd fd fd[fd]fd fd fd fd fd fd fd fd fd fd fd
  0x0c2a8000f6d0: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2a8000f6e0: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2a8000f6f0: fd fd fd fd fd fd fd fd fd fd fa fa fa fa fa fa
  0x0c2a8000f700: fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa
  0x0c2a8000f710: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
Shadow byte legend (one shadow byte represents 8 application bytes):
  Addressable:           00
  Partially addressable: 01 02 03 04 05 06 07 
  Heap left redzone:       fa
  Freed heap region:       fd
  Stack left redzone:      f1
  Stack mid redzone:       f2
  Stack right redzone:     f3
  Stack after return:      f5
  Stack use after scope:   f8
  Global redzone:          f9
  Global init order:       f6
  Poisoned by user:        f7
  Container overflow:      fc
  Array cookie:            ac
  Intra object redzone:    bb
  ASan internal:           fe
  Left alloca redzone:     ca
  Right alloca redzone:    cb

Additional information


It's a shutdown-issue

First, based on my execution logs, I can confirm this is a shutdown issue.

It is caused by the dyn_param_handler_ in the inflation_layer_ not being actively closed.
  1. The callback function InflationLayer::dynamicParametersCallback() that triggers the bug is executed by the dynamic_handler_ of inflation_layer_:

https://github.com/ros-navigation/navigation2/blob/a6b3de13f3c26f9df43ae45065c6a9a48053cccb/nav2_costmap_2d/plugins/inflation_layer.cpp#L105-L109

  1. Although there is release behavior for the dyn_param_handler_ in the destructor of InflationLayer, but it can't shutdown the callback thread of this handler.

Such conclusion has been proved by the experiment described in another issue #4496

  1. so that the thread of this handler may keep executing after the on_cleanup() of costmap_ros_

https://github.com/ros-navigation/navigation2/blob/9fbae3e66ecc3b7315ca7cbb070468a564f5e111/nav2_costmap_2d/plugins/inflation_layer.cpp#L79-L83

  1. During the on_cleanup() process of the costmap_ros_ node, inflation_layer_ is released:

https://github.com/ros-navigation/navigation2/blob/9fbae3e66ecc3b7315ca7cbb070468a564f5e111/nav2_costmap_2d/src/costmap_2d_ros.cpp#L364

however, if here's a callback task being executed by dyn_param_handler_, it would access the released resource in inflation_layer_, and UAF-bug occurs.

suggestion

Similarly, perhaps we need to update the way to completely shutdown dyn_param_handler_ of inflation_layer_?

SteveMacenski commented 6 days ago

See https://github.com/ros-navigation/navigation2/issues/4496#issuecomment-2192172525