16 #include "nav2_smac_planner/costmap_downsampler.hpp"
22 namespace nav2_smac_planner
27 _downsampled_costmap(nullptr),
28 _downsampled_costmap_pub(nullptr)
37 const nav2::LifecycleNode::WeakPtr & node,
38 const std::string & global_frame,
39 const std::string & topic_name,
41 const unsigned int & downsampling_factor,
42 const bool & use_min_cost_neighbor)
45 _downsampling_factor = downsampling_factor;
46 _use_min_cost_neighbor = use_min_cost_neighbor;
49 _downsampled_costmap = std::make_unique<nav2_costmap_2d::Costmap2D>(
50 _downsampled_size_x, _downsampled_size_y, _downsampled_resolution,
53 if (!node.expired()) {
54 _downsampled_costmap_pub = std::make_unique<nav2_costmap_2d::Costmap2DPublisher>(
55 node, _downsampled_costmap.get(), global_frame, topic_name,
false);
61 if (_downsampled_costmap_pub) {
62 _downsampled_costmap_pub->on_activate();
68 if (_downsampled_costmap_pub) {
69 _downsampled_costmap_pub->on_deactivate();
76 _downsampled_costmap.reset();
77 _downsampled_costmap_pub.reset();
81 const unsigned int & downsampling_factor)
83 _downsampling_factor = downsampling_factor;
87 if (_downsampled_costmap->getSizeInCellsX() != _downsampled_size_x ||
88 _downsampled_costmap->getSizeInCellsY() != _downsampled_size_y ||
89 _downsampled_costmap->getResolution() != _downsampled_resolution)
95 for (
unsigned int i = 0; i < _downsampled_size_x; ++i) {
96 for (
unsigned int j = 0; j < _downsampled_size_y; ++j) {
101 if (_downsampled_costmap_pub) {
102 _downsampled_costmap_pub->publishCostmap();
104 return _downsampled_costmap.get();
111 _downsampled_size_x = ceil(
static_cast<float>(_size_x) / _downsampling_factor);
112 _downsampled_size_y = ceil(
static_cast<float>(_size_y) / _downsampling_factor);
113 _downsampled_resolution = _downsampling_factor * _costmap->
getResolution();
118 _downsampled_costmap->resizeMap(
121 _downsampled_resolution,
127 const unsigned int & new_mx,
128 const unsigned int & new_my)
131 unsigned char cost = _use_min_cost_neighbor ? 255 : 0;
132 unsigned int x_offset = new_mx * _downsampling_factor;
133 unsigned int y_offset = new_my * _downsampling_factor;
135 for (
unsigned int i = 0; i < _downsampling_factor; ++i) {
140 for (
unsigned int j = 0; j < _downsampling_factor; ++j) {
145 cost = _use_min_cost_neighbor ?
146 std::min(cost, _costmap->
getCost(mx, my)) :
147 std::max(cost, _costmap->
getCost(mx, my));
151 _downsampled_costmap->setCost(new_mx, new_my, cost);
A 2D costmap provides a mapping between points in the world and their associated "costs".
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
double getResolution() const
Accessor for the resolution of the costmap.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
double getOriginY() const
Accessor for the y origin of the costmap.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
double getOriginX() const
Accessor for the x origin of the costmap.
~CostmapDownsampler()
A destructor for CostmapDownsampler.
CostmapDownsampler()
A constructor for CostmapDownsampler.
void resizeCostmap()
Resize the downsampled costmap. Used in case the costmap changes and we need to update the downsample...
void on_activate()
Activate the publisher of the downsampled costmap.
void on_deactivate()
Deactivate the publisher of the downsampled costmap.
void on_cleanup()
Cleanup the publisher of the downsampled costmap.
void on_configure(const nav2::LifecycleNode::WeakPtr &node, const std::string &global_frame, const std::string &topic_name, nav2_costmap_2d::Costmap2D *const costmap, const unsigned int &downsampling_factor, const bool &use_min_cost_neighbor=false)
Configure the downsampled costmap object and the ROS publisher.
void updateCostmapSize()
Update the sizes X-Y of the costmap and its downsampled version.
void setCostOfCell(const unsigned int &new_mx, const unsigned int &new_my)
Explore all subcells of the original costmap and assign the max cost to the new (downsampled) cell.
nav2_costmap_2d::Costmap2D * downsample(const unsigned int &downsampling_factor)
Downsample the given costmap by the downsampling factor, and publish the downsampled costmap.