Skip to content

unclosed map_sub_ of nav2_amcl may cause use-after-free and NullPtr-accessed bug #4078

@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 one of my previous usage in the past, an unexpected situation occurred.

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 

I am curious about how navigation2's response to received map-messages after startup, so I send it map messages at intervals.

Then, after a period, I finally sent Ctrl+C to shutdown navigation2, which is before stop the map-msg sending.

Finally, I accidentally discovered an ASAN report file in my execution environment.

Expected behavior

Actual behavior

The ASAN reporting a use-after-free bug to me, as following:

================================================================= ==63495==ERROR: AddressSanitizer: heap-use-after-free on address 0x7f846c10e750 at pc 0x7f8475f86273 bp 0x7ffdfad859d0 sp 0x7ffdfad859c8 READ of size 4 at 0x7f846c10e750 thread T0 #0 0x7f8475f86272 in nav2_amcl::AmclNode::createFreeSpaceVector() (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x386272) (BuildId: cd5c2976e01c9da15407c21629e0d7116e9e5b20) #1 0x7f8475f84feb in nav2_amcl::AmclNode::handleMapMessage(nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x384feb) (BuildId: cd5c2976e01c9da15407c21629e0d7116e9e5b20) #2 0x7f8475f844b7 in nav2_amcl::AmclNode::mapReceived(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x3844b7) (BuildId: cd5c2976e01c9da15407c21629e0d7116e9e5b20) #3 0x7f847607ea7e in void std::__invoke_impl<void, void (nav2_amcl::AmclNode::*&)(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >), nav2_amcl::AmclNode*&, std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >(std::__invoke_memfun_deref, void (nav2_amcl::AmclNode::*&)(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >), nav2_amcl::AmclNode*&, std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >&&) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x47ea7e) (BuildId: cd5c2976e01c9da15407c21629e0d7116e9e5b20) #4 0x7f84760c79f2 in auto rclcpp::AnySubscriptionCallback<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, rclcpp::MessageInfo const&)::'lambda'(auto&&)::operator()<std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>&>(auto&&) const (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x4c79f2) (BuildId: cd5c2976e01c9da15407c21629e0d7116e9e5b20) #5 0x7f84760c48db in rclcpp::AnySubscriptionCallback<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, rclcpp::MessageInfo const&) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x4c48db) (BuildId: cd5c2976e01c9da15407c21629e0d7116e9e5b20) #6 0x7f847608acec in rclcpp::Subscription<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::allocator<void>, nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::allocator<void> > >::handle_message(std::shared_ptr<void>&, rclcpp::MessageInfo const&) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x48acec) (BuildId: cd5c2976e01c9da15407c21629e0d7116e9e5b20) #7 0x7f8476fb07ab in rclcpp::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>) (/opt/ros/humble/lib/librclcpp.so+0xe77ab) (BuildId: 79589eb7552577357ad155ddcc914b38e18f0811) #8 0x7f8476fb0fae in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&) (/opt/ros/humble/lib/librclcpp.so+0xe7fae) (BuildId: 79589eb7552577357ad155ddcc914b38e18f0811) #9 0x7f8476fb889f in rclcpp::executors::SingleThreadedExecutor::spin() (/opt/ros/humble/lib/librclcpp.so+0xef89f) (BuildId: 79589eb7552577357ad155ddcc914b38e18f0811) #10 0x7f8476fb8ab4 in rclcpp::spin(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>) (/opt/ros/humble/lib/librclcpp.so+0xefab4) (BuildId: 79589eb7552577357ad155ddcc914b38e18f0811) #11 0x560f55acd975 in main (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/nav2_amcl/amcl+0xeb975) (BuildId: 4870a9636ab41ccba29820da43686a7014f94dd5) #12 0x7f8475229d8f in __libc_start_call_main csu/../sysdeps/nptl/libc_start_call_main.h:58:16 #13 0x7f8475229e3f in __libc_start_main csu/../csu/libc-start.c:392:3 #14 0x560f55a0d514 in _start (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/nav2_amcl/amcl+0x2b514) (BuildId: 4870a9636ab41ccba29820da43686a7014f94dd5) 0x7f846c10e750 is located 3920 bytes inside of 2359296-byte region [0x7f846c10d800,0x7f846c34d800) freed by thread T1 here: #0 0x560f55a900b2 in free (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/nav2_amcl/amcl+0xae0b2) (BuildId: 4870a9636ab41ccba29820da43686a7014f94dd5) #1 0x7f847596d8f8 in map_free (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libmap_lib.so+0x68f8) (BuildId: de1c15a5d90034069bb9b3e8003b71f3c358c504) #2 0x7f8476eacb8c (/opt/ros/humble/lib/librclcpp_lifecycle.so+0x28b8c) (BuildId: ccb1b39efb3eaee63de490386a8850a5752f307d) previously allocated by thread T0 here: #0 0x560f55a9035e in malloc (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/nav2_amcl/amcl+0xae35e) (BuildId: 4870a9636ab41ccba29820da43686a7014f94dd5) #1 0x7f8475f85a5b in nav2_amcl::AmclNode::convertMap(nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&) (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/libamcl_core.so+0x385a5b) (BuildId: cd5c2976e01c9da15407c21629e0d7116e9e5b20) Thread T1 created by T0 here: #0 0x560f55a797dc in __interceptor_pthread_create (/home/****/ROS_ws/nav2/install/nav2_amcl/lib/nav2_amcl/amcl+0x977dc) (BuildId: 4870a9636ab41ccba29820da43686a7014f94dd5) #1 0x7f84756dc328 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+0x386272) (BuildId: cd5c2976e01c9da15407c21629e0d7116e9e5b20) in nav2_amcl::AmclNode::createFreeSpaceVector() Shadow bytes around the buggy address: 0x0ff10d819c90: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd 0x0ff10d819ca0: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd 0x0ff10d819cb0: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd 0x0ff10d819cc0: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd 0x0ff10d819cd0: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd =>0x0ff10d819ce0: fd fd fd fd fd fd fd fd fd fd[fd]fd fd fd fd fd 0x0ff10d819cf0: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd 0x0ff10d819d00: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd 0x0ff10d819d10: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd 0x0ff10d819d20: fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd fd 0x0ff10d819d30: 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 ==63495==ABORTING 

Additional information


We found a pointer named map_sub_ created by nav2_amcl that was not freed in the cleanup function amcl_node::on_cleanup(), and it was not freed in the preceding runtime function either.

Also, focus on code lines amcl_node.cpp#L335-L339, the pointer map_ would be freed by map_free(map_).

Thus, if the map_sub_ recieved a map-msg after the map_free(map_) has been done, map_sub_ initiates the following function calls: mapReceived() -> handleMapMessage() -> createFreeSpaceVector(), and finally use the freed pointer map_ in this line amcl_node.cpp#L1418

By the way, if map_sub_ received map-message after map_=nullptr, it would also cause the nullptr accessed.

a suggestion that may be helpful:

  • shall we close the subscriber map_sub_ and do map_sub_.reset() before map_free(map_) ?

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