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();