Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
costmap_downsampler.cpp
1 // Copyright (c) 2020, Carlos Luis
2 // Copyright (c) 2020, Samsung Research America
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License. Reserved.
15 
16 #include "nav2_smac_planner/costmap_downsampler.hpp"
17 
18 #include <string>
19 #include <memory>
20 #include <algorithm>
21 
22 namespace nav2_smac_planner
23 {
24 
26 : _costmap(nullptr),
27  _downsampled_costmap(nullptr),
28  _downsampled_costmap_pub(nullptr)
29 {
30 }
31 
33 {
34 }
35 
37  const nav2_util::LifecycleNode::WeakPtr & node,
38  const std::string & global_frame,
39  const std::string & topic_name,
40  nav2_costmap_2d::Costmap2D * const costmap,
41  const unsigned int & downsampling_factor,
42  const bool & use_min_cost_neighbor)
43 {
44  _costmap = costmap;
45  _downsampling_factor = downsampling_factor;
46  _use_min_cost_neighbor = use_min_cost_neighbor;
48 
49  _downsampled_costmap = std::make_unique<nav2_costmap_2d::Costmap2D>(
50  _downsampled_size_x, _downsampled_size_y, _downsampled_resolution,
51  _costmap->getOriginX(), _costmap->getOriginY(), UNKNOWN_COST);
52 
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);
56  }
57 }
58 
60 {
61  if (_downsampled_costmap_pub) {
62  _downsampled_costmap_pub->on_activate();
63  }
64 }
65 
67 {
68  if (_downsampled_costmap_pub) {
69  _downsampled_costmap_pub->on_deactivate();
70  }
71 }
72 
74 {
75  _costmap = nullptr;
76  _downsampled_costmap.reset();
77  _downsampled_costmap_pub.reset();
78 }
79 
81  const unsigned int & downsampling_factor)
82 {
83  _downsampling_factor = downsampling_factor;
85 
86  // Adjust costmap size if needed
87  if (_downsampled_costmap->getSizeInCellsX() != _downsampled_size_x ||
88  _downsampled_costmap->getSizeInCellsY() != _downsampled_size_y ||
89  _downsampled_costmap->getResolution() != _downsampled_resolution)
90  {
91  resizeCostmap();
92  }
93 
94  // Assign costs
95  for (unsigned int i = 0; i < _downsampled_size_x; ++i) {
96  for (unsigned int j = 0; j < _downsampled_size_y; ++j) {
97  setCostOfCell(i, j);
98  }
99  }
100 
101  if (_downsampled_costmap_pub) {
102  _downsampled_costmap_pub->publishCostmap();
103  }
104  return _downsampled_costmap.get();
105 }
106 
108 {
109  _size_x = _costmap->getSizeInCellsX();
110  _size_y = _costmap->getSizeInCellsY();
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();
114 }
115 
117 {
118  _downsampled_costmap->resizeMap(
119  _downsampled_size_x,
120  _downsampled_size_y,
121  _downsampled_resolution,
122  _costmap->getOriginX(),
123  _costmap->getOriginY());
124 }
125 
127  const unsigned int & new_mx,
128  const unsigned int & new_my)
129 {
130  unsigned int mx, 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;
134 
135  for (unsigned int i = 0; i < _downsampling_factor; ++i) {
136  mx = x_offset + i;
137  if (mx >= _size_x) {
138  continue;
139  }
140  for (unsigned int j = 0; j < _downsampling_factor; ++j) {
141  my = y_offset + j;
142  if (my >= _size_y) {
143  continue;
144  }
145  cost = _use_min_cost_neighbor ?
146  std::min(cost, _costmap->getCost(mx, my)) :
147  std::max(cost, _costmap->getCost(mx, my));
148  }
149  }
150 
151  _downsampled_costmap->setCost(new_mx, new_my, cost);
152 }
153 
154 } // namespace nav2_smac_planner
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:264
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:576
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:546
double getOriginY() const
Accessor for the y origin of the costmap.
Definition: costmap_2d.cpp:571
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:551
double getOriginX() const
Accessor for the x origin of the costmap.
Definition: costmap_2d.cpp:566
~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 updateCostmapSize()
Update the sizes X-Y of the costmap and its downsampled version.
void on_configure(const nav2_util::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 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.