ros-navigation / navigation2

ROS 2 Navigation Framework and System
https://nav2.org/
Other
2.3k stars 1.2k forks source link

NullPointer Accessed during `makePlan` calculation of nav2_navfn_planner #4466

Closed GoesM closed 1 week ago

GoesM commented 1 week ago

Bug report

Required Info:

Steps to reproduce issue

Launch the navigation2 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

no bug occured.

Actual behavior

the Asan report of this bug is as following:

=================================================================
==1073701==ERROR: AddressSanitizer: SEGV on unknown address 0x00000001164b (pc 0x7466da520cda bp 0x7466da0eed10 sp 0x7466c9070298 T34)
==1073701==The signal is caused by a WRITE memory access.
     #1 0x7466d670d21f in nav2_navfn_planner::NavfnPlanner::makePlan(geometry_msgs::msg::Pose_<std::allocator<void> > const&, geometry_msgs::msg::Pose_<std::allocator<void> > const&, double, nav_msgs::msg::Path_<std::allocator<void> >&) (/home/*****/nav2_humble/install/nav2_navfn_planner/lib/libnav2_navfn_planner.so+0xd21f) (BuildId: b1e5753b18f33b46dab7d58e6194ddc8a97af59a)
    #2 0x7466d670cbd1 in nav2_navfn_planner::NavfnPlanner::createPlan(geometry_msgs::msg::PoseStamped_<std::allocator<void> > const&, geometry_msgs::msg::PoseStamped_<std::allocator<void> > const&) (/home/*****/nav2_humble/install/nav2_navfn_planner/lib/libnav2_navfn_planner.so+0xcbd1) (BuildId: b1e5753b18f33b46dab7d58e6194ddc8a97af59a)
    #3 0x7466dab78cf4 in nav2_planner::PlannerServer::getPlan(geometry_msgs::msg::PoseStamped_<std::allocator<void> > const&, geometry_msgs::msg::PoseStamped_<std::allocator<void> > const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x178cf4) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #4 0x7466dab6cfc1 in nav2_planner::PlannerServer::computePlanThroughPoses() (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x16cfc1) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #5 0x7466dac70aa3 in nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::work() (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x270aa3) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #6 0x7466dac70084 in std::__future_base::_Task_setter<std::unique_ptr<std::__future_base::_Result<void>, std::__future_base::_Result_base::_Deleter>, std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()> >, void>::operator()() const (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x270084) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #7 0x7466dac6fd97 in std::enable_if<is_invocable_r_v<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter>, std::__future_base::_Task_setter<std::unique_ptr<std::__future_base::_Result<void>, std::__future_base::_Result_base::_Deleter>, std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()> >, void>&>, std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> >::type std::__invoke_r<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter>, std::__future_base::_Task_setter<std::unique_ptr<std::__future_base::_Result<void>, std::__future_base::_Result_base::_Deleter>, std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()> >, void>&>(std::__future_base::_Task_setter<std::unique_ptr<std::__future_base::_Result<void>, std::__future_base::_Result_base::_Deleter>, std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()> >, void>&) (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x26fd97) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #8 0x7466dac6fbd8 in std::_Function_handler<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> (), std::__future_base::_Task_setter<std::unique_ptr<std::__future_base::_Result<void>, std::__future_base::_Result_base::_Deleter>, std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()> >, void> >::_M_invoke(std::_Any_data const&) (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x26fbd8) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #9 0x7466dac483ef in std::__future_base::_State_baseV2::_M_do_set(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*) (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x2483ef) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #10 0x7466d8a99ee7 in __pthread_once_slow nptl/./nptl/pthread_once.c:116:7
    #11 0x7466dac6f0e1 in std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()> >, void>::_M_run() (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x26f0e1) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #12 0x7466d8edc252  (/lib/x86_64-linux-gnu/libstdc++.so.6+0xdc252) (BuildId: e37fe1a879783838de78cbc8c80621fa685d58a2)
    #13 0x7466d8a94ac2 in start_thread nptl/./nptl/pthread_create.c:442:8
    #14 0x7466d8b2684f  misc/../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

AddressSanitizer can not provide additional info.
SUMMARY: AddressSanitizer: SEGV (/home/*****/nav2_humble/install/nav2_costmap_2d/lib/libnav2_costmap_2d_core.so+0xc3cda) (BuildId: ae00021bac019132f382130b42d6275d543c55a4) in nav2_costmap_2d::Costmap2D::setCost(unsigned int, unsigned int, unsigned char)
Thread T34 created by T16 here:
    #0 0x5d5cd0ef987c in __interceptor_pthread_create (/home/*****/nav2_humble/install/nav2_planner/lib/nav2_planner/planner_server+0x9387c) (BuildId: 191f253724b34c41ec9522f9202cc91f782cabef)
    #1 0x7466d8edc328 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 0x7466dac6ea42 in std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()> >, void>::_Async_state_impl<nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()>(nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()&&) (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x26ea42) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #3 0x7466dac6e1e8 in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::__shared_count<std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()> >, void>, std::allocator<void>, nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()>(std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()> >, void>*&, std::_Sp_alloc_shared_tag<std::allocator<void> >, nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()&&) (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x26e1e8) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #4 0x7466dac6cd03 in std::future<std::__invoke_result<std::decay<nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()>::type>::type> std::async<nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()>(std::launch, nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >)::'lambda'()&&) (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x26cd03) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #5 0x7466dac56419 in nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >) (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x256419) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #6 0x7466dac74c97 in void std::__invoke_impl<void, void (nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::*&)(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >), nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>*&, std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> > >(std::__invoke_memfun_deref, void (nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::*&)(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >), nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>*&, std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathThroughPoses> >&&) (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x274c97) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #7 0x7466dac5d836 in rclcpp_action::Server<nav2_msgs::action::ComputePathThroughPoses>::call_goal_accepted_callback(std::shared_ptr<rcl_action_goal_handle_s>, std::array<unsigned char, 16ul>, std::shared_ptr<void>) (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x25d836) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #8 0x7466da28e246 in rclcpp_action::ServerBase::execute_goal_request_received(std::shared_ptr<void>&) (/opt/ros/humble/lib/librclcpp_action.so+0x13246) (BuildId: 4dfcc4cee7010878193255b3a622d5194654caa8)

Thread T16 created by T0 here:
    #0 0x5d5cd0ef987c in __interceptor_pthread_create (/home/*****/nav2_humble/install/nav2_planner/lib/nav2_planner/planner_server+0x9387c) (BuildId: 191f253724b34c41ec9522f9202cc91f782cabef)
    #1 0x7466d8edc328 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 0x7466dac52034 in nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::SimpleActionServer(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeWaitablesInterface>, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::function<void ()>, std::function<void ()>, std::chrono::duration<long, std::ratio<1l, 1000l> >, bool, rcl_action_server_options_s const&) (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x252034) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #3 0x7466dac4fd35 in nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>::SimpleActionServer<std::shared_ptr<nav2_util::LifecycleNode> >(std::shared_ptr<nav2_util::LifecycleNode>, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::function<void ()>, std::function<void ()>, std::chrono::duration<long, std::ratio<1l, 1000l> >, bool, rcl_action_server_options_s const&) (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x24fd35) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #4 0x7466dab6b9b8 in std::__detail::_MakeUniq<nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses> >::__single_object std::make_unique<nav2_util::SimpleActionServer<nav2_msgs::action::ComputePathThroughPoses>, std::shared_ptr<nav2_util::LifecycleNode>, char const (&) [27], std::_Bind<void (nav2_planner::PlannerServer::* (nav2_planner::PlannerServer*))()>, std::nullptr_t, std::chrono::duration<long, std::ratio<1l, 1000l> >, bool>(std::shared_ptr<nav2_util::LifecycleNode>&&, char const (&) [27], std::_Bind<void (nav2_planner::PlannerServer::* (nav2_planner::PlannerServer*))()>&&, std::nullptr_t&&, std::chrono::duration<long, std::ratio<1l, 1000l> >&&, bool&&) (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x16b9b8) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #5 0x7466dab641ac in nav2_planner::PlannerServer::on_configure(rclcpp_lifecycle::State const&) (/home/*****/nav2_humble/install/nav2_planner/lib/libplanner_server_core.so+0x1641ac) (BuildId: 1b8bf26805500b9cf783c2dd56285836f05b374f)
    #6 0x7466da08b8ec  (/opt/ros/humble/lib/librclcpp_lifecycle.so+0x288ec) (BuildId: 97f6428dc1ee45fd402b522b3b8e6b4fcfeabe76)

==1073701==ABORTING

Additional information


It's a shutdown-issue

First, based on my execution logs, I can confirm this is a shutdown issue.

It's additional tickets related to #4463, which behaviors in nav2_planner

Below is an analysis of the cause of this bug:

The action_server_ binds the nav2_planner::PlannerServer::computePlan() function as a callback function,

and using the nav2_navfn_planner->makePlan(), which may access the early shutdowncostmapros`:

https://github.com/ros-navigation/navigation2/blob/9fbae3e66ecc3b7315ca7cbb070468a564f5e111/nav2_navfn_planner/src/navfn_planner.cpp#L242-L245

This issue would be fixed in humble by PR #4463
This issue would be fixed in Iron by my later PR
GoesM commented 1 week ago

also just another tickets, I'd close it.