datetime:2025/06/03 14:56
author:nzb

使用GDB调试ROS2程序

我们使用 backward_ros 功能包来快速实现用 GDB 调试 ROS2 程序。

backward_ros 功能包介绍

backward_ros功能包是对backward-cpp包的ROS2封装,以便可以简单快速地使用GDB工具。

backward-cpp包的介绍可以查看其仓库:

使用 backward_ros 功能包实现 GDB 调试 ROS2 程序只需下面三个步骤:

  • 添加backward_rospackage.xml文件。
<depend>backward_ros</depend>
  • 添加backward_rosCMakeLists.txt文件中。
find_package(backward_ros REQUIRED)
  • 使用 Debug 或者 RelWithDebInfo 选项编译程序。
# Debug
colcon build --packages-select  simple_walk_controller --mixin debug
# RelWithDebInfo
colcon build --packages-select  simple_walk_controller --mixin rel-with-deb-info
  • 或者在CMakeLists.txt文件中添加参数。
set(CMAKE_BUILD_TYPE "Debug")
set(CMAKE_BUILD_TYPE "RelWithDebInfo")
set(CMAKE_BUILD_TYPE "Release")

示例

  • colcon build --packages-select simple_walk_controller --mixin release
blues@pasture-10:~/vscode_projects/cy1_ws$ ros2 run  simple_walk_controller simple_walk_controller 
[INFO] [1748935276.221676740] [orca_controller]: Starting orca_controller
Stack trace (most recent call last):
#11   Object "", at 0xffffffffffffffff, in 
#10   Object "/home/blues/vscode_projects/cy1_ws/install/simple_walk_controller/lib/simple_walk_controller/simple_walk_controller", at 0x648c61f9a8a4, in _start
#9    Source "../csu/libc-start.c", line 392, in __libc_start_main_impl [0x7008a2629e3f]
#8    Source "../sysdeps/nptl/libc_start_call_main.h", line 58, in __libc_start_call_main [0x7008a2629d8f]
#7    Object "/home/blues/vscode_projects/cy1_ws/install/simple_walk_controller/lib/simple_walk_controller/simple_walk_controller", at 0x648c61f9a712, in main
#6    Object "/opt/ros/humble/lib/librclcpp.so", at 0x7008a44e5c8e, in rclcpp::spin(std::shared_ptr<rclcpp::Node>)
#5    Object "/opt/ros/humble/lib/librclcpp.so", at 0x7008a44e5b94, in rclcpp::spin(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>)
#4    Object "/opt/ros/humble/lib/librclcpp.so", at 0x7008a44e597f, in rclcpp::executors::SingleThreadedExecutor::spin()
#3    Object "/opt/ros/humble/lib/librclcpp.so", at 0x7008a44de030, in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&)
#2    Object "/home/blues/vscode_projects/cy1_ws/install/simple_walk_controller/lib/simple_walk_controller/simple_walk_controller", at 0x648c61fa3d84, in rclcpp::GenericTimer<std::_Bind<void (OrcaController::*(OrcaController*))()>, (void*)0>::execute_callback()
#1    Object "/home/blues/vscode_projects/cy1_ws/install/simple_walk_controller/lib/simple_walk_controller/simple_walk_controller", at 0x648c61fa2a5f, in OrcaController::control_loop()
#0    Object "/home/blues/vscode_projects/cy1_ws/install/simple_walk_controller/lib/simple_walk_controller/simple_walk_controller", at 0x648c61f9cc05, in OrcaController::send_action(std::vector<std::vector<float, std::allocator<float> >, std::allocator<std::vector<float, std::allocator<float> > > > const&, std::vector<float, std::allocator<float> > const&, std::vector<float, std::allocator<float> > const&, std::vector<float, std::allocator<float> > const&)
Segmentation fault (Address not mapped to object [0x8])
[ros2run]: Segmentation fault
  • colcon build --packages-select simple_walk_controller --mixin debug
blues@pasture-10:~/vscode_projects/cy1_ws$ ros2 run  simple_walk_controller simple_walk_controller 
[INFO] [1748935389.556873639] [orca_controller]: Starting orca_controller
Stack trace (most recent call last):
#18   Object "", at 0xffffffffffffffff, in 
#17   Object "/home/blues/vscode_projects/cy1_ws/install/simple_walk_controller/lib/simple_walk_controller/simple_walk_controller", at 0x6526cae464e4, in _start
#16   Source "../csu/libc-start.c", line 392, in __libc_start_main_impl [0x744a24629e3f]
#15   Source "../sysdeps/nptl/libc_start_call_main.h", line 58, in __libc_start_call_main [0x744a24629d8f]
#14   Source "/home/blues/vscode_projects/cy1_ws/src/simple_walk_controller/src/simple_walk_controller.cpp", line 456, in main [0x6526cae4bc34]
        453:     rclcpp::init(argc, argv);
        454:     auto node = std::make_shared<OrcaController>();
        455:     node->initialize();
      > 456:     rclcpp::spin(node);
        457:     rclcpp::shutdown();
        458:     return 0;
        459: }
#13   Object "/opt/ros/humble/lib/librclcpp.so", at 0x744a263acc8e, in rclcpp::spin(std::shared_ptr<rclcpp::Node>)
#12   Object "/opt/ros/humble/lib/librclcpp.so", at 0x744a263acb94, in rclcpp::spin(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>)
#11   Object "/opt/ros/humble/lib/librclcpp.so", at 0x744a263ac97f, in rclcpp::executors::SingleThreadedExecutor::spin()
#10   Object "/opt/ros/humble/lib/librclcpp.so", at 0x744a263a5030, in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&)
#9    Source "/opt/ros/humble/include/rclcpp/rclcpp/timer.hpp", line 230, in execute_callback [0x6526cae8b1d8]
        227:   execute_callback() override
        228:   {
        229:     TRACEPOINT(callback_start, static_cast<const void *>(&callback_), false);
      > 230:     execute_callback_delegate<>();
        231:     TRACEPOINT(callback_end, static_cast<const void *>(&callback_));
        232:   }
#8    Source "/opt/ros/humble/include/rclcpp/rclcpp/timer.hpp", line 244, in execute_callback_delegate<> [0x6526cae8c23f]
        241:   void
        242:   execute_callback_delegate()
        243:   {
      > 244:     callback_();
        245:   }
        246: 
        247:   template<
#7    Source "/usr/include/c++/11/functional", line 503, in operator()<> [0x6526cae8cbe0]
        500:    _Result
        501:    operator()(_Args&&... __args)
        502:    {
      > 503:      return this->__call<_Result>(
        504:          std::forward_as_tuple(std::forward<_Args>(__args)...),
        505:          _Bound_indexes());
        506:    }
#6    Source "/usr/include/c++/11/functional", line 420, in __call<void, 0> [0x6526cae8cf34]
        417:    _Result
        418:    __call(tuple<_Args...>&& __args, _Index_tuple<_Indexes...>)
        419:    {
      > 420:      return std::__invoke(_M_f,
        421:          _Mu<_Bound_args>()(std::get<_Indexes>(_M_bound_args), __args)...
        422:          );
        423:    }
#5    Source "/usr/include/c++/11/bits/invoke.h", line 96, in __invoke<void (OrcaController::*&)(), OrcaController*&> [0x6526cae8d1be]
         93:       using __result = __invoke_result<_Callable, _Args...>;
         94:       using __type = typename __result::type;
         95:       using __tag = typename __result::__invoke_type;
      >  96:       return std::__invoke_impl<__type>(__tag{}, std::forward<_Callable>(__fn),
         97:                                    std::forward<_Args>(__args)...);
         98:     }
#4    Source "/usr/include/c++/11/bits/invoke.h", line 74, in __invoke_impl<void, void (OrcaController::*&)(), OrcaController*&> [0x6526cae8d67b]
         71:     __invoke_impl(__invoke_memfun_deref, _MemFun&& __f, _Tp&& __t,
         72:              _Args&&... __args)
         73:     {
      >  74:       return ((*std::forward<_Tp>(__t)).*__f)(std::forward<_Args>(__args)...);
         75:     }
         76: 
         77:   template<typename _Res, typename _MemPtr, typename _Tp>
#3    Source "/home/blues/vscode_projects/cy1_ws/src/simple_walk_controller/src/simple_walk_controller.cpp", line 173, in control_loop [0x6526cae4992d]
        170:     switch (fsm_->getCurrentState())
        171:     {
        172:     case orca_fsm::State::Passive:
      > 173:         send_action(ptargets, std::vector<float>(28, 0.0f), std::vector<float>(28, 0.0f));
        174:         reset();
        175:         step_data_.reset();
        176:         break;
#2    Source "/home/blues/vscode_projects/cy1_ws/src/simple_walk_controller/src/simple_walk_controller.cpp", line 339, in send_action [0x6526cae4aa8a]
        336:     std::copy(d_gain.begin(), d_gain.end(), extended_d.begin());
        337: 
        338:     // 获取最终动作值
      > 339:     std::vector<float> final_action = targets[0]; // 假设 cmd 至少有一个元素
        340: 
        341:     std::vector<float> p{final_action.begin(), final_action.end()};
        342:     std::vector<float> d{final_action.begin(), final_action.end()};
#1    Source "/usr/include/c++/11/bits/stl_vector.h", line 555, in vector [0x6526cae58b01]
        552:        */
        553:       vector(const vector& __x)
        554:       : _Base(__x.size(),
      > 555:    _Alloc_traits::_S_select_on_copy(__x._M_get_Tp_allocator()))
        556:       {
        557:    this->_M_impl._M_finish =
        558:      std::__uninitialized_copy_a(__x.begin(), __x.end(),
#0    Source "/usr/include/c++/11/bits/stl_vector.h", line 919, in size [0x6526cae57bb6]
        916:       /**  Returns the number of elements in the %vector.  */
        917:       size_type
        918:       size() const _GLIBCXX_NOEXCEPT
      > 919:       { return size_type(this->_M_impl._M_finish - this->_M_impl._M_start); }
        920: 
        921:       /**  Returns the size() of the largest possible %vector.  */
        922:       size_type
Segmentation fault (Address not mapped to object [0x8])
[ros2run]: Segmentation fault

results matching ""

    No results matching ""