Skip to content
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

UAF bug caused by laser_callback() #694

Open
GoesM opened this issue Apr 27, 2024 · 4 comments
Open

UAF bug caused by laser_callback() #694

GoesM opened this issue Apr 27, 2024 · 4 comments

Comments

@GoesM
Copy link

GoesM commented Apr 27, 2024

Required Info:

  • Operating System:
    • Ubuntu 22.04
  • Installation type:
    • source
  • ROS Version
    • ROS2-humble
  • Version or commit hash:
    • the latest
  • Laser unit:
    • defaulted

Steps to reproduce issue

I use slam-toolbox (async) by following command :

#!/bin/bash
export ASAN_OPTIONS=halt_on_error=0:new_delete_type_mismatch=0:detect_leaks=0:log_path=asan
source install/setup.bash
ros2 launch slam_toolbox online_async_launch.py

Running Slam-Toolbox within AddressSanitizer , I always faced to such UAF report during shutdown-period

Expected behavior

No UAF occurs

Actual behavior

we could always face to an ASAN-report about UAF bug as following:

=================================================================
==18319==ERROR: AddressSanitizer: heap-use-after-free on address 0x6060000736b8 at pc 0x7605a1e5f0d5 bp 0x76058f4c8340 sp 0x76058f4c8338
READ of size 8 at 0x6060000736b8 thread T20
    #0 0x7605a1e5f0d4 in std::_Rb_tree<karto::Name, std::pair<karto::Name const, karto::Sensor*>, std::_Select1st<std::pair<karto::Name const, karto::Sensor*> >, std::less<karto::Name>, std::allocator<std::pair<karto::Name const, karto::Sensor*> > >::find(karto::Name const&) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x65f0d4) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #1 0x7605a1e5ec16 in karto::SensorManager::GetSensorByName(karto::Name const&) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x65ec16) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #2 0x76059d6a9d28 in karto::GridIndexLookup<unsigned char>::ComputeOffsets(karto::LocalizedRangeScan*, double, double, double) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libkartoSlamToolbox.so+0x4a9d28) (BuildId: 438116af7e8121c8d8c716f02dee888c7979effe)
    #3 0x76059d65afb3 in karto::ScanMatcher::CorrelateScan(karto::LocalizedRangeScan*, karto::Pose2 const&, karto::Vector2<double> const&, karto::Vector2<double> const&, double, double, bool, karto::Pose2&, karto::Matrix3&, bool) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libkartoSlamToolbox.so+0x45afb3) (BuildId: 438116af7e8121c8d8c716f02dee888c7979effe)
    #4 0x76059d6ad3bf in double karto::ScanMatcher::MatchScan<std::vector<karto::LocalizedRangeScan*, std::allocator<karto::LocalizedRangeScan*> > >(karto::LocalizedRangeScan*, std::vector<karto::LocalizedRangeScan*, std::allocator<karto::LocalizedRangeScan*> > const&, karto::Pose2&, karto::Matrix3&, bool, bool) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libkartoSlamToolbox.so+0x4ad3bf) (BuildId: 438116af7e8121c8d8c716f02dee888c7979effe)
    #5 0x76059d6776c7 in karto::Mapper::Process(karto::LocalizedRangeScan*, karto::Matrix3*) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libkartoSlamToolbox.so+0x4776c7) (BuildId: 438116af7e8121c8d8c716f02dee888c7979effe)
    #6 0x7605a1dfa61a in slam_toolbox::SlamToolbox::addScan(karto::LaserRangeFinder*, std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&, karto::Pose2&) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x5fa61a) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #7 0x7605a2ab0c89 in slam_toolbox::AsynchronousSlamToolbox::laserCallback(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libasync_slam_toolbox.so+0xb3c89) (BuildId: ab3d6662343414a1ceb1f167a59faeabcec8089b)
    #8 0x7605a200c7b1 in void std::__invoke_impl<void, void (slam_toolbox::SlamToolbox::*&)(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>), slam_toolbox::SlamToolbox*&, std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&>(std::__invoke_memfun_deref, void (slam_toolbox::SlamToolbox::*&)(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>), slam_toolbox::SlamToolbox*&, std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x80c7b1) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #9 0x7605a200bed2 in message_filters::CallbackHelper1T<std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&, sensor_msgs::msg::LaserScan_<std::allocator<void> > >::call(message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&, bool) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x80bed2) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #10 0x7605a1fa434b 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/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x7a434b) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #11 0x7605a2003cba in tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>::transformReadyCallback(tf2_ros::TransformStampedFuture const&, unsigned long) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x803cba) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #12 0x7605a20083ce 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/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x8083ce) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #13 0x7605a2953e8d  (/opt/ros/humble/lib/libtf2_ros.so+0x4fe8d) (BuildId: dceacb25e05c8a82678784802b23fb16ba98d172)
    #14 0x76059f94a65e in tf2::BufferCore::testTransformableRequests() (/opt/ros/humble/lib/libtf2.so+0x1065e) (BuildId: 5677f8e557cfe0980662adcc0a17f03987f8b7f1)
    #15 0x76059f94d3fa 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+0x133fa) (BuildId: 5677f8e557cfe0980662adcc0a17f03987f8b7f1)
    #16 0x76059f94db29 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+0x13b29) (BuildId: 5677f8e557cfe0980662adcc0a17f03987f8b7f1)
    #17 0x7605a295cbb0 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: dceacb25e05c8a82678784802b23fb16ba98d172)
    #18 0x7605a159f1c9 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/librviz_default_plugins.so+0x79f1c9) (BuildId: 9da6509995fc2c916736fdd2d61b58739854b36d)
    #19 0x7605a15ae031 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/librviz_default_plugins.so+0x7ae031) (BuildId: 9da6509995fc2c916736fdd2d61b58739854b36d)
    #20 0x7605a15b4942  (/opt/ros/humble/lib/librviz_default_plugins.so+0x7b4942) (BuildId: 9da6509995fc2c916736fdd2d61b58739854b36d)
    #21 0x76059d0f07bb in rclcpp::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>) (/opt/ros/humble/lib/librclcpp.so+0xe77bb) (BuildId: 4cca8a387f3c93d38a0567a8efc7cba9106f5d9a)
    #22 0x76059d0f0fbe in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&) (/opt/ros/humble/lib/librclcpp.so+0xe7fbe) (BuildId: 4cca8a387f3c93d38a0567a8efc7cba9106f5d9a)
    #23 0x76059d0f88af in rclcpp::executors::SingleThreadedExecutor::spin() (/opt/ros/humble/lib/librclcpp.so+0xef8af) (BuildId: 4cca8a387f3c93d38a0567a8efc7cba9106f5d9a)
    #24 0x76059c4dc252  (/lib/x86_64-linux-gnu/libstdc++.so.6+0xdc252) (BuildId: e37fe1a879783838de78cbc8c80621fa685d58a2)
    #25 0x76059c094ac2 in start_thread nptl/./nptl/pthread_create.c:442:8
    #26 0x76059c12684f  misc/../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

0x6060000736b8 is located 24 bytes inside of 56-byte region [0x6060000736a0,0x6060000736d8)
freed by thread T0 here:
    #0 0x5a96964dfb5d in operator delete(void*) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/slam_toolbox/async_slam_toolbox_node+0x17fb5d) (BuildId: 25c5d29166b39455dc07d15264c602c467187757)
    #1 0x76059c045494 in __run_exit_handlers stdlib/./stdlib/exit.c:113:8

previously allocated by thread T20 here:
    #0 0x5a96964df2fd in operator new(unsigned long) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/slam_toolbox/async_slam_toolbox_node+0x17f2fd) (BuildId: 25c5d29166b39455dc07d15264c602c467187757)
    #1 0x76059d5c347b in karto::SensorManager::GetInstance() (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libkartoSlamToolbox.so+0x3c347b) (BuildId: 438116af7e8121c8d8c716f02dee888c7979effe)
    #2 0x7605a1df54af in slam_toolbox::SlamToolbox::getLaser(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x5f54af) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #3 0x7605a2ab0c35 in slam_toolbox::AsynchronousSlamToolbox::laserCallback(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libasync_slam_toolbox.so+0xb3c35) (BuildId: ab3d6662343414a1ceb1f167a59faeabcec8089b)
    #4 0x7605a200c7b1 in void std::__invoke_impl<void, void (slam_toolbox::SlamToolbox::*&)(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>), slam_toolbox::SlamToolbox*&, std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&>(std::__invoke_memfun_deref, void (slam_toolbox::SlamToolbox::*&)(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>), slam_toolbox::SlamToolbox*&, std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x80c7b1) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #5 0x7605a200bed2 in message_filters::CallbackHelper1T<std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&, sensor_msgs::msg::LaserScan_<std::allocator<void> > >::call(message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&, bool) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x80bed2) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #6 0x7605a1fa434b 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/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x7a434b) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #7 0x7605a2003cba in tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>::transformReadyCallback(tf2_ros::TransformStampedFuture const&, unsigned long) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x803cba) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #8 0x7605a20083ce 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/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x8083ce) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #9 0x7605a2953e8d  (/opt/ros/humble/lib/libtf2_ros.so+0x4fe8d) (BuildId: dceacb25e05c8a82678784802b23fb16ba98d172)
    #10 0x76058f4cd91f  (<unknown module>)

Thread T20 created by T0 here:
    #0 0x5a969648d9ac in __interceptor_pthread_create (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/slam_toolbox/async_slam_toolbox_node+0x12d9ac) (BuildId: 25c5d29166b39455dc07d15264c602c467187757)
    #1 0x76059c4dc328 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 0x7605a1e4165b in std::__detail::_MakeUniq<tf2_ros::TransformListener>::__single_object std::make_unique<tf2_ros::TransformListener, tf2_ros::Buffer&>(tf2_ros::Buffer&) (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x64165b) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #3 0x7605a1de5775 in slam_toolbox::SlamToolbox::configure() (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x5e5775) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1)
    #4 0x5a96964e2308 in main (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/slam_toolbox/async_slam_toolbox_node+0x182308) (BuildId: 25c5d29166b39455dc07d15264c602c467187757)
    #5 0x76059c029d8f in __libc_start_call_main csu/../sysdeps/nptl/libc_start_call_main.h:58:16

SUMMARY: AddressSanitizer: heap-use-after-free (/home/****/slam_toolbox_humble_fork/install/slam_toolbox/lib/libtoolbox_common.so+0x65f0d4) (BuildId: a965c84ea396d1a224891c94c234cfed672c2bd1) in std::_Rb_tree<karto::Name, std::pair<karto::Name const, karto::Sensor*>, std::_Select1st<std::pair<karto::Name const, karto::Sensor*> >, std::less<karto::Name>, std::allocator<std::pair<karto::Name const, karto::Sensor*> > >::find(karto::Name const&)
Shadow bytes around the buggy address:
  0x0c0c80006680: 00 00 00 00 00 00 00 fa fa fa fa fa 00 00 00 00
  0x0c0c80006690: 00 00 00 fa fa fa fa fa 00 00 00 00 00 00 00 fa
  0x0c0c800066a0: fa fa fa fa 00 00 00 00 00 00 00 fa fa fa fa fa
  0x0c0c800066b0: 00 00 00 00 00 00 00 fa fa fa fa fa fd fd fd fd
  0x0c0c800066c0: fd fd fd fd fa fa fa fa fd fd fd fd fd fd fd fd
=>0x0c0c800066d0: fa fa fa fa fd fd fd[fd]fd fd fd fa fa fa fa fa
  0x0c0c800066e0: fd fd fd fd fd fd fd fd fa fa fa fa 00 00 00 00
  0x0c0c800066f0: 00 00 00 fa fa fa fa fa 00 00 00 00 00 00 00 fa
  0x0c0c80006700: fa fa fa fa fd fd fd fd fd fd fd fd fa fa fa fa
  0x0c0c80006710: fd fd fd fd fd fd fd fd fa fa fa fa fd fd fd fd
  0x0c0c80006720: fd fd fd fd fa fa fa fa 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
==18319==ABORTING

Additional information

the function laserCallback() is bind to the scan_filter_sub_ and scan_filter_ as following:

scan_filter_sub_ =
std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>(
shared_from_this().get(), scan_topic_, rmw_qos_profile_sensor_data);
scan_filter_ =
std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
*scan_filter_sub_, *tf_, odom_frame_, scan_queue_size_, shared_from_this(),
tf2::durationFromSec(transform_timeout_.seconds()));
scan_filter_->registerCallback(
std::bind(&SlamToolbox::laserCallback, this, std::placeholders::_1));

but here's no reset() for such two pointer in the destructor

/*****************************************************************************/
SlamToolbox::~SlamToolbox()
/*****************************************************************************/
{
for (int i = 0; i != threads_.size(); i++) {
threads_[i]->join();
}
smapper_.reset();
dataset_.reset();
closure_assistant_.reset();
map_saver_.reset();
pose_helper_.reset();
laser_assistant_.reset();
scan_holder_.reset();
solver_.reset();
}

So that, the callback-function might be still working after the node is destructed and cause the UAF bug as a result.

@GoesM
Copy link
Author

GoesM commented Apr 27, 2024

well, it seems that such issue has been fixed in ros2 branch :

SlamToolbox::~SlamToolbox()
/*****************************************************************************/
{
for (int i = 0; i != threads_.size(); i++) {
threads_[i]->interrupt();
threads_[i]->join();
threads_[i].reset();
}
threads_.clear();
smapper_.reset();
dataset_.reset();
closure_assistant_.reset();
map_saver_.reset();
pose_helper_.reset();
laser_assistant_.reset();
scan_holder_.reset();
solver_.reset();
scan_filter_.reset();
scan_filter_sub_.reset();

but no such code to reset these pointers in both iron and humble branch.

@SteveMacenski
Copy link
Owner

Feel free to backport, happy to merge that for humble/iron

@GoesM
Copy link
Author

GoesM commented Jun 28, 2024

Shall I backport by cherry-pick ? 🤔 I think the past commit for this issue would change humble a lot:

de13553

@SteveMacenski
Copy link
Owner

I'd try cherry-pick, but if it looks too hard, I understand manual for this case.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants