ros / geometry2

A set of ROS packages for keeping track of coordinate transforms.
189 stars 273 forks source link

[bug] [tf2_ros::Message_filter] `transformReadyCallback()` continue to execute after the destruction of `Message_filter` #565

Open GoesM opened 3 weeks ago

GoesM commented 3 weeks ago

Bug Report

Operating System:

ROS2 Version:

Based on the issue in the tf2_ros::Message_filter in the ros2-navigation2 stack: https://github.com/ros-navigation/navigation2/issues/4414

I have identified a potential bug in the tf2_ros::Message_filter class. The relevant function is defined here:

https://github.com/ros/geometry2/blob/6df9e94363061a24ba890a6ff29771a96b0d756b/tf2_ros/include/tf2_ros/message_filter.h#L459

The function transformable, known as transformReadyCallback() in the ROS2 Humble version, may continue to execute after the Message_filter object has been destructed. This could lead to a potential Use-After-Free (UAF) bug if we attempt to release the message filter pointer, resulting in a crash of the ROS2 program.

Additonal Information:

the Asan-report is as following when the UAF bug occurs:

=================================================================
==76105==ERROR: AddressSanitizer: heap-use-after-free on address 0x6170000a5c90 at pc 0x79ff0b559bba bp 0x79ff01bf6ab0 sp 0x79ff01bf6aa8
READ of size 8 at 0x6170000a5c90 thread T12
    #0 0x79ff0b559bb9 in tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>::transformReadyCallback(tf2_ros::TransformStampedFuture const&, unsigned long) (/home/goes/ROS_Workstation/humble_navigation2/install/nav2_amcl/lib/libamcl_core.so+0x559bb9) (BuildId: f870739ccc7779266347919193e71b4cf78860c9)
    #1 0x79ff0b55db4e 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/goes/ROS_Workstation/humble_navigation2/install/nav2_amcl/lib/libamcl_core.so+0x55db4e) (BuildId: f870739ccc7779266347919193e71b4cf78860c9)
    #2 0x79ff0c85130b in std::_Function_handler<void (unsigned long const&), std::_Bind<void (tf2_ros::Buffer::* (tf2_ros::Buffer*, std::_Placeholder<1>, std::shared_ptr<std::promise<geometry_msgs::msg::TransformStamped_<std::allocator<void> > > >, tf2_ros::TransformStampedFuture, std::function<void (tf2_ros::TransformStampedFuture const&)>))(unsigned long const&, std::shared_ptr<std::promise<geometry_msgs::msg::TransformStamped_<std::allocator<void> > > >, tf2_ros::TransformStampedFuture, std::function<void (tf2_ros::TransformStampedFuture const&)>)> >::_M_invoke(std::_Any_data const&, unsigned long const&) (/opt/ros/humble/lib/libtf2_ros.so+0x5130b) (BuildId: 4ee0e77870b47da6b41a530a2970e853eafce773)
    #3 0x79ff0c84eb35 in std::_Function_handler<void (), std::_Bind<void (tf2_ros::CreateTimerROS::* (tf2_ros::CreateTimerROS*, unsigned long, std::function<void (unsigned long const&)>))(unsigned long const&, std::function<void (unsigned long const&)>)> >::_M_invoke(std::_Any_data const&) (/opt/ros/humble/lib/libtf2_ros.so+0x4eb35) (BuildId: 4ee0e77870b47da6b41a530a2970e853eafce773)
    #4 0x79ff0c84dd97  (/opt/ros/humble/lib/libtf2_ros.so+0x4dd97) (BuildId: 4ee0e77870b47da6b41a530a2970e853eafce773)
    #5 0x79ff0c407030 in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&) (/opt/ros/humble/lib/librclcpp.so+0xe7030) (BuildId: bd69d2a87470f6b9fdc0534ef05dc334083a0b6c)
    #6 0x79ff0c40e97f in rclcpp::executors::SingleThreadedExecutor::spin() (/opt/ros/humble/lib/librclcpp.so+0xee97f) (BuildId: bd69d2a87470f6b9fdc0534ef05dc334083a0b6c)
    #7 0x79ff0aadc252  (/lib/x86_64-linux-gnu/libstdc++.so.6+0xdc252) (BuildId: e37fe1a879783838de78cbc8c80621fa685d58a2)
    #8 0x79ff0a694ac2 in start_thread nptl/./nptl/pthread_create.c:442:8
    #9 0x79ff0a72684f  misc/../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

0x6170000a5c90 is located 656 bytes inside of 704-byte region [0x6170000a5a00,0x6170000a5cc0)
freed by thread T0 here:
    #0 0x5f969785c98d in operator delete(void*) (/home/goes/ROS_Workstation/humble_navigation2/install/nav2_amcl/lib/nav2_amcl/amcl+0xe998d) (BuildId: 8210e9eb79b766128e96cd73bfae12d14cdc1560)
    #1 0x79ff0b3ec48c 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/goes/ROS_Workstation/humble_navigation2/install/nav2_amcl/lib/libamcl_core.so+0x3ec48c) (BuildId: f870739ccc7779266347919193e71b4cf78860c9)
    #2 0x79ff0b45a3ce in std::__invoke_result<rcl_interfaces::msg::SetParametersResult_<std::allocator<void> > (nav2_amcl::AmclNode::*&)(std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> >), nav2_amcl::AmclNode*&, std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> > const&>::type std::__invoke<rcl_interfaces::msg::SetParametersResult_<std::allocator<void> > (nav2_amcl::AmclNode::*&)(std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> >), nav2_amcl::AmclNode*&, std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> > const&>(rcl_interfaces::msg::SetParametersResult_<std::allocator<void> > (nav2_amcl::AmclNode::*&)(std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> >), nav2_amcl::AmclNode*&, std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> > const&) (/home/goes/ROS_Workstation/humble_navigation2/install/nav2_amcl/lib/libamcl_core.so+0x45a3ce) (BuildId: f870739ccc7779266347919193e71b4cf78860c9)
    #3 0x79ff0b45a231 in rcl_interfaces::msg::SetParametersResult_<std::allocator<void> > std::__invoke_impl<rcl_interfaces::msg::SetParametersResult_<std::allocator<void> >, std::_Bind<rcl_interfaces::msg::SetParametersResult_<std::allocator<void> > (nav2_amcl::AmclNode::* (nav2_amcl::AmclNode*, std::_Placeholder<1>))(std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> >)>&, std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> > const&>(std::__invoke_other, std::_Bind<rcl_interfaces::msg::SetParametersResult_<std::allocator<void> > (nav2_amcl::AmclNode::* (nav2_amcl::AmclNode*, std::_Placeholder<1>))(std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> >)>&, std::vector<rclcpp::Parameter, std::allocator<rclcpp::Parameter> > const&) (/home/goes/ROS_Workstation/humble_navigation2/install/nav2_amcl/lib/libamcl_core.so+0x45a231) (BuildId: f870739ccc7779266347919193e71b4cf78860c9)

previously allocated by thread T0 here:
    #0 0x5f969785c12d in operator new(unsigned long) (/home/goes/ROS_Workstation/humble_navigation2/install/nav2_amcl/lib/nav2_amcl/amcl+0xe912d) (BuildId: 8210e9eb79b766128e96cd73bfae12d14cdc1560)
    #1 0x79ff0b3e42df 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/goes/ROS_Workstation/humble_navigation2/install/nav2_amcl/lib/libamcl_core.so+0x3e42df) (BuildId: f870739ccc7779266347919193e71b4cf78860c9)

Thread T12 created by T0 here:
    #0 0x5f969780a7dc in __interceptor_pthread_create (/home/goes/ROS_Workstation/humble_navigation2/install/nav2_amcl/lib/nav2_amcl/amcl+0x977dc) (BuildId: 8210e9eb79b766128e96cd73bfae12d14cdc1560)
    #1 0x79ff0aadc328 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 0x79ff0b3772f0 in nav2_amcl::AmclNode::on_configure(rclcpp_lifecycle::State const&) (/home/goes/ROS_Workstation/humble_navigation2/install/nav2_amcl/lib/libamcl_core.so+0x3772f0) (BuildId: f870739ccc7779266347919193e71b4cf78860c9)
    #3 0x79ff0c3038ec  (/opt/ros/humble/lib/librclcpp_lifecycle.so+0x288ec) (BuildId: 97f6428dc1ee45fd402b522b3b8e6b4fcfeabe76)

SUMMARY: AddressSanitizer: heap-use-after-free (/home/goes/ROS_Workstation/humble_navigation2/install/nav2_amcl/lib/libamcl_core.so+0x559bb9) (BuildId: f870739ccc7779266347919193e71b4cf78860c9) in tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>::transformReadyCallback(tf2_ros::TransformStampedFuture const&, unsigned long)
Shadow bytes around the buggy address:
  0x0c2e8000cb40: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2e8000cb50: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2e8000cb60: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2e8000cb70: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
  0x0c2e8000cb80: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd
=>0x0c2e8000cb90: fd fd[fd]fd fd fd fd fd fa fa fa fa fa fa fa fa
  0x0c2e8000cba0: fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa
  0x0c2e8000cbb0: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
  0x0c2e8000cbc0: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
  0x0c2e8000cbd0: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
  0x0c2e8000cbe0: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
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
==76105==ABORTING

in this report, let's notice the following lines:

  1. the free operation of this UAF bug is called by the destructor of message_filter
    freed by thread T0 here:
    #0 0x5f969785c98d in operator delete(void*) (/home/goes/ROS_Workstation/humble_navigation2/install/nav2_amcl/lib/nav2_amcl/amcl+0xe998d) (BuildId: 8210e9eb79b766128e96cd73bfae12d14cdc1560)
    #1 0x79ff0b3ec48c 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/goes/ROS_Workstation/humble_navigation2/install/nav2_amcl/lib/libamcl_core.so+0x3ec48c) (BuildId: f870739ccc7779266347919193e71b4cf78860c9)
  2. the use operation of this UAF bug is called by the function transformReadyCallback
    READ of size 8 at 0x6170000a5c90 thread T12
    #0 0x79ff0b559bb9 in tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>::transformReadyCallback(tf2_ros::TransformStampedFuture const&, unsigned long) (/home/goes/ROS_Workstation/humble_navigation2/install/nav2_amcl/lib/libamcl_core.so+0x559bb9) (BuildId: f870739ccc7779266347919193e71b4cf78860c9)

SO

it proves that function transformReadyCallback() continue to execute after the destruction of Message_filter.

suggestion

Should we add a mechanism to protect against such bugs? For instance, adding a thread shutdown at the beginning of the destructor might help mitigate this issue (I think)