1738_29102025
This commit is contained in:
@@ -2,14 +2,13 @@
|
||||
#ifndef COSTMAP_2D_INFLATION_LAYER_H_
|
||||
#define COSTMAP_2D_INFLATION_LAYER_H_
|
||||
|
||||
// #include <ros/ros.h>
|
||||
#include <costmap_2d/layer.h>
|
||||
#include <costmap_2d/layered_costmap.h>
|
||||
// #include <costmap_2d/InflationPluginConfig.h>
|
||||
// #include <dynamic_reconfigure/server.h>
|
||||
#include <boost/thread.hpp>
|
||||
#include <boost/dll/alias.hpp>
|
||||
|
||||
#include <stdexcept>
|
||||
#include <iostream>
|
||||
#include <yaml-cpp/yaml.h>
|
||||
|
||||
namespace costmap_2d
|
||||
{
|
||||
@@ -46,8 +45,6 @@ public:
|
||||
virtual ~InflationLayer()
|
||||
{
|
||||
deleteKernels();
|
||||
// if (dsrv_)
|
||||
// delete dsrv_;
|
||||
if (seen_)
|
||||
delete[] seen_;
|
||||
}
|
||||
@@ -155,8 +152,7 @@ private:
|
||||
double** cached_distances_;
|
||||
double last_min_x_, last_min_y_, last_max_x_, last_max_y_;
|
||||
|
||||
// dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig> *dsrv_;
|
||||
// void reconfigureCB(costmap_2d::InflationPluginConfig &config, uint32_t level);
|
||||
bool getParams();
|
||||
|
||||
bool need_reinflation_; ///< Indicates that the entire costmap should be reinflated next time around.
|
||||
};
|
||||
|
||||
Reference in New Issue
Block a user