From a829de6565112242fcd0db4ae03bded35deec0ef Mon Sep 17 00:00:00 2001 From: Robofish <1683502971@qq.com> Date: Mon, 9 Mar 2026 14:23:59 +0800 Subject: [PATCH] =?UTF-8?q?fix:=20=E4=BF=AE=E5=A4=8D=20TEB=20local=20plann?= =?UTF-8?q?er=20=E7=AC=A6=E5=8F=B7=E9=93=BE=E6=8E=A5=E9=94=99=E8=AF=AF?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - 在 optimal_planner.h 中添加缺失的 node_ 成员变量声明 - 修复 teb_local_planner_ros.cpp 中的异常类型(ControllerException -> PlannerException) 这修复了启动时的符号未定义错误: undefined symbol: _ZN17teb_local_planner17TebOptimalPlannerC1E... Co-Authored-By: Claude Opus 4.6 (1M context) --- .../include/teb_local_planner/optimal_planner.h | 1 + .../teb_local_planner/src/teb_local_planner_ros.cpp | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/include/teb_local_planner/optimal_planner.h b/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/include/teb_local_planner/optimal_planner.h index f76efe8..614ccb7 100644 --- a/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/include/teb_local_planner/optimal_planner.h +++ b/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/include/teb_local_planner/optimal_planner.h @@ -710,6 +710,7 @@ protected: RotType prefer_rotdir_; //!< Store whether to prefer a specific initial rotation in optimization (might be activated in case the robot oscillates) // internal objects (memory management owned) + nav2_util::LifecycleNode::SharedPtr node_; //!< ROS2 lifecycle node pointer TebVisualizationPtr visualization_; //!< Instance of the visualization class TimedElasticBand teb_; //!< Actual trajectory object RobotFootprintModelPtr robot_model_; //!< Robot model diff --git a/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/teb_local_planner_ros.cpp b/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/teb_local_planner_ros.cpp index 5374a92..5d8294b 100644 --- a/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/teb_local_planner_ros.cpp +++ b/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/teb_local_planner_ros.cpp @@ -200,7 +200,7 @@ void TebLocalPlannerROS::configure( auto node = std::dynamic_pointer_cast(nh_.lock()); if (!node) { - throw nav2_core::ControllerException( + throw nav2_core::PlannerException( "Failed to cast controller parent node to nav2_util::LifecycleNode"); } logger_ = node->get_logger();