Skip to content

Add backward_ros dependency #5404

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

Open
wants to merge 1 commit into
base: main
Choose a base branch
from

Conversation

Sushant-Chavan
Copy link
Contributor

@Sushant-Chavan Sushant-Chavan commented Jul 30, 2025


Basic Info

Info Please fill out this column
Primary OS tested on Ubuntu
Robotic platform tested on N/A
Does this PR contain AI generated software? No

Description of contribution in a few bullet points

  • Added backward_ros as a dependency to nav2 packages
  • This activates pretty-printed logging of back-trace on application crash
    • Very detailed back-trace with code snippets and line numbers if the nav2 packages are built with RelWithDebInfo or Debug configurations. See sample output below
  • Does not yet work with composed-nodes. There is an open issue to address this in rclcpp.
  • I did not do any in-depth evaluation of impact on runtime performance. But the author of backward-cpp mentions that there is no runtime impact and only kicks in when an application crashes to generate the stack trace.

Description of how this change was tested

  • Deliberately reset the plan_publisher_ shared pointer right before publishing the global plan in the PlannerServer::publishPlan()
  • Build nav2 packages with RelWithDebInfo configuration
  • Start navigation with the use_composition flag set to false, using the command:
    ros2 launch nav2_bringup tb3_simulation_launch.py headless:=False use_composition:=false
  • Send a navigation goal from RViz and check the logs for a crash in planner_server. Below are the logs generated with & without backward_ros

Logs without backward_ros dependency

[rviz2-7] Start navigation
[bt_navigator-16] [INFO] [1754377648.631768181] [bt_navigator]: Begin navigating from current location (-1.99, -0.54) to (0.40, 1.87)
[planner_server-13] [INFO] [1754377648.634265021] [planner_server]: Computing path to goal....
[ERROR] [planner_server-13]: process has died [pid 165734, exit code -11, cmd '/opt/overlay_ws/src/navigation2/install/nav2_planner/lib/nav2_planner/planner_server --ros-args --log-level info --ros-args -r __node:=planner_server -r __ns:=/ -p use_sim_time:=True --params-file /tmp/launch_params_ou47e26i -r /tf:=tf -r /tf_static:=tf_static'].
[lifecycle_manager-21] [INFO] [1754377652.776501186] [lifecycle_manager_navigation]: Have not received a heartbeat from planner_server.
[lifecycle_manager-21] [ERROR] [1754377652.776564762] [lifecycle_manager_navigation]: CRITICAL FAILURE: SERVER planner_server IS DOWN after not receiving a heartbeat for 4000 ms. Shutting down related nodes.
[lifecycle_manager-21] [INFO] [1754377652.776661960] [lifecycle_manager_navigation]: Terminating bond timer...
[lifecycle_manager-21] [INFO] [1754377652.776679511] [lifecycle_manager_navigation]: Resetting managed nodes...
[lifecycle_manager-21] [INFO] [1754377652.776693925] [lifecycle_manager_navigation]: Deactivating docking_server
[opennav_docking-20] [INFO] [1754377652.777353259] [docking_server]: Deactivating docking_server
[opennav_docking-20] [INFO] [1754377652.799257043] [docking_server]: Destroying bond (docking_server) to lifecycle manager.
[lifecycle_manager-21] [INFO] [1754377652.915464654] [lifecycle_manager_navigation]: Deactivating waypoint_follower
[waypoint_follower-17] [INFO] [1754377652.916216375] [waypoint_follower]: Deactivating
[waypoint_follower-17] [INFO] [1754377652.916259099] [waypoint_follower]: Destroying bond (waypoint_follower) to lifecycle manager.
[lifecycle_manager-21] [INFO] [1754377653.031245084] [lifecycle_manager_navigation]: Deactivating bt_navigator
[bt_navigator-16] [INFO] [1754377653.032668964] [bt_navigator]: Deactivating
[bt_navigator-16] [WARN] [1754377653.032856395] [bt_navigator]: [navigate_to_pose] [ActionServer] Requested to deactivate server but goal is still executing. Should check if action server is running before deactivating.
[bt_navigator-16] [ERROR] [1754377653.061987682] [bt_navigator_navigate_to_pose_rclcpp_node]: Failed to cancel action server for compute_path_to_pose
[bt_navigator-16] [ERROR] [1754377653.082434056] [bt_navigator_navigate_to_pose_rclcpp_node]: Failed to get result for compute_path_to_pose in node halt!
[bt_navigator-16] [WARN] [1754377653.083296698] [bt_navigator]: [navigate_to_pose] [ActionServer] Aborting handle. error_code:0, error_msg:''.
[bt_navigator-16] [INFO] [1754377653.083944907] [bt_navigator]: Goal canceled
[bt_navigator-16] [WARN] [1754377653.084121490] [bt_navigator]: [navigate_to_pose] [ActionServer] Stopping the thread per request.
[bt_navigator-16] [INFO] [1754377653.084371434] [bt_navigator]: Destroying bond (bt_navigator) to lifecycle manager.
[lifecycle_manager-21] [INFO] [1754377653.207501450] [lifecycle_manager_navigation]: Deactivating collision_monitor
[collision_monitor-19] [INFO] [1754377653.208152003] [collision_monitor]: Deactivating
[collision_monitor-19] [INFO] [1754377653.208184623] [collision_monitor]: Destroying bond (collision_monitor) to lifecycle manager.
[lifecycle_manager-21] [INFO] [1754377653.325251961] [lifecycle_manager_navigation]: Deactivating velocity_smoother
[velocity_smoother-18] [INFO] [1754377653.325678192] [velocity_smoother]: Deactivating
[velocity_smoother-18] [INFO] [1754377653.325731656] [velocity_smoother]: Destroying bond (velocity_smoother) to lifecycle manager.
[lifecycle_manager-21] [INFO] [1754377653.444103256] [lifecycle_manager_navigation]: Deactivating behavior_server
[behavior_server-15] [INFO] [1754377653.445339457] [behavior_server]: Deactivating
[behavior_server-15] [INFO] [1754377653.445644234] [behavior_server]: Destroying bond (behavior_server) to lifecycle manager.
[lifecycle_manager-21] [INFO] [1754377653.562364960] [lifecycle_manager_navigation]: Deactivating route_server
[route_server-14] [INFO] [1754377653.563061925] [route_server]: Deactivating
[route_server-14] [INFO] [1754377653.563208930] [route_server]: Destroying bond (route_server) to lifecycle manager.
[lifecycle_manager-21] [INFO] [1754377653.680189859] [lifecycle_manager_navigation]: Deactivating planner_server

Logs with backward_ros dependency

[rviz2-7] Start navigation
[bt_navigator-16] [INFO] [1754377736.954637893] [bt_navigator]: Begin navigating from current location (-2.00, -0.47) to (0.06, 2.02)
[planner_server-13] [INFO] [1754377736.955537475] [planner_server]: Computing path to goal....
[planner_server-13] Stack trace (most recent call last) in thread 173639:
[planner_server-13] #11   Object "/usr/lib/x86_64-linux-gnu/ld-linux-x86-64.so.2", at 0xffffffffffffffff, in 
[planner_server-13] #10   Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x795ea7ac8c3b, in 
[planner_server-13] #9    Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x795ea7a3baa3, in 
[planner_server-13] #8    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.33", at 0x795ea7ccbdb3, in 
[planner_server-13] #7  | Source "/usr/include/c++/13/future", line 1774, in _M_set_result
[planner_server-13]     |  1772: 	__try
[planner_server-13]     |  1773: 	  {
[planner_server-13]     | >1774: 	    _M_set_result(_S_task_setter(_M_result, _M_fn));
[planner_server-13]     |  1775: 	  }
[planner_server-13]     |  1776: 	__catch (const __cxxabiv1::__forced_unwind&)
[planner_server-13]     | Source "/usr/include/c++/13/future", line 428, in call_once<void (std::__future_base::_State_baseV2::*)(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter>()>*, bool*), std::__future_base::_State_baseV2*, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter>()>*, bool*>
[planner_server-13]     |   426:         // all calls to this function are serialized,
[planner_server-13]     |   427:         // side-effects of invoking __res only happen once
[planner_server-13]     | > 428: 	call_once(_M_once, &_State_baseV2::_M_do_set, this,
[planner_server-13]     |   429: 		  std::__addressof(__res), std::__addressof(__did_set));
[planner_server-13]     |   430: 	if (__did_set)
[planner_server-13]     | Source "/usr/include/c++/13/mutex", line 907, in __gthread_once
[planner_server-13]     |   906:       // XXX pthread_once does not reset the flag if an exception is thrown.
[planner_server-13]     | > 907:       if (int __e = __gthread_once(&__once._M_once, &__once_proxy))
[planner_server-13]     |   908: 	__throw_system_error(__e);
[planner_server-13]     |   909:     }
[planner_server-13]       Source "/usr/include/x86_64-linux-gnu/c++/13/bits/gthr-default.h", line 700, in _M_run [0x795ea8356c57]
[planner_server-13]         697: __gthread_once (__gthread_once_t *__once, void (*__func) (void))
[planner_server-13]         698: {
[planner_server-13]         699:   if (__gthread_active_p ())
[planner_server-13]       > 700:     return __gthrw_(pthread_once) (__once, __func);
[planner_server-13]         701:   else
[planner_server-13]         702:     return -1;
[planner_server-13]         703: }
[planner_server-13] #6    Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x795ea7a40ed2, in 
[planner_server-13] #5  | Source "/usr/include/c++/13/future", line 589, in operator()
[planner_server-13]     |   587:       _M_do_set(function<_Ptr_type()>* __f, bool* __did_set)
[planner_server-13]     |   588:       {
[planner_server-13]     | > 589:         _Ptr_type __res = (*__f)();
[planner_server-13]     |   590:         // Notify the caller that we did try to set; if we do not throw an
[planner_server-13]     |   591:         // exception, the caller will be aware that it did set (e.g., see
[planner_server-13]       Source "/usr/include/c++/13/bits/std_function.h", line 591, in _M_do_set [0x795ea834aa7c]
[planner_server-13]         588:       {
[planner_server-13]         589: 	if (_M_empty())
[planner_server-13]         590: 	  __throw_bad_function_call();
[planner_server-13]       > 591: 	return _M_invoker(_M_functor, std::forward<_ArgTypes>(__args)...);
[planner_server-13]         592:       }
[planner_server-13]         593: 
[planner_server-13]         594: #if __cpp_rtti
[planner_server-13] #4  | Source "/usr/include/c++/13/bits/std_function.h", line 291, in __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::SimpleActionServer<nav2_msgs::action::ComputePathToPose>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathToPose> >)::<lambda()> > >, void>&>
[planner_server-13]     |   289:       {
[planner_server-13]     |   290: 	return std::__invoke_r<_Res>(*_Base::_M_get_pointer(__functor),
[planner_server-13]     | > 291: 				     std::forward<_ArgTypes>(__args)...);
[planner_server-13]     |   292:       }
[planner_server-13]     | Source "/usr/include/c++/13/bits/invoke.h", line 116, in __invoke_impl<std::unique_ptr<std::__future_base::_Result<void>, 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::SimpleActionServer<nav2_msgs::action::ComputePathToPose>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathToPose> >)::<lambda()> > >, void>&>
[planner_server-13]     |   114: 	return std::__invoke_impl<__type>(__tag{},
[planner_server-13]     |   115: 					  std::forward<_Callable>(__fn),
[planner_server-13]     | > 116: 					  std::forward<_Args>(__args)...);
[planner_server-13]     |   117:     }
[planner_server-13]     |   118: #else // C++11 or C++14
[planner_server-13]     | Source "/usr/include/c++/13/bits/invoke.h", line 61, in operator()
[planner_server-13]     |    59:     constexpr _Res
[planner_server-13]     |    60:     __invoke_impl(__invoke_other, _Fn&& __f, _Args&&... __args)
[planner_server-13]     | >  61:     { return std::forward<_Fn>(__f)(std::forward<_Args>(__args)...); }
[planner_server-13]     |    62: 
[planner_server-13]     |    63:   template<typename _Res, typename _MemFun, typename _Tp, typename... _Args>
[planner_server-13]     | Source "/usr/include/c++/13/future", line 1432, in operator()
[planner_server-13]     |  1430: 	__try
[planner_server-13]     |  1431: 	  {
[planner_server-13]     | >1432: 	    (*_M_fn)();
[planner_server-13]     |  1433: 	  }
[planner_server-13]     |  1434: 	__catch(const __cxxabiv1::__forced_unwind&)
[planner_server-13]     | Source "/usr/include/c++/13/bits/std_thread.h", line 299, in _M_invoke<0>
[planner_server-13]     |   297: 	  using _Indices
[planner_server-13]     |   298: 	    = typename _Build_index_tuple<tuple_size<_Tuple>::value>::__type;
[planner_server-13]     | > 299: 	  return _M_invoke(_Indices());
[planner_server-13]     |   300: 	}
[planner_server-13]     |   301:       };
[planner_server-13]     | Source "/usr/include/c++/13/bits/std_thread.h", line 292, in __invoke<nav2::SimpleActionServer<nav2_msgs::action::ComputePathToPose>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathToPose> >)::<lambda()> >
[planner_server-13]     |   290: 	  typename __result<_Tuple>::type
[planner_server-13]     |   291: 	  _M_invoke(_Index_tuple<_Ind...>)
[planner_server-13]     | > 292: 	  { return std::__invoke(std::get<_Ind>(std::move(_M_t))...); }
[planner_server-13]     |   293: 
[planner_server-13]     |   294: 	typename __result<_Tuple>::type
[planner_server-13]     | Source "/usr/include/c++/13/bits/invoke.h", line 96, in __invoke_impl<void, nav2::SimpleActionServer<nav2_msgs::action::ComputePathToPose>::handle_accepted(std::shared_ptr<rclcpp_action::ServerGoalHandle<nav2_msgs::action::ComputePathToPose> >)::<lambda()> >
[planner_server-13]     |    94:       using __type = typename __result::type;
[planner_server-13]     |    95:       using __tag = typename __result::__invoke_type;
[planner_server-13]     | >  96:       return std::__invoke_impl<__type>(__tag{}, std::forward<_Callable>(__fn),
[planner_server-13]     |    97: 					std::forward<_Args>(__args)...);
[planner_server-13]     |    98:     }
[planner_server-13]     | Source "/usr/include/c++/13/bits/invoke.h", line 61, in operator()
[planner_server-13]     |    59:     constexpr _Res
[planner_server-13]     |    60:     __invoke_impl(__invoke_other, _Fn&& __f, _Args&&... __args)
[planner_server-13]     | >  61:     { return std::forward<_Fn>(__f)(std::forward<_Args>(__args)...); }
[planner_server-13]     |    62: 
[planner_server-13]     |    63:   template<typename _Res, typename _MemFun, typename _Tp, typename... _Args>
[planner_server-13]       Source "/opt/overlay_ws/src/navigation2/nav2_ros_common/include/nav2_ros_common/simple_action_server.hpp", line 239, in _M_invoke [0x795ea83813c0]
[planner_server-13]         236:       execution_future_ = std::async(
[planner_server-13]         237:         std::launch::async, [this]() {
[planner_server-13]         238:           setSoftRealTimePriority();
[planner_server-13]       > 239:           work();
[planner_server-13]         240:         });
[planner_server-13]         241:     }
[planner_server-13]         242:   }
[planner_server-13] #3  | Source "/opt/overlay_ws/src/navigation2/nav2_ros_common/include/nav2_ros_common/simple_action_server.hpp", line 252, in operator()
[planner_server-13]     |   250:       debug_msg("Executing the goal...");
[planner_server-13]     |   251:       try {
[planner_server-13]     | > 252:         execute_callback_();
[planner_server-13]     |   253:       } catch (std::exception & ex) {
[planner_server-13]     |   254:         RCLCPP_ERROR(
[planner_server-13]       Source "/usr/include/c++/13/bits/std_function.h", line 591, in work [0x795ea8380944]
[planner_server-13]         588:       {
[planner_server-13]         589: 	if (_M_empty())
[planner_server-13]         590: 	  __throw_bad_function_call();
[planner_server-13]       > 591: 	return _M_invoker(_M_functor, std::forward<_ArgTypes>(__args)...);
[planner_server-13]         592:       }
[planner_server-13]         593: 
[planner_server-13]         594: #if __cpp_rtti
[planner_server-13] #2    Source "/opt/overlay_ws/src/navigation2/nav2_planner/src/planner_server.cpp", line 546, in computePlan [0x795ea8344363]
[planner_server-13]         543:     }
[planner_server-13]         544: 
[planner_server-13]         545:     // Publish the plan for visualization purposes
[planner_server-13]       > 546:     publishPlan(result->path);
[planner_server-13]         547: 
[planner_server-13]         548:     auto cycle_duration = this->now() - start_time;
[planner_server-13]         549:     result->planning_time = cycle_duration;
[planner_server-13] #1    Source "/opt/overlay_ws/src/navigation2/nav2_planner/src/planner_server.cpp", line 640, in publishPlan [0x795ea833df4a]
[planner_server-13]         637:   auto msg = std::make_unique<nav_msgs::msg::Path>(path);
[planner_server-13]         638:   RCLCPP_WARN(get_logger(), "Publishing plan with %zu poses", path.poses.size());
[planner_server-13]         639:   plan_publisher_.reset();
[planner_server-13]       > 640:   if (plan_publisher_->is_activated() && plan_publisher_->get_subscription_count() > 0) {
[planner_server-13]         641:     plan_publisher_->publish(std::move(msg));
[planner_server-13]         642:   }
[planner_server-13]         643: }
[planner_server-13] #0    Object "/opt/ros/rolling/lib/librclcpp_lifecycle.so", at 0x795ea80f1f94, in rclcpp_lifecycle::SimpleManagedEntity::is_activated() const
[planner_server-13] Segmentation fault (Address not mapped to object [0x8])
[ERROR] [planner_server-13]: process has died [pid 172784, exit code -11, cmd '/opt/overlay_ws/src/navigation2/install/nav2_planner/lib/nav2_planner/planner_server --ros-args --log-level info --ros-args -r __node:=planner_server -r __ns:=/ -p use_sim_time:=True --params-file /tmp/launch_params_px13xl6j -r /tf:=tf -r /tf_static:=tf_static'].
[lifecycle_manager-21] [INFO] [1754377741.311127479] [lifecycle_manager_navigation]: Have not received a heartbeat from planner_server.
[lifecycle_manager-21] [ERROR] [1754377741.311199220] [lifecycle_manager_navigation]: CRITICAL FAILURE: SERVER planner_server IS DOWN after not receiving a heartbeat for 4000 ms. Shutting down related nodes.
[lifecycle_manager-21] [INFO] [1754377741.311276663] [lifecycle_manager_navigation]: Terminating bond timer...
[lifecycle_manager-21] [INFO] [1754377741.311290870] [lifecycle_manager_navigation]: Resetting managed nodes...
[lifecycle_manager-21] [INFO] [1754377741.311301699] [lifecycle_manager_navigation]: Deactivating docking_server
[opennav_docking-20] [INFO] [1754377741.311769074] [docking_server]: Deactivating docking_server
[opennav_docking-20] [INFO] [1754377741.342044972] [docking_server]: Destroying bond (docking_server) to lifecycle manager.
[lifecycle_manager-21] [INFO] [1754377741.456373263] [lifecycle_manager_navigation]: Deactivating waypoint_follower
[waypoint_follower-17] [INFO] [1754377741.457138274] [waypoint_follower]: Deactivating
[waypoint_follower-17] [INFO] [1754377741.457205291] [waypoint_follower]: Destroying bond (waypoint_follower) to lifecycle manager.
[lifecycle_manager-21] [INFO] [1754377741.572234297] [lifecycle_manager_navigation]: Deactivating bt_navigator
[bt_navigator-16] [INFO] [1754377741.572785873] [bt_navigator]: Deactivating
[bt_navigator-16] [WARN] [1754377741.572864426] [bt_navigator]: [navigate_to_pose] [ActionServer] Requested to deactivate server but goal is still executing. Should check if action server is running before deactivating.
[bt_navigator-16] [ERROR] [1754377741.594958660] [bt_navigator_navigate_to_pose_rclcpp_node]: Failed to cancel action server for compute_path_to_pose
[bt_navigator-16] [ERROR] [1754377741.615126369] [bt_navigator_navigate_to_pose_rclcpp_node]: Failed to get result for compute_path_to_pose in node halt!
[bt_navigator-16] [WARN] [1754377741.615465459] [bt_navigator]: [navigate_to_pose] [ActionServer] Aborting handle. error_code:0, error_msg:''.
[bt_navigator-16] [INFO] [1754377741.615764530] [bt_navigator]: Goal canceled
[bt_navigator-16] [WARN] [1754377741.615861834] [bt_navigator]: [navigate_to_pose] [ActionServer] Stopping the thread per request.
[bt_navigator-16] [INFO] [1754377741.616305682] [bt_navigator]: Destroying bond (bt_navigator) to lifecycle manager.
[lifecycle_manager-21] [INFO] [1754377741.734371342] [lifecycle_manager_navigation]: Deactivating collision_monitor
[collision_monitor-19] [INFO] [1754377741.735557303] [collision_monitor]: Deactivating
[collision_monitor-19] [INFO] [1754377741.735761427] [collision_monitor]: Destroying bond (collision_monitor) to lifecycle manager.
[lifecycle_manager-21] [INFO] [1754377741.855522185] [lifecycle_manager_navigation]: Deactivating velocity_smoother
[velocity_smoother-18] [INFO] [1754377741.855967907] [velocity_smoother]: Deactivating
[velocity_smoother-18] [INFO] [1754377741.856026630] [velocity_smoother]: Destroying bond (velocity_smoother) to lifecycle manager.
[lifecycle_manager-21] [INFO] [1754377741.970283622] [lifecycle_manager_navigation]: Deactivating behavior_server
[behavior_server-15] [INFO] [1754377741.971206856] [behavior_server]: Deactivating
[behavior_server-15] [INFO] [1754377741.971436228] [behavior_server]: Destroying bond (behavior_server) to lifecycle manager.
[lifecycle_manager-21] [INFO] [1754377742.086493739] [lifecycle_manager_navigation]: Deactivating route_server
[route_server-14] [INFO] [1754377742.087515287] [route_server]: Deactivating
[route_server-14] [INFO] [1754377742.087567390] [route_server]: Destroying bond (route_server) to lifecycle manager.
[lifecycle_manager-21] [INFO] [1754377742.202508544] [lifecycle_manager_navigation]: Deactivating planner_server

Future work that may be required in bullet points

None

For Maintainers:

  • Check that any new parameters added are updated in docs.nav2.org
  • Check that any significant change is added to the migration guide
  • Check that any new features OR changes to existing behaviors are reflected in the tuning guide
  • Check that any new functions have Doxygen added
  • Check that any new features have test coverage
  • Check that any new plugins is added to the plugins page
  • If BT Node, Additionally: add to BT's XML index of nodes for groot, BT package's readme table, and BT library lists
  • Should this be backported to current distributions? If so, tag with backport-*.

Signed-off-by: Sushant Chavan <gitecsvc@gmail.com>
@Sushant-Chavan Sushant-Chavan force-pushed the feature/setup_backward_ros branch from 4d3d62d to 1389e07 Compare July 30, 2025 14:45
Copy link
Contributor

mergify bot commented Jul 30, 2025

@Sushant-Chavan, your PR has failed to build. Please check CI outputs and resolve issues.
You may need to rebase or pull in main due to API changes (or your contribution genuinely fails).

Copy link
Member

@SteveMacenski SteveMacenski left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM. Two questions:

  1. How does this look when a crash occurs? Can you cause one on a normal nav2_bringup composed bringup and let me know (a) the logging output (b) what do the other servers react to it
  2. Did you do any perf testing to check on the runtime difference on this addition? Anything appreciable?

@Sushant-Chavan
Copy link
Contributor Author

Sorry, this PR was meant to be for my fork. Unfortunately I didnt realize that I created an upstream PR until you reviewed it 😞

I am yet to test it properly, so setting this PR as a draft for now. But I realized that using backward_ros with composed node will not work and there is already an open issue in rclcpp for addressing this.

I will perform some tests without node composition and re-request a review with the details you requested :)

@Sushant-Chavan Sushant-Chavan marked this pull request as draft August 1, 2025 15:12
@Sushant-Chavan Sushant-Chavan marked this pull request as ready for review August 5, 2025 08:19
@Sushant-Chavan
Copy link
Contributor Author

Sushant-Chavan commented Aug 5, 2025

I was able to do some tests to see the effects of using backward_ros. I updated the PR description with details of the same, along with answers to your questions :)

what do the other servers react to it

The behavior of other servers was exactly the same in both cases as can be seen in the app logs.

@SteveMacenski
Copy link
Member

SteveMacenski commented Aug 5, 2025

Pull in main and CI should pass now. I hot-fixed an issue with load balancing packages to stay under a 1 hour build time in worst-case situations like this where we rebuild from the ground up

Build nav2 packages with RelWithDebInfo configuration
Start navigation with the use_composition flag set to false, using the command: ros2 launch nav2_bringup tb3_simulation_launch.py headless:=False use_composition:=false

I think adding these instructions to https://docs.nav2.org/tutorials/docs/get_backtrace.html for the backward ros section is important context to add.

What happens if we don't use RelWithDebInfo? Just wanting to know the output and if its useful. I expect it provides some context, yeah?

I realized that using backward_ros with composed node will not work and there is already an ros2/rclcpp#2396 for addressing this

Whats your sense on the likelihood of this being completed?

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

Successfully merging this pull request may close these issues.

2 participants