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

NullPtr bug occurs during costmap-calculation of controller_server #4323

Closed
GoesM opened this issue May 10, 2024 · 5 comments
Closed

NullPtr bug occurs during costmap-calculation of controller_server #4323

GoesM opened this issue May 10, 2024 · 5 comments

Comments

@GoesM
Copy link
Contributor

GoesM commented May 10, 2024

Bug report

Required Info:

  • Operating System:
    • Ubuntu22.04
  • ROS2 Version:
    • humble
  • Version or commit hash:
    • the latest
  • DDS implementation:
    • defaulted

Steps to reproduce issue

Just launch 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 

And finally sent Ctrl+C to shutdown navigation2.

An ASAN report file was discovered in my execution environment.

Expected behavior

no bug occured.

Actual behavior

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

=================================================================
==130823==ERROR: AddressSanitizer: SEGV on unknown address 0x000000000000 (pc 0x729ae10db0a7 bp 0x729ad2e5b518 sp 0x729ad2e5b420 T19)
==130823==The signal is caused by a READ memory access.
==130823==Hint: address points to the zero page.
    #0 0x729ae10db0a7 in geometry_msgs::msg::PoseStamped_<std::allocator<void> >& tf2_ros::BufferInterface::transform<geometry_msgs::msg::PoseStamped_<std::allocator<void> > >(geometry_msgs::msg::PoseStamped_<std::allocator<void> > const&, geometry_msgs::msg::PoseStamped_<std::allocator<void> >&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >) const (/home/ROS/nav2_humble/install/nav_2d_utils/lib/libtf_help.so+0x50a7) (BuildId: f41cf37be8ae9a489a0e1967e8f3d5855328550d)
    #1 0x729ae082510c in geometry_msgs::msg::PoseStamped_<std::allocator<void> > tf2_ros::BufferInterface::transform<geometry_msgs::msg::PoseStamped_<std::allocator<void> > >(geometry_msgs::msg::PoseStamped_<std::allocator<void> > const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >) const (/home/ROS/nav2_humble/install/nav2_util/lib/libnav2_util_core.so+0x8a10c) (BuildId: 074014a12aa30b6de43159e7eb335b66f35e5343)
    #2 0x729ae082394d in nav2_util::transformPoseInTargetFrame(geometry_msgs::msg::PoseStamped_<std::allocator<void> > const&, geometry_msgs::msg::PoseStamped_<std::allocator<void> >&, tf2_ros::Buffer&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, double) (/home/ROS/nav2_humble/install/nav2_util/lib/libnav2_util_core.so+0x8894d) (BuildId: 074014a12aa30b6de43159e7eb335b66f35e5343)
    #3 0x729ae082383f in nav2_util::getCurrentPose(geometry_msgs::msg::PoseStamped_<std::allocator<void> >&, tf2_ros::Buffer&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, double, rclcpp::Time) (/home/ROS/nav2_humble/install/nav2_util/lib/libnav2_util_core.so+0x8883f) (BuildId: 074014a12aa30b6de43159e7eb335b66f35e5343)
    #4 0x729ae09e44f8 in nav2_costmap_2d::Costmap2DROS::getRobotPose(geometry_msgs::msg::PoseStamped_<std::allocator<void> >&) (/home/ROS/nav2_humble/install/nav2_costmap_2d/lib/libnav2_costmap_2d_core.so+0xd74f8) (BuildId: d3f6c00ef70b4aad0debc1ebe06356b8e99d1629)
    #5 0x729adf0a6813 in nav2_controller::ControllerServer::getRobotPose(geometry_msgs::msg::PoseStamped_<std::allocator<void> >&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x2a6813) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #6 0x729adf0a4c71 in nav2_controller::ControllerServer::isGoalReached() (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x2a4c71) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #7 0x729adf094472 in nav2_controller::ControllerServer::computeControl() (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x294472) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #8 0x729adf21cad3 in nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::work() (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x41cad3) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #9 0x729adf21be44 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::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void>::operator()() const (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x41be44) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #10 0x729adf21bb57 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::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'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::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'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::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void>&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x41bb57) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #11 0x729adf21b998 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::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void> >::_M_invoke(std::_Any_data const&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x41b998) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #12 0x729ae081ab46 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/ROS/nav2_humble/install/nav2_util/lib/libnav2_util_core.so+0x7fb46) (BuildId: 074014a12aa30b6de43159e7eb335b66f35e5343)
    #13 0x729ade699ee7 in __pthread_once_slow nptl/./nptl/pthread_once.c:116:7
    #14 0x729adf219561 in std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void>::_M_run() (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x419561) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #15 0x729adeadc252  (/lib/x86_64-linux-gnu/libstdc++.so.6+0xdc252) (BuildId: e37fe1a879783838de78cbc8c80621fa685d58a2)
    #16 0x729ade694ac2 in start_thread nptl/./nptl/pthread_create.c:442:8
    #17 0x729ade72684f  misc/../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

AddressSanitizer can not provide additional info.
SUMMARY: AddressSanitizer: SEGV (/home/ROS/nav2_humble/install/nav_2d_utils/lib/libtf_help.so+0x50a7) (BuildId: f41cf37be8ae9a489a0e1967e8f3d5855328550d) in geometry_msgs::msg::PoseStamped_<std::allocator<void> >& tf2_ros::BufferInterface::transform<geometry_msgs::msg::PoseStamped_<std::allocator<void> > >(geometry_msgs::msg::PoseStamped_<std::allocator<void> > const&, geometry_msgs::msg::PoseStamped_<std::allocator<void> >&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >) const
Thread T19 created by T15 here:
    #0 0x5c5ac718d83c in __interceptor_pthread_create (/home/ROS/nav2_humble/install/nav2_controller/lib/nav2_controller/controller_server+0x9383c) (BuildId: 60fb04b0300c8f65b9f573a6e9d75aa30322c8e1)
    #1 0x729adeadc328 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 0x729adf218ec2 in std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void>::_Async_state_impl<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()>(nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()&&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x418ec2) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #3 0x729adf218668 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::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void>, std::allocator<void>, nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()>(std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void>*&, std::_Sp_alloc_shared_tag<std::allocator<void> >, nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()&&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x418668) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #4 0x729adf216913 in std::future<std::__invoke_result<std::decay<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()>::type>::type> std::async<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()>(std::launch, nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()&&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x416913) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #5 0x729adf1ffa39 in nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x3ffa39) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #6 0x729adf2206d7 in void std::__invoke_impl<void, void (nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::*&)(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >), nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>*&, std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> > >(std::__invoke_memfun_deref, void (nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::*&)(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >), nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>*&, std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >&&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x4206d7) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #7 0x729adf207596 in rclcpp_action::Server<nav2_msgs::action::FollowPath>::call_goal_accepted_callback(std::shared_ptr<rcl_action_goal_handle_s>, std::array<unsigned char, 16ul>, std::shared_ptr<void>) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x407596) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #8 0x729ae04ea1b6 in rclcpp_action::ServerBase::execute_goal_request_received(std::shared_ptr<void>&) (/opt/ros/humble/lib/librclcpp_action.so+0x131b6) (BuildId: 8da0710b8af025b200f6ce73ffc85c5ed5c45a8d)

Thread T15 created by T0 here:
    #0 0x5c5ac718d83c in __interceptor_pthread_create (/home/ROS/nav2_humble/install/nav2_controller/lib/nav2_controller/controller_server+0x9383c) (BuildId: 60fb04b0300c8f65b9f573a6e9d75aa30322c8e1)
    #1 0x729adeadc328 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 0x729adf1f8eb5 in nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::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/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x3f8eb5) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #3 0x729adf092bc8 in std::__detail::_MakeUniq<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath> >::__single_object std::make_unique<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>, std::shared_ptr<nav2_util::LifecycleNode>, char const (&) [12], std::_Bind<void (nav2_controller::ControllerServer::* (nav2_controller::ControllerServer*))()>, std::nullptr_t, std::chrono::duration<long, std::ratio<1l, 1000l> >, bool>(std::shared_ptr<nav2_util::LifecycleNode>&&, char const (&) [12], std::_Bind<void (nav2_controller::ControllerServer::* (nav2_controller::ControllerServer*))()>&&, std::nullptr_t&&, std::chrono::duration<long, std::ratio<1l, 1000l> >&&, bool&&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x292bc8) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #4 0x729adf088021 in nav2_controller::ControllerServer::on_configure(rclcpp_lifecycle::State const&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x288021) (BuildId: 72a6929e4535368de7f442ee4162f491af872269)
    #5 0x729ae00fbb8c  (/opt/ros/humble/lib/librclcpp_lifecycle.so+0x28b8c) (BuildId: e9b8e454bf87aaab775667b79aefcab12c018de9)

==130823==ABORTING

Additional information


Accroding to the ASAN report ,

it seems that global_pose variable is changed as a NullPtr when costmap_ros->getRobotPose is still running.

https://github.com/open-navigation/navigation2/blob/8f097af08ced738f4a0797d941a60d834ebc8d80/nav2_controller/src/controller_server.cpp#L613-L621

@GoesM
Copy link
Contributor Author

GoesM commented May 10, 2024

Additional Information

an experiment

step 0. insert a delay into the function:

bool
Costmap2DROS::getRobotPose(geometry_msgs::msg::PoseStamped & global_pose)
{
std::this_thread::sleep_for(std::chrono::seconds(10));
RCLCPP_INFO(get_logger(),"[GOES|DEBUG] after insesrt");
  return nav2_util::getCurrentPose(
    global_pose, *tf_buffer_,
    global_frame_, robot_base_frame_, transform_tolerance_);
}

step 1. launch the nav2

step 2. send a Nav2Goal

step 3. Ctrl+C to navigation2 before it finished the goal

step 4. then, we could get a similar Asan report stablely.

=================================================================
==35202==ERROR: AddressSanitizer: SEGV on unknown address 0x000000000000 (pc 0x7efba39f7511 bp 0x000000000001 sp 0x7efb96a50e10 T17)
==35202==The signal is caused by a READ memory access.
==35202==Hint: address points to the zero page.
    #0 0x7efba39f7511 in rclcpp_lifecycle::LifecycleNode::get_logger() const (/opt/ros/humble/lib/librclcpp_lifecycle.so+0x23511) (BuildId: e9b8e454bf87aaab775667b79aefcab12c018de9)
    #1 0x7efba43e4591 in nav2_costmap_2d::Costmap2DROS::getRobotPose(geometry_msgs::msg::PoseStamped_<std::allocator<void> >&) (/home/ROS/nav2_humble/install/nav2_costmap_2d/lib/libnav2_costmap_2d_core.so+0xd7591) (BuildId: 49676d3cd8f2fb2bf6c57b7774a5bffa91ef920a)
    #2 0x7efba2a9439e in nav2_controller::ControllerServer::getRobotPose(geometry_msgs::msg::PoseStamped_<std::allocator<void> >&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x29439e) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #3 0x7efba2a914a7 in nav2_controller::ControllerServer::computeAndPublishVelocity() (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x2914a7) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #4 0x7efba2a86731 in nav2_controller::ControllerServer::computeControl() (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x286731) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #5 0x7efba2c3bbd7 in nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::work() (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x43bbd7) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #6 0x7efba2c3af98 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::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void>::operator()() const (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x43af98) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #7 0x7efba2c3acb9 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::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'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::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'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::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void>&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x43acb9) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #8 0x7efba2c3ab40 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::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void> >::_M_invoke(std::_Any_data const&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x43ab40) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #9 0x7efba411bb46 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/ROS/nav2_humble/install/nav2_util/lib/libnav2_util_core.so+0x7fb46) (BuildId: 074014a12aa30b6de43159e7eb335b66f35e5343)
    #10 0x7efba2099ee7 in __pthread_once_slow nptl/./nptl/pthread_once.c:116:7
    #11 0x7efba2c3891a in std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void>::_M_run() (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x43891a) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #12 0x7efba24dc252  (/lib/x86_64-linux-gnu/libstdc++.so.6+0xdc252) (BuildId: e37fe1a879783838de78cbc8c80621fa685d58a2)
    #13 0x7efba2094ac2 in start_thread nptl/./nptl/pthread_create.c:442:8
    #14 0x7efba212684f  misc/../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

AddressSanitizer can not provide additional info.
SUMMARY: AddressSanitizer: SEGV (/opt/ros/humble/lib/librclcpp_lifecycle.so+0x23511) (BuildId: e9b8e454bf87aaab775667b79aefcab12c018de9) in rclcpp_lifecycle::LifecycleNode::get_logger() const
Thread T17 created by T15 here:
    #0 0x5cf4825297cc in __interceptor_pthread_create (/home/ROS/nav2_humble/install/nav2_controller/lib/nav2_controller/controller_server+0x937cc) (BuildId: d2576a54366d5dd7100c534f6f2fd3c780cb2112)
    #1 0x7efba24dc328 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 0x7efba2c38299 in std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void>::_Async_state_impl<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()>(nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()&&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x438299) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #3 0x7efba2c37abc 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::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void>, std::allocator<void>, nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()>(std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()> >, void>*&, std::_Sp_alloc_shared_tag<std::allocator<void> >, nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()&&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x437abc) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #4 0x7efba2c35e67 in std::future<std::__invoke_result<std::decay<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()>::type>::type> std::async<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()>(std::launch, nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >)::'lambda'()&&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x435e67) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #5 0x7efba2c1fc6d in nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x41fc6d) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #6 0x7efba2c3f4e4 in void std::__invoke_impl<void, void (nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::*&)(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >), nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>*&, std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> > >(std::__invoke_memfun_deref, void (nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::*&)(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >), nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>*&, std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::FollowPath> >&&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x43f4e4) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #7 0x7efba2c274a7 in rclcpp_action::Server<nav2_msgs::action::FollowPath>::call_goal_accepted_callback(std::shared_ptr<rcl_action_goal_handle_s>, std::array<unsigned char, 16ul>, std::shared_ptr<void>) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x4274a7) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #8 0x7efba3deb1b6 in rclcpp_action::ServerBase::execute_goal_request_received(std::shared_ptr<void>&) (/opt/ros/humble/lib/librclcpp_action.so+0x131b6) (BuildId: 8da0710b8af025b200f6ce73ffc85c5ed5c45a8d)

Thread T15 created by T0 here:
    #0 0x5cf4825297cc in __interceptor_pthread_create (/home/ROS/nav2_humble/install/nav2_controller/lib/nav2_controller/controller_server+0x937cc) (BuildId: d2576a54366d5dd7100c534f6f2fd3c780cb2112)
    #1 0x7efba24dc328 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 0x7efba2c19249 in nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>::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/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x419249) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #3 0x7efba2acdd66 in std::__detail::_MakeUniq<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath> >::__single_object std::make_unique<nav2_util::SimpleActionServer<nav2_msgs::action::FollowPath>, std::shared_ptr<nav2_util::LifecycleNode>, char const (&) [12], std::_Bind<void (nav2_controller::ControllerServer::* (nav2_controller::ControllerServer*))()>, std::nullptr_t, std::chrono::duration<long, std::ratio<1l, 1000l> >, bool>(std::shared_ptr<nav2_util::LifecycleNode>&&, char const (&) [12], std::_Bind<void (nav2_controller::ControllerServer::* (nav2_controller::ControllerServer*))()>&&, std::nullptr_t&&, std::chrono::duration<long, std::ratio<1l, 1000l> >&&, bool&&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x2cdd66) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #4 0x7efba2a816cc in nav2_controller::ControllerServer::on_configure(rclcpp_lifecycle::State const&) (/home/ROS/nav2_humble/install/nav2_controller/lib/libcontroller_server_core.so+0x2816cc) (BuildId: b94c87d452d9ab1ddc25cd204767851aceff6456)
    #5 0x7efba39fcb8c  (/opt/ros/humble/lib/librclcpp_lifecycle.so+0x28b8c) (BuildId: e9b8e454bf87aaab775667b79aefcab12c018de9)

==35202==ABORTING

And part of the log info is as following:

[INFO] [lifecycle_manager-16]: process has finished cleanly [pid 35216]
[INFO] [bt_navigator-13]: process has finished cleanly [pid 35210]
[INFO] [gzserver-1]: process has finished cleanly [pid 35186]
[INFO] [gzclient-2]: process has finished cleanly [pid 35188]
[ERROR] [rviz2-5]: process has died [pid 35194, exit code -6, cmd '/opt/ros/humble/lib/rviz2/rviz2 -d /home/goes/ROS_Workstation/nav2_humble_experiment/install/nav2_bringup/share/nav2_bringup/rviz/nav2_default_view.rviz --ros-args'].
[ERROR] [planner_server-11]: process[planner_server-11] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM'
[ERROR] [controller_server-9]: process[controller_server-9] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM'
[INFO] [planner_server-11]: sending signal 'SIGTERM' to process[planner_server-11]
[INFO] [controller_server-9]: sending signal 'SIGTERM' to process[controller_server-9]
[planner_server-11] [INFO] [1715323667.199657994] [rclcpp]: signal_handler(signum=15)
[controller_server-9] [INFO] [1715323667.200369276] [rclcpp]: signal_handler(signum=15)
[controller_server-9] [INFO] [1715323667.849136127] [local_costmap.local_costmap]: [GOES|DEBUG] after insesrt
[controller_server-9] [INFO] [1715323667.850311477] [local_costmap.local_costmap]: Cleaning up
[controller_server-9] [INFO] [1715323667.852673116] [local_costmap.local_costmap]: Destroying bond (local_costmap) to lifecycle manager.
[controller_server-9] [INFO] [1715323667.852688105] [controller_server]: Running Nav2 LifecycleNode rcl preshutdown (controller_server)
[controller_server-9] [INFO] [1715323667.852702404] [controller_server]: Deactivating
[controller_server-9] [WARN] [1715323667.852711466] [controller_server]: [follow_path] [ActionServer] Requested to deactivate server but goal is still executing. Should check if action server is running before deactivating.
[controller_server-9] [INFO] [1715323667.952765915] [controller_server]: [follow_path] [ActionServer] Waiting for async process to finish.
[controller_server-9] [INFO] [1715323668.052934597] [controller_server]: [follow_path] [ActionServer] Waiting for async process to finish.
[controller_server-9] [INFO] [1715323668.153069458] [controller_server]: [follow_path] [ActionServer] Waiting for async process to finish.
[controller_server-9] [INFO] [1715323668.253188671] [controller_server]: [follow_path] [ActionServer] Waiting for async process to finish.
[controller_server-9] [INFO] [1715323668.353364179] [controller_server]: [follow_path] [ActionServer] Waiting for async process to finish.
[controller_server-9] [WARN] [1715323668.353428297] [controller_server]: [follow_path] [ActionServer] Client requested to cancel the goal. Cancelling.
[controller_server-9] [ERROR] [1715323668.353541656] [controller_server]: Caught exception in callback for transition 14
[controller_server-9] [ERROR] [1715323668.353548292] [controller_server]: Original error: bad_function_call
[controller_server-9] [WARN] [1715323668.353561163] [controller_server]: Error occurred while doing error handling.
[controller_server-9] [FATAL] [1715323668.353571155] [controller_server]: Lifecycle node controller_server does not have error state implemented
[controller_server-9] [INFO] [1715323668.353581680] [controller_server]: Destroying bond (controller_server) to lifecycle manager.
[controller_server-9] [INFO] [1715323668.361706505] [local_costmap.local_costmap]: Destroying
[planner_server-11] [INFO] [1715323669.105028547] [global_costmap.global_costmap]: [GOES|DEBUG] after insesrt
[planner_server-11] [INFO] [1715323669.105871126] [global_costmap.global_costmap]: Cleaning up
[planner_server-11] [INFO] [1715323669.107943705] [global_costmap.global_costmap]: Destroying bond (global_costmap) to lifecycle manager.
[planner_server-11] [INFO] [1715323669.107952933] [planner_server]: Running Nav2 LifecycleNode rcl preshutdown (planner_server)
[planner_server-11] [INFO] [1715323669.107960546] [planner_server]: Deactivating
[planner_server-11] [INFO] [1715323669.107971924] [planner_server]: Deactivating plugin GridBased of type NavfnPlanner
[planner_server-11] [INFO] [1715323669.107992062] [planner_server]: Destroying bond (planner_server) to lifecycle manager.
[planner_server-11] [INFO] [1715323669.108015218] [planner_server]: Cleaning up
[planner_server-11] [INFO] [1715323669.112134008] [planner_server]: Cleaning up plugin GridBased of type NavfnPlanner
[planner_server-11] [INFO] [1715323669.112177999] [planner_server]: Destroying plugin GridBased of type NavfnPlanner
[planner_server-11] [INFO] [1715323669.114519533] [planner_server]: Destroying bond (planner_server) to lifecycle manager.
[planner_server-11] [INFO] [1715323669.116766443] [global_costmap.global_costmap]: Destroying
[planner_server-11] [INFO] [1715323669.119784660] [planner_server]: Destroying
[INFO] [planner_server-11]: process has finished cleanly [pid 35206]
[controller_server-9] AddressSanitizer:DEADLYSIGNAL
[ERROR] [controller_server-9]: process has died [pid 35202, exit code 1, cmd '/home/goes/ROS_Workstation/nav2_humble_experiment/install/nav2_controller/lib/nav2_controller/controller_server --ros-args --log-level info --ros-args --params-file /tmp/launch_params_1tw7epfv -r /tf:=tf -r /tf_static:=tf_static -r cmd_vel:=cmd_vel_nav'].

a conclusion from the experiment

it proves that , the costmap_ros's work could be still running after the resource of controller_server has been all freed.

Also, I noticed that some [ERROR] log of the controller_server occurs during shutdown-period:

[controller_server-9] [ERROR] [1715323668.353541656] [controller_server]: Caught exception in callback for transition 14
[controller_server-9] [ERROR] [1715323668.353548292] [controller_server]: Original error: bad_function_call
....
[ERROR] [controller_server-9]: process has died [pid 35202, exit code 1, cmd '/home/goes/ROS_Workstation/nav2_humble_experiment/install/nav2_controller/lib/nav2_controller/controller_server --ros-args --log-level info --ros-args --params-file /tmp/launch_params_1tw7epfv -r /tf:=tf -r /tf_static:=tf_static -r cmd_vel:=cmd_vel_nav'].

I'd further check why the error log occured.

@SteveMacenski
Copy link
Member

Seems like a lifecycle thing that just needs to be reordered 👍

@SteveMacenski
Copy link
Member

@GoesM any update?

@GoesM
Copy link
Contributor Author

GoesM commented May 30, 2024

Seems like a lifecycle thing that just needs to be reordered 👍

Yeah, it's finally confirmed that the executor_thread_. should reset() firstly.

nav2_util::CallbackReturn
Costmap2DROS::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Cleaning up");
layered_costmap_.reset();
tf_listener_.reset();
tf_buffer_.reset();
footprint_sub_.reset();
footprint_pub_.reset();
costmap_publisher_.reset();
clear_costmap_service_.reset();
executor_thread_.reset();
return nav2_util::CallbackReturn::SUCCESS;
}

doing so , we could make sure that the thread wouldn't access the pointer which has been freed before.

Shall I open a PR for this ISSUE ?

@SteveMacenski
Copy link
Member

Please!

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