diff --git a/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/include/teb_local_planner/homotopy_class_planner.h b/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/include/teb_local_planner/homotopy_class_planner.h index 841e630..b25f2ec 100644 --- a/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/include/teb_local_planner/homotopy_class_planner.h +++ b/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/include/teb_local_planner/homotopy_class_planner.h @@ -54,6 +54,7 @@ #include #include +#include #include "teb_local_planner/planner_interface.h" #include "teb_local_planner/teb_config.h" 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 614ccb7..ee3c68c 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 @@ -41,6 +41,7 @@ #include +#include // teb stuff #include "teb_local_planner/teb_config.h" @@ -130,12 +131,12 @@ public: */ TebOptimalPlanner(nav2_util::LifecycleNode::SharedPtr node, const TebConfig& cfg, ObstContainer* obstacles = NULL, TebVisualizationPtr visual = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL); - + /** * @brief Destruct the optimal planner. */ virtual ~TebOptimalPlanner(); - + /** * @brief Initializes the optimal planner * @param node Shared pointer for rclcpp::Node diff --git a/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/optimal_planner.cpp b/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/optimal_planner.cpp index 1ab883f..3c7764a 100644 --- a/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/optimal_planner.cpp +++ b/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/optimal_planner.cpp @@ -64,11 +64,11 @@ namespace teb_local_planner TebOptimalPlanner::TebOptimalPlanner() : cfg_(nullptr), obstacles_(NULL), via_points_(NULL), cost_(HUGE_VAL), prefer_rotdir_(RotType::none), initialized_(false), optimized_(false) -{ +{ } - + TebOptimalPlanner::TebOptimalPlanner(nav2_util::LifecycleNode::SharedPtr node, const TebConfig& cfg, ObstContainer* obstacles, TebVisualizationPtr visual, const ViaPointContainer* via_points) -{ +{ initialize(node, cfg, obstacles, visual, via_points); } @@ -76,7 +76,7 @@ TebOptimalPlanner::~TebOptimalPlanner() { clearGraph(); // free dynamically allocated memory - //if (optimizer_) + //if (optimizer_) // g2o::Factory::destroy(); //g2o::OptimizationAlgorithmFactory::destroy(); //g2o::HyperGraphActionLibrary::destroy();