Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
denoise_layer.cpp
1 // Copyright (c) 2023 Andrey Ryzhikov
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "nav2_costmap_2d/denoise_layer.hpp"
16 
17 #include <string>
18 #include <vector>
19 #include <algorithm>
20 #include <memory>
21 
22 #include "rclcpp/rclcpp.hpp"
23 
24 namespace nav2_costmap_2d
25 {
26 
27 void
29 {
30  // Enable/disable plugin
31  declareParameter("enabled", rclcpp::ParameterValue(true));
32  // Smaller groups should be filtered
33  declareParameter("minimal_group_size", rclcpp::ParameterValue(2));
34  // Pixels connectivity type
35  declareParameter("group_connectivity_type", rclcpp::ParameterValue(8));
36 
37  const auto node = node_.lock();
38 
39  if (!node) {
40  throw std::runtime_error("DenoiseLayer::onInitialize: Failed to lock node");
41  }
42  node->get_parameter(name_ + "." + "enabled", enabled_);
43 
44  auto getInt = [&](const std::string & parameter_name) {
45  int param{};
46  node->get_parameter(name_ + "." + parameter_name, param);
47  return param;
48  };
49 
50  const int minimal_group_size_param = getInt("minimal_group_size");
51 
52  if (minimal_group_size_param <= 1) {
53  RCLCPP_WARN(
54  logger_,
55  "DenoiseLayer::onInitialize(): param minimal_group_size: %i."
56  " A value of 1 or less means that all map cells will be left as they are.",
57  minimal_group_size_param);
58  minimal_group_size_ = 1;
59  } else {
60  minimal_group_size_ = static_cast<size_t>(minimal_group_size_param);
61  }
62 
63  const int group_connectivity_type_param = getInt("group_connectivity_type");
64 
65  if (group_connectivity_type_param == 4) {
66  group_connectivity_type_ = ConnectivityType::Way4;
67  } else {
68  group_connectivity_type_ = ConnectivityType::Way8;
69 
70  if (group_connectivity_type_param != 8) {
71  RCLCPP_WARN(
72  logger_, "DenoiseLayer::onInitialize(): param group_connectivity_type: %i."
73  " Possible values are 4 (neighbors pixels are connected horizontally and vertically) "
74  "or 8 (neighbors pixels are connected horizontally, vertically and diagonally)."
75  "The default value 8 will be used",
76  group_connectivity_type_param);
77  }
78  }
79 
80  current_ = true;
81 }
82 
83 void
85 {
86  current_ = false;
87 }
88 
89 bool
91 {
92  return false;
93 }
94 
95 void
97  double /*robot_x*/, double /*robot_y*/, double /*robot_yaw*/,
98  double * /*min_x*/, double * /*min_y*/,
99  double * /*max_x*/, double * /*max_y*/) {}
100 
101 void
103  nav2_costmap_2d::Costmap2D & master_grid, int min_x, int min_y, int max_x, int max_y)
104 {
105  if (!enabled_) {
106  return;
107  }
108 
109  if (min_x >= max_x || min_y >= max_y) {
110  return;
111  }
112  no_information_is_obstacle_ = master_grid.getDefaultValue() != NO_INFORMATION;
113 
114  // wrap roi_image over existing costmap2d buffer
115  unsigned char * master_array = master_grid.getCharMap();
116  const int step = static_cast<int>(master_grid.getSizeInCellsX());
117 
118  const size_t width = max_x - min_x;
119  const size_t height = max_y - min_y;
120  Image<uint8_t> roi_image(height, width, master_array + min_y * step + min_x, step);
121 
122  try {
123  denoise(roi_image);
124  } catch (std::exception & ex) {
125  RCLCPP_ERROR(logger_, "%s", (std::string("Inner error: ") + ex.what()).c_str());
126  }
127 
128  current_ = true;
129 }
130 
131 void
132 DenoiseLayer::denoise(Image<uint8_t> & image) const
133 {
134  if (image.empty()) {
135  return;
136  }
137 
138  if (minimal_group_size_ <= 1) {
139  return; // A smaller group cannot exist. No one pixel will be changed
140  }
141 
142  if (minimal_group_size_ == 2) {
143  // Performs fast filtration based on erosion function
144  removeSinglePixels(image);
145  } else {
146  // Performs a slower segmentation-based operation
147  removeGroups(image);
148  }
149 }
150 
151 void
152 DenoiseLayer::removeGroups(Image<uint8_t> & image) const
153 {
154  groups_remover_.removeGroups(
155  image, buffer_, group_connectivity_type_, minimal_group_size_,
156  [this](uint8_t pixel) {return isBackground(pixel);});
157 }
158 
159 void
160 DenoiseLayer::removeSinglePixels(Image<uint8_t> & image) const
161 {
162  // Building a map of 4 or 8-connected neighbors.
163  // The pixel of the map is 255 if there is an obstacle nearby
164  uint8_t * buf = buffer_.get<uint8_t>(image.rows() * image.columns());
165  Image<uint8_t> max_neighbors_image(image.rows(), image.columns(), buf, image.columns());
166 
167  // If NO_INFORMATION (=255) isn't obstacle, we can't use a simple max() to check
168  // any obstacle nearby. In this case, we interpret NO_INFORMATION as an empty space.
169  if (!no_information_is_obstacle_) {
170  auto replace_to_free = [](uint8_t v) {
171  return v == NO_INFORMATION ? FREE_SPACE : v;
172  };
173  auto max = [&](const std::initializer_list<uint8_t> lst) {
174  std::array<uint8_t, 3> buf = {
175  replace_to_free(*lst.begin()),
176  replace_to_free(*(lst.begin() + 1)),
177  replace_to_free(*(lst.begin() + 2))
178  };
179  return *std::max_element(buf.begin(), buf.end());
180  };
181  dilate(image, max_neighbors_image, group_connectivity_type_, max);
182  } else {
183  auto max = [](const std::initializer_list<uint8_t> lst) {
184  return std::max(lst);
185  };
186  dilate(image, max_neighbors_image, group_connectivity_type_, max);
187  }
188 
189  max_neighbors_image.convert(
190  image, [this](uint8_t maxNeighbor, uint8_t & img) {
191  if (!isBackground(img) && isBackground(maxNeighbor)) {
192  img = FREE_SPACE;
193  }
194  });
195 }
196 
197 bool DenoiseLayer::isBackground(uint8_t pixel) const
198 {
199  bool is_obstacle =
200  pixel == LETHAL_OBSTACLE ||
201  pixel == INSCRIBED_INFLATED_OBSTACLE ||
202  (pixel == NO_INFORMATION && no_information_is_obstacle_);
203  return !is_obstacle;
204 }
205 
206 } // namespace nav2_costmap_2d
207 
208 // This is the macro allowing a DenoiseLayer class
209 // to be registered in order to be dynamically loadable of base type nav2_costmap_2d::Layer.
210 #include "pluginlib/class_list_macros.hpp"
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition: costmap_2d.cpp:261
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:501
unsigned char getDefaultValue()
Get the default background value of the costmap.
Definition: costmap_2d.hpp:289
Layer filters noise-induced standalone obstacles (white costmap pixels) or small obstacles groups.
void updateCosts(nav2_costmap_2d::Costmap2D &master_grid, int min_x, int min_y, int max_x, int max_y) override
Filters noise-induced obstacles in the selected region of the costmap The method is called when costm...
void onInitialize() override
Initializes the layer on startup This method is called at the end of plugin initialization....
void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y) override
Reports that no expansion is required The method is called to ask the plugin: which area of costmap i...
bool isClearable() override
Reports that no clearing operation is required.
void reset() override
Reset this layer.
Image with pixels of type T Сan own data, be a wrapper over some memory buffer, or refer to a fragmen...
Definition: image.hpp:33
bool empty() const
Definition: image.hpp:67
Abstract class for layered costmap plugin implementations.
Definition: layer.hpp:59
void declareParameter(const std::string &param_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
Definition: layer.cpp:76
T * get(std::size_t count)
Return a pointer to an uninitialized array of count elements Delete the old block of memory and alloc...
void removeGroups(Image< uint8_t > &image, MemoryBuffer &buffer, ConnectivityType group_connectivity_type, size_t minimal_group_size, const IsBg &is_background) const
Calls removeGroupsPickLabelType with the Way4/Way8 template parameter based on the runtime value of g...
@ Way4
neighbors pixels are connected horizontally and vertically
@ Way8
neighbors pixels are connected horizontally, vertically and diagonally
void dilate(const Image< uint8_t > &input, Image< uint8_t > &output, ConnectivityType connectivity, Max &&max_function)
Perform morphological dilation.