15 #include "nav2_costmap_2d/denoise_layer.hpp"
22 #include "rclcpp/rclcpp.hpp"
37 const auto node = node_.lock();
40 throw std::runtime_error(
"DenoiseLayer::onInitialize: Failed to lock node");
42 node->get_parameter(name_ +
"." +
"enabled", enabled_);
44 auto getInt = [&](
const std::string & parameter_name) {
46 node->get_parameter(name_ +
"." + parameter_name, param);
50 const int minimal_group_size_param = getInt(
"minimal_group_size");
52 if (minimal_group_size_param <= 1) {
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;
60 minimal_group_size_ =
static_cast<size_t>(minimal_group_size_param);
63 const int group_connectivity_type_param = getInt(
"group_connectivity_type");
65 if (group_connectivity_type_param == 4) {
70 if (group_connectivity_type_param != 8) {
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);
97 double ,
double ,
double ,
99 double * ,
double * ) {}
109 if (min_x >= max_x || min_y >= max_y) {
112 no_information_is_obstacle_ = master_grid.
getDefaultValue() != NO_INFORMATION;
115 unsigned char * master_array = master_grid.
getCharMap();
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);
124 }
catch (std::exception & ex) {
125 RCLCPP_ERROR(logger_,
"%s", (std::string(
"Inner error: ") + ex.what()).c_str());
138 if (minimal_group_size_ <= 1) {
142 if (minimal_group_size_ == 2) {
144 removeSinglePixels(image);
152 DenoiseLayer::removeGroups(Image<uint8_t> & image)
const
155 image, buffer_, group_connectivity_type_, minimal_group_size_,
156 [
this](uint8_t pixel) {
return isBackground(pixel);});
160 DenoiseLayer::removeSinglePixels(Image<uint8_t> & image)
const
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());
169 if (!no_information_is_obstacle_) {
170 auto replace_to_free = [](uint8_t v) {
171 return v == NO_INFORMATION ? FREE_SPACE : v;
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))
179 return *std::max_element(buf.begin(), buf.end());
181 dilate(image, max_neighbors_image, group_connectivity_type_, max);
183 auto max = [](
const std::initializer_list<uint8_t> lst) {
184 return std::max(lst);
186 dilate(image, max_neighbors_image, group_connectivity_type_, max);
189 max_neighbors_image.convert(
190 image, [
this](uint8_t maxNeighbor, uint8_t & img) {
191 if (!isBackground(img) && isBackground(maxNeighbor)) {
197 bool DenoiseLayer::isBackground(uint8_t pixel)
const
200 pixel == LETHAL_OBSTACLE ||
201 pixel == INSCRIBED_INFLATED_OBSTACLE ||
202 (pixel == NO_INFORMATION && no_information_is_obstacle_);
210 #include "pluginlib/class_list_macros.hpp"
A 2D costmap provides a mapping between points in the world and their associated "costs".
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
unsigned char getDefaultValue()
Get the default background value of the costmap.
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...
Abstract class for layered costmap plugin implementations.
void declareParameter(const std::string ¶m_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
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.