Skip to content

[nav2_dwb_controller] Race Condition in KinematicsHandler Causing Heap-Use-After-Free #5706

@suifengersan123

Description

@suifengersan123

Bug report

Required Info:

  • Operating System:
    • ubuntu 20.04
  • ROS2 Version:
    • foxy
  • DDS implementation:
    • the defaulted

Steps to reproduce issue

1.Thread T17 (control thread) is calling getKinematics() to read kinematic parameters
2.Thread T0 (main thread) calls update_kinematics() in a parameter callback to update parameters
3.Thread T0 executes delete kinematics_.load() first, freeing the old memory
4.Thread T17 still holds the old pointer and attempts to dereference *kinematics_.load(), resulting in accessing freed memory (heap-use-after-free)

Expected behavior

no bug occured.

Actual behavior

the Asan report of this bug is as following:

==887786==ERROR: AddressSanitizer: heap-use-after-free on address 0x60c000213b80 at pc 0x0000005b078a bp 0x7fcdacc55b30 sp 0x7fcdacc552f8
READ of size 128 at 0x60c000213b80 thread T17
    #0 0x5b0789 in __asan_memcpy (/yzyproject/rofer/rofer/fuzz_manager/build/nav2_controller/controller_server+0x5b0789)
    #1 0x7fcdad74263c in dwb_plugins::KinematicsHandler::getKinematics() /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/kinematic_parameters.hpp:110:54
    #2 0x7fcdad83cf07 in dwb_plugins::XYThetaIterator::isValidSpeed(double, double, double) /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_dwb_controller/dwb_plugins/src/xy_theta_iterator.cpp:97:57
    #3 0x7fcdad83d25f in dwb_plugins::XYThetaIterator::isValidVelocity() /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_dwb_controller/dwb_plugins/src/xy_theta_iterator.cpp:115:10
    #4 0x7fcdad83cd69 in dwb_plugins::XYThetaIterator::iterateToValidVelocity() /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_dwb_controller/dwb_plugins/src/xy_theta_iterator.cpp:150:13
    #5 0x7fcdad83d450 in dwb_plugins::XYThetaIterator::nextTwist() /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_dwb_controller/dwb_plugins/src/xy_theta_iterator.cpp:132:3
    #6 0x7fcdad73d342 in dwb_plugins::StandardTrajectoryGenerator::nextTwist() /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp:116:30
    #7 0x7fcdadb4b8e7 in dwb_core::DWBLocalPlanner::coreScoringAlgorithm(geometry_msgs::msg::Pose2D_<std::allocator<void> > const&, nav_2d_msgs::msg::Twist2D_<std::allocator<void> >, std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation_<std::allocator<void> > >&) /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp:392:30
    #8 0x7fcdadb49d6d in dwb_core::DWBLocalPlanner::computeVelocityCommands(nav_2d_msgs::msg::Pose2DStamped_<std::allocator<void> > const&, nav_2d_msgs::msg::Twist2D_<std::allocator<void> > const&, std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation_<std::allocator<void> > >&) /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp:342:43
    #9 0x7fcdadb47ad5 in dwb_core::DWBLocalPlanner::computeVelocityCommands(geometry_msgs::msg::PoseStamped_<std::allocator<void> > const&, geometry_msgs::msg::Twist_<std::allocator<void> > const&) /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp:286:50
    #10 0x600286 in nav2_controller::ControllerServer::computeAndPublishVelocity() /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_controller/src/nav2_controller.cpp:363:40
    #11 0x5f6b79 in nav2_controller::ControllerServer::computeControl() /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_controller/src/nav2_controller.cpp:296:7


0x60c000213b80 is located 0 bytes inside of 128-byte region [0x60c000213b80,0x60c000213c00)
freed by thread T0 here:
    #0 0x5e130d in operator delete(void*) (/yzyproject/rofer/rofer/fuzz_manager/build/nav2_controller/controller_server+0x5e130d)
    #1 0x7fcdad767958 in dwb_plugins::KinematicsHandler::update_kinematics(dwb_plugins::KinematicParameters) /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_dwb_controller/dwb_plugins/src/kinematic_parameters.cpp:183:3
    #2 0x7fcdad767776 in dwb_plugins::KinematicsHandler::on_parameter_event_callback(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > >) /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_dwb_controller/dwb_plugins/src/kinematic_parameters.cpp:178:3

previously allocated by thread T0 here:
    #0 0x5e0aad in operator new(unsigned long) (/yzyproject/rofer/rofer/fuzz_manager/build/nav2_controller/controller_server+0x5e0aad)
    #1 0x7fcdad76796c in dwb_plugins::KinematicsHandler::update_kinematics(dwb_plugins::KinematicParameters) /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_dwb_controller/dwb_plugins/src/kinematic_parameters.cpp:184:21
    #2 0x7fcdad767776 in dwb_plugins::KinematicsHandler::on_parameter_event_callback(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > >) /yzyproject/rofer/rofer/fuzz_manager/src/navigation2/nav2_dwb_controller/dwb_plugins/src/kinematic_parameters.cpp:178:3

Thread T17 created by T11 here:
    #0 0x59c0ea in pthread_create (/yzyproject/rofer/rofer/fuzz_manager/build/nav2_controller/controller_server+0x59c0ea)
    #1 0x7fcdbef0d0c9 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+0xd70c9)
    #2 0x84a3f3 in std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath, rclcpp::Node>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void>::_Async_state_impl(std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath, rclcpp::Node>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >&&) /usr/bin/../lib/gcc/x86_64-linux-gnu/10/../../../../include/c++/10/future:1703:14


Additional information

This bug is a critical safety issue for production deployments
The race condition can cause unpredictable crashes during normal operation
Similar patterns may exist in other parts of the codebase that use std::atomic with raw pointers

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