Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
denoise_layer.hpp
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 #ifndef NAV2_COSTMAP_2D__DENOISE_LAYER_HPP_
16 #define NAV2_COSTMAP_2D__DENOISE_LAYER_HPP_
17 
18 #include "nav2_costmap_2d/layer.hpp"
19 #include "nav2_costmap_2d/denoise/image_processing.hpp"
20 
21 namespace nav2_costmap_2d
22 {
28 class DenoiseLayer : public Layer
29 {
30  friend class DenoiseLayerTester; // For test some private methods using gtest
31 
32 public:
33  DenoiseLayer() = default;
34  ~DenoiseLayer() = default;
35 
39  void reset() override;
40 
44  bool isClearable() override;
45 
51  void updateBounds(
52  double robot_x, double robot_y, double robot_yaw,
53  double * min_x, double * min_y,
54  double * max_x, double * max_y) override;
55 
66  void updateCosts(
67  nav2_costmap_2d::Costmap2D & master_grid,
68  int min_x, int min_y, int max_x, int max_y) override;
69 
70 protected:
76  void onInitialize() override;
77 
78 private:
92  void denoise(Image<uint8_t> & image) const;
93 
101  void removeGroups(Image<uint8_t> & image) const;
102 
109  void removeSinglePixels(Image<uint8_t> & image) const;
114  bool isBackground(uint8_t pixel) const;
115 
116 private:
117  // The border value of group size. Groups of this and larger size will be kept
118  size_t minimal_group_size_{};
119  // Pixels connectivity type. Determines how pixels belonging to the same group can be arranged
120  ConnectivityType group_connectivity_type_{ConnectivityType::Way8};
121  // Memory buffer for temporal image
122  mutable MemoryBuffer buffer_;
123  // Implementing the removal of grouped noise
124  imgproc_impl::GroupsRemover groups_remover_;
125  // Interpret NO_INFORMATION code as obstacle
126  bool no_information_is_obstacle_{};
127 };
128 
129 } // namespace nav2_costmap_2d
130 
131 #endif // NAV2_COSTMAP_2D__DENOISE_LAYER_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
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
Abstract class for layered costmap plugin implementations.
Definition: layer.hpp:59
A memory buffer that can grow to an upper-bounded capacity.
Object to eliminate grouped noise on the image Stores a label tree that is reused.
@ Way8
neighbors pixels are connected horizontally, vertically and diagonally