fix: 修复 TEB local planner 符号链接错误

- 在 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) <noreply@anthropic.com>
This commit is contained in:
Robofish 2026-03-09 14:23:59 +08:00
parent d459b500ba
commit a829de6565
2 changed files with 2 additions and 1 deletions

View File

@ -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) 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) // internal objects (memory management owned)
nav2_util::LifecycleNode::SharedPtr node_; //!< ROS2 lifecycle node pointer
TebVisualizationPtr visualization_; //!< Instance of the visualization class TebVisualizationPtr visualization_; //!< Instance of the visualization class
TimedElasticBand teb_; //!< Actual trajectory object TimedElasticBand teb_; //!< Actual trajectory object
RobotFootprintModelPtr robot_model_; //!< Robot model RobotFootprintModelPtr robot_model_; //!< Robot model

View File

@ -200,7 +200,7 @@ void TebLocalPlannerROS::configure(
auto node = std::dynamic_pointer_cast<nav2_util::LifecycleNode>(nh_.lock()); auto node = std::dynamic_pointer_cast<nav2_util::LifecycleNode>(nh_.lock());
if (!node) { if (!node) {
throw nav2_core::ControllerException( throw nav2_core::PlannerException(
"Failed to cast controller parent node to nav2_util::LifecycleNode"); "Failed to cast controller parent node to nav2_util::LifecycleNode");
} }
logger_ = node->get_logger(); logger_ = node->get_logger();