fix tebplanner
This commit is contained in:
parent
a829de6565
commit
37554e7dd7
@ -54,6 +54,7 @@
|
|||||||
#include <std_msgs/msg/color_rgba.hpp>
|
#include <std_msgs/msg/color_rgba.hpp>
|
||||||
|
|
||||||
#include <rclcpp/rclcpp.hpp>
|
#include <rclcpp/rclcpp.hpp>
|
||||||
|
#include <nav2_util/lifecycle_node.hpp>
|
||||||
|
|
||||||
#include "teb_local_planner/planner_interface.h"
|
#include "teb_local_planner/planner_interface.h"
|
||||||
#include "teb_local_planner/teb_config.h"
|
#include "teb_local_planner/teb_config.h"
|
||||||
|
|||||||
@ -41,6 +41,7 @@
|
|||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
|
#include <nav2_util/lifecycle_node.hpp>
|
||||||
|
|
||||||
// teb stuff
|
// teb stuff
|
||||||
#include "teb_local_planner/teb_config.h"
|
#include "teb_local_planner/teb_config.h"
|
||||||
@ -130,12 +131,12 @@ public:
|
|||||||
*/
|
*/
|
||||||
TebOptimalPlanner(nav2_util::LifecycleNode::SharedPtr node, const TebConfig& cfg, ObstContainer* obstacles = NULL,
|
TebOptimalPlanner(nav2_util::LifecycleNode::SharedPtr node, const TebConfig& cfg, ObstContainer* obstacles = NULL,
|
||||||
TebVisualizationPtr visual = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL);
|
TebVisualizationPtr visual = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Destruct the optimal planner.
|
* @brief Destruct the optimal planner.
|
||||||
*/
|
*/
|
||||||
virtual ~TebOptimalPlanner();
|
virtual ~TebOptimalPlanner();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Initializes the optimal planner
|
* @brief Initializes the optimal planner
|
||||||
* @param node Shared pointer for rclcpp::Node
|
* @param node Shared pointer for rclcpp::Node
|
||||||
|
|||||||
@ -64,11 +64,11 @@ namespace teb_local_planner
|
|||||||
|
|
||||||
TebOptimalPlanner::TebOptimalPlanner() : cfg_(nullptr), obstacles_(NULL), via_points_(NULL), cost_(HUGE_VAL), prefer_rotdir_(RotType::none),
|
TebOptimalPlanner::TebOptimalPlanner() : cfg_(nullptr), obstacles_(NULL), via_points_(NULL), cost_(HUGE_VAL), prefer_rotdir_(RotType::none),
|
||||||
initialized_(false), optimized_(false)
|
initialized_(false), optimized_(false)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
TebOptimalPlanner::TebOptimalPlanner(nav2_util::LifecycleNode::SharedPtr node, const TebConfig& cfg, ObstContainer* obstacles, TebVisualizationPtr visual, const ViaPointContainer* via_points)
|
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);
|
initialize(node, cfg, obstacles, visual, via_points);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -76,7 +76,7 @@ TebOptimalPlanner::~TebOptimalPlanner()
|
|||||||
{
|
{
|
||||||
clearGraph();
|
clearGraph();
|
||||||
// free dynamically allocated memory
|
// free dynamically allocated memory
|
||||||
//if (optimizer_)
|
//if (optimizer_)
|
||||||
// g2o::Factory::destroy();
|
// g2o::Factory::destroy();
|
||||||
//g2o::OptimizationAlgorithmFactory::destroy();
|
//g2o::OptimizationAlgorithmFactory::destroy();
|
||||||
//g2o::HyperGraphActionLibrary::destroy();
|
//g2o::HyperGraphActionLibrary::destroy();
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user