Skip to content

Inappropriate pointer free order in amcl may trigger use-after-free bug #4068

@GoesM

Description

@GoesM

Bug report

Required Info:

  • Operating System:
    • Ubuntu22.04
  • ROS2 Version:
    • humble
  • Version or commit hash:
    • the latest
  • DDS implementation:
    • defaulted

Steps to reproduce issue

During my very ordinary use, an unexpected situation was triggered.

I launched the navigation2 normally, 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

Actual behavior

During my usage, the ASAN report a use-after-free bug to me, as following:

=================================================================
==1627006==ERROR: AddressSanitizer: heap-use-after-free on address 0x61700009e6b8 at pc 0x7ff9b0cf3539 bp 0x7ff9a7db9230 sp 0x7ff9a7db9228
READ of size 8 at 0x61700009e6b8 thread T11
    #0 0x7ff9b0cf3538 in message_filters::Signal1<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::call(message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x4f3538) (BuildId: 427f1d8584980a1646cc60c7a8e1d2739c4c5ca0)
    #1 0x7ff9b0d38790 in tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>::transformReadyCallback(tf2_ros::TransformStampedFuture const&, unsigned long) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x538790) (BuildId: 427f1d8584980a1646cc60c7a8e1d2739c4c5ca0)
    #2 0x7ff9b0d3cc6e in std::_Function_handler<void (tf2_ros::TransformStampedFuture const&), std::_Bind<void (tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>::* (tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>*, std::_Placeholder<1>, unsigned long))(tf2_ros::TransformStampedFuture const&, unsigned long)> >::_M_invoke(std::_Any_data const&, tf2_ros::TransformStampedFuture const&) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x53cc6e) (BuildId: 427f1d8584980a1646cc60c7a8e1d2739c4c5ca0)
    #3 0x7ff9b2091e8d  (/opt/ros/humble/lib/libtf2_ros.so+0x4fe8d) (BuildId: dc6ad94876402bc27e6b8ba01e2b78c714ce71a6)
    #4 0x7ff9b200d5fe in tf2::BufferCore::testTransformableRequests() (/opt/ros/humble/lib/libtf2.so+0x105fe) (BuildId: 3860beff8328ff840e10c2fded56403848cba9a0)
    #5 0x7ff9b2010321 in tf2::BufferCore::setTransformImpl(tf2::Transform const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, std::chrono::time_point<std::chrono::_V2::system_clock, std::chrono::duration<long, std::ratio<1l, 1000000000l> > >, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, bool) (/opt/ros/humble/lib/libtf2.so+0x13321) (BuildId: 3860beff8328ff840e10c2fded56403848cba9a0)
    #6 0x7ff9b2010b69 in tf2::BufferCore::setTransform(geometry_msgs::msg::TransformStamped_<std::allocator<void> > const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, bool) (/opt/ros/humble/lib/libtf2.so+0x13b69) (BuildId: 3860beff8328ff840e10c2fded56403848cba9a0)
    #7 0x7ff9b209abb0 in tf2_ros::TransformListener::subscription_callback(std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > const>, bool) (/opt/ros/humble/lib/libtf2_ros.so+0x58bb0) (BuildId: dc6ad94876402bc27e6b8ba01e2b78c714ce71a6)
    #8 0x7ff9b209aa89 in std::_Function_handler<void (std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > const>), std::_Bind<void (tf2_ros::TransformListener::* (tf2_ros::TransformListener*, std::_Placeholder<1>, bool))(std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > const>, bool)> >::_M_invoke(std::_Any_data const&, std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > const>&&) (/opt/ros/humble/lib/libtf2_ros.so+0x58a89) (BuildId: dc6ad94876402bc27e6b8ba01e2b78c714ce71a6)
    #9 0x7ff9b20af601 in std::__detail::__variant::__gen_vtable_impl<std::__detail::__variant::_Multi_array<std::__detail::__variant::__deduce_visit_result<void> (*)(rclcpp::AnySubscriptionCallback<tf2_msgs::msg::TFMessage_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > >, rclcpp::MessageInfo const&)::'lambda'(auto&&)&&, std::variant<std::function<void (tf2_msgs::msg::TFMessage_<std::allocator<void> > const&)>, std::function<void (tf2_msgs::msg::TFMessage_<std::allocator<void> > const&, rclcpp::MessageInfo const&)>, std::function<void (rclcpp::SerializedMessage const&)>, std::function<void (rclcpp::SerializedMessage const&, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> >, std::default_delete<tf2_msgs::msg::TFMessage_<std::allocator<void> > > >)>, std::function<void (std::unique_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> >, std::default_delete<tf2_msgs::msg::TFMessage_<std::allocator<void> > > >, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > const>)>, std::function<void (std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > const> const&)>, std::function<void (std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > >)>, std::function<void (std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>, rclcpp::MessageInfo const&)> >&)>, std::integer_sequence<unsigned long, 8ul> >::__visit_invoke(rclcpp::AnySubscriptionCallback<tf2_msgs::msg::TFMessage_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > >, rclcpp::MessageInfo const&)::'lambda'(auto&&)&&, std::variant<std::function<void (tf2_msgs::msg::TFMessage_<std::allocator<void> > const&)>, std::function<void (tf2_msgs::msg::TFMessage_<std::allocator<void> > const&, rclcpp::MessageInfo const&)>, std::function<void (rclcpp::SerializedMessage const&)>, std::function<void (rclcpp::SerializedMessage const&, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> >, std::default_delete<tf2_msgs::msg::TFMessage_<std::allocator<void> > > >)>, std::function<void (std::unique_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> >, std::default_delete<tf2_msgs::msg::TFMessage_<std::allocator<void> > > >, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > const>)>, std::function<void (std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > const> const&)>, std::function<void (std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > >)>, std::function<void (std::shared_ptr<tf2_msgs::msg::TFMessage_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>, rclcpp::MessageInfo const&)> >&) (/opt/ros/humble/lib/libtf2_ros.so+0x6d601) (BuildId: dc6ad94876402bc27e6b8ba01e2b78c714ce71a6)
    #10 0x7ff9b20ae93e  (/opt/ros/humble/lib/libtf2_ros.so+0x6c93e) (BuildId: dc6ad94876402bc27e6b8ba01e2b78c714ce71a6)
    #11 0x7ff9b1c4c7ab in rclcpp::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>) (/opt/ros/humble/lib/librclcpp.so+0xe77ab) (BuildId: 79589eb7552577357ad155ddcc914b38e18f0811)
    #12 0x7ff9b1c4cfae in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&) (/opt/ros/humble/lib/librclcpp.so+0xe7fae) (BuildId: 79589eb7552577357ad155ddcc914b38e18f0811)
    #13 0x7ff9b1c5489f in rclcpp::executors::SingleThreadedExecutor::spin() (/opt/ros/humble/lib/librclcpp.so+0xef89f) (BuildId: 79589eb7552577357ad155ddcc914b38e18f0811)
    #14 0x7ff9b02dc252  (/lib/x86_64-linux-gnu/libstdc++.so.6+0xdc252) (BuildId: e37fe1a879783838de78cbc8c80621fa685d58a2)
    #15 0x7ff9afe94ac2 in start_thread nptl/./nptl/pthread_create.c:442:8
    #16 0x7ff9aff26a3f  misc/../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

0x61700009e6b8 is located 56 bytes inside of 704-byte region [0x61700009e680,0x61700009e940)
freed by thread T1 here:
    #0 0x55697b23a98d in operator delete(void*) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/nav2_amcl/amcl+0xe998d) (BuildId: 4e1ce3fcf62a6d0e51a98b07383906fe5ca789ec)
    #1 0x7ff9b0bcbabc in std::__uniq_ptr_impl<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>, std::default_delete<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer> > >::reset(tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>*) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x3cbabc) (BuildId: 427f1d8584980a1646cc60c7a8e1d2739c4c5ca0)
    #2 0x7ff9b1b48b8c  (/opt/ros/humble/lib/librclcpp_lifecycle.so+0x28b8c) (BuildId: ccb1b39efb3eaee63de490386a8850a5752f307d)

previously allocated by thread T0 here:
    #0 0x55697b23a12d in operator new(unsigned long) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/nav2_amcl/amcl+0xe912d) (BuildId: 4e1ce3fcf62a6d0e51a98b07383906fe5ca789ec)
    #1 0x7ff9b0bc407f in std::_MakeUniq<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer> >::__single_object std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>, message_filters::Subscriber<sensor_msgs::msg::LaserScan_<std::allocator<void> >, rclcpp_lifecycle::LifecycleNode>&, tf2_ros::Buffer&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >&, int, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::chrono::duration<long, std::ratio<1l, 1000000000l> >&>(message_filters::Subscriber<sensor_msgs::msg::LaserScan_<std::allocator<void> >, rclcpp_lifecycle::LifecycleNode>&, tf2_ros::Buffer&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >&, int&&, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>&&, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>&&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >&) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x3c407f) (BuildId: 427f1d8584980a1646cc60c7a8e1d2739c4c5ca0)

Thread T11 created by T0 here:
    #0 0x55697b1e87dc in __interceptor_pthread_create (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/nav2_amcl/amcl+0x977dc) (BuildId: 4e1ce3fcf62a6d0e51a98b07383906fe5ca789ec)
    #1 0x7ff9b02dc328 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)
    #2 0x7ff9b0cd3359 in std::_Sp_counted_ptr_inplace<tf2_ros::TransformListener, std::allocator<tf2_ros::TransformListener>, (__gnu_cxx::_Lock_policy)2>::_Sp_counted_ptr_inplace<tf2_ros::Buffer&>(std::allocator<tf2_ros::TransformListener>, tf2_ros::Buffer&) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x4d3359) (BuildId: 427f1d8584980a1646cc60c7a8e1d2739c4c5ca0)
    #3 0x7ff9b0b60ad2 in nav2_amcl::AmclNode::initTransforms() (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x360ad2) (BuildId: 427f1d8584980a1646cc60c7a8e1d2739c4c5ca0)
    #4 0x7ff9b0b59aa9 in nav2_amcl::AmclNode::on_configure(rclcpp_lifecycle::State const&) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x359aa9) (BuildId: 427f1d8584980a1646cc60c7a8e1d2739c4c5ca0)
    #5 0x7ff9b1b48b8c  (/opt/ros/humble/lib/librclcpp_lifecycle.so+0x28b8c) (BuildId: ccb1b39efb3eaee63de490386a8850a5752f307d)

Thread T1 created by T0 here:
    #0 0x55697b1e87dc in __interceptor_pthread_create (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/nav2_amcl/amcl+0x977dc) (BuildId: 4e1ce3fcf62a6d0e51a98b07383906fe5ca789ec)
    #1 0x7ff9b02dc328 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/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x4f3538) (BuildId: 427f1d8584980a1646cc60c7a8e1d2739c4c5ca0) in message_filters::Signal1<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::call(message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&)
Shadow bytes around the buggy address:
  0x0c2e8000bc80: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2e8000bc90: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2e8000bca0: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2e8000bcb0: fd fd fd fd fd fa fa fa fa fa fa fa fa fa fa fa
  0x0c2e8000bcc0: fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa
=>0x0c2e8000bcd0: fd fd fd fd fd fd fd[fd]fd fd fd fd fd fd fd fd
  0x0c2e8000bce0: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2e8000bcf0: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2e8000bd00: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2e8000bd10: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2e8000bd20: fd fd fd fd fd fd fd fd fa fa fa fa fa fa fa fa
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
==1627006==ABORTING

Additional information


It seems like a shutdown-issue, and caused by the inappropriate Ptr release order

focus on code lines in AmclNode::on_cleanup() : amcl_node.cpp#L331-L344, the laser_scan_filter_.reset() is done before tf_listener_.reset().

SO, If there happens to be a message comming within the interval between two pointers being reset, tf_listener_ would be in callback-work. And during the work, it would access the laser_scan_filter_ to filter compliance messages, while the laser_scan_filter_ has been freed. Finally, it would trigger an error similar to the UAF we reported this time.

a suggestion that may be helpful:

  • shall we place tf_listener_.reset() before laser_scan_filter_.reset() ?

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions