Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
image_processing.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__IMAGE_PROCESSING_HPP_
16 #define NAV2_COSTMAP_2D__DENOISE__IMAGE_PROCESSING_HPP_
17 
18 #include "image.hpp"
19 #include <algorithm>
20 #include <vector>
21 #include <array>
22 #include <memory>
23 #include <limits>
24 
25 namespace nav2_costmap_2d
26 {
27 
33 enum class ConnectivityType : int
34 {
36  Way4 = 4,
38  Way8 = 8
39 };
40 
45 {
46 public:
48  inline ~MemoryBuffer() {reset();}
57  template<class T>
58  T * get(std::size_t count);
59 
60 private:
61  inline void reset();
62  inline void allocate(size_t bytes);
63 
64 private:
65  void * data_{};
66  size_t size_{};
67 };
68 
69 // forward declarations
70 namespace imgproc_impl
71 {
72 template<class Label>
73 class EquivalenceLabelTrees;
74 
75 template<class AggregateFn>
76 void morphologyOperation(
77  const Image<uint8_t> & input, Image<uint8_t> & output,
78  const Image<uint8_t> & shape, AggregateFn aggregate);
79 
80 using ShapeBuffer3x3 = std::array<uint8_t, 9>;
81 inline Image<uint8_t> createShape(ShapeBuffer3x3 & buffer, ConnectivityType connectivity);
82 } // namespace imgproc_impl
83 
93 template<class Max>
94 inline void dilate(
95  const Image<uint8_t> & input, Image<uint8_t> & output,
96  ConnectivityType connectivity, Max && max_function)
97 {
98  using namespace imgproc_impl;
99  ShapeBuffer3x3 shape_buffer;
100  Image<uint8_t> shape = createShape(shape_buffer, connectivity);
101  morphologyOperation(input, output, shape, max_function);
102 }
103 
128 template<ConnectivityType connectivity, class Label, class IsBg>
129 std::pair<Image<Label>, Label> connectedComponents(
130  const Image<uint8_t> & image, MemoryBuffer & buffer,
132  IsBg && is_background);
133 
134 // Implementation
135 
136 template<class T>
137 T * MemoryBuffer::get(std::size_t count)
138 {
139  // Check the memory allocated by ::operator new can be used to store the type T
140  static_assert(
141  alignof(std::max_align_t) >= alignof(T),
142  "T alignment is more than the fundamental alignment of the platform");
143 
144  const size_t required_bytes = sizeof(T) * count;
145 
146  if (size_ < required_bytes) {
147  allocate(required_bytes);
148  }
149  return static_cast<T *>(data_);
150 }
151 
152 void MemoryBuffer::reset()
153 {
154  ::operator delete(data_);
155  size_ = 0;
156 }
157 
158 void MemoryBuffer::allocate(size_t bytes)
159 {
160  reset();
161  data_ = ::operator new(bytes);
162  size_ = bytes;
163 }
164 
165 namespace imgproc_impl
166 {
167 
186 template<class T, class Bin>
187 std::vector<Bin>
188 histogram(const Image<T> & image, T image_max, Bin bin_max)
189 {
190  if (image.empty()) {
191  return {};
192  }
193  std::vector<Bin> histogram(size_t(image_max) + 1);
194 
195  // Increases the bin value corresponding to the pixel by one
196  auto add_pixel_value = [&histogram, bin_max](T pixel) {
197  auto & h = histogram[pixel];
198  h = std::min(Bin(h + 1), bin_max);
199  };
200 
201  image.forEach(add_pixel_value);
202  return histogram;
203 }
204 
205 namespace out_of_bounds_policy
206 {
207 
214 template<class T>
215 struct DoNothing
216 {
217  T & up(T * v) const {return *v;}
218  T & down(T * v) const {return *v;}
219 };
220 
227 template<class T>
229 {
230 public:
237  ReplaceToZero(const T * up_row_start, const T * down_row_start, size_t columns)
238  : up_row_start_{up_row_start}, up_row_end_{up_row_start + columns},
239  down_row_start_{down_row_start}, down_row_end_{down_row_start + columns} {}
240 
245  T & up(T * v)
246  {
247  if (up_row_start_ == nullptr) {
248  return zero_;
249  }
250  return replaceOutOfBounds(v, up_row_start_, up_row_end_);
251  }
252 
257  T & down(T * v)
258  {
259  return replaceOutOfBounds(v, down_row_start_, down_row_end_);
260  }
261 
262 private:
267  T & replaceOutOfBounds(T * v, const T * begin, const T * end)
268  {
269  if (v < begin || v >= end) {
270  return zero_;
271  }
272  return *v;
273  }
274 
275  const T * up_row_start_;
276  const T * up_row_end_;
277  const T * down_row_start_;
278  const T * down_row_end_;
279  T zero_{};
280 };
281 
282 } // namespace out_of_bounds_policy
283 
295 template<class T, template<class> class Border>
296 class Window
297 {
298 public:
305  inline Window(T * up_row, T * down_row, Border<T> border = {})
306  : up_row_{up_row}, down_row_{down_row}, border_{border} {}
307 
308  inline T & a() {return border_.up(up_row_ - 1);}
309  inline T & b() {return border_.up(up_row_);}
310  inline T & c() {return border_.up(up_row_ + 1);}
311  inline T & d() {return border_.down(down_row_ - 1);}
312  inline T & e() {return *down_row_;}
313  inline const T * anchor() const {return down_row_;}
314 
316  inline void next()
317  {
318  ++up_row_;
319  ++down_row_;
320  }
321 
322 private:
323  T * up_row_;
324  T * down_row_;
325  Border<T> border_;
326 };
327 
329 template<class T>
330 T * dropConst(const T * ptr)
331 {
332  return const_cast<T *>(ptr);
333 }
334 
348 template<class T>
349 Window<T, out_of_bounds_policy::ReplaceToZero> makeSafeWindow(
350  const T * up_row, const T * down_row, size_t columns, size_t offset = 0)
351 {
352  return {
353  dropConst(up_row) + offset, dropConst(down_row) + offset,
354  out_of_bounds_policy::ReplaceToZero<T>{up_row, down_row, columns}
355  };
356 }
357 
366 template<class T>
367 Window<T, out_of_bounds_policy::DoNothing> makeUnsafeWindow(const T * up_row, const T * down_row)
368 {
369  return {dropConst(up_row), dropConst(down_row)};
370 }
371 
373 {
374  virtual ~EquivalenceLabelTreesBase() = default;
375 };
376 
377 struct LabelOverflow : public std::runtime_error
378 {
379  LabelOverflow(const std::string & message)
380  : std::runtime_error(message) {}
381 };
382 
390 template<class Label>
392 {
393 public:
400  void reset(const size_t rows, const size_t columns, ConnectivityType connectivity)
401  {
402  // Trying to reserve memory with a margin
403  const size_t max_labels_count = maxLabels(rows, columns, connectivity);
404  // Number of labels cannot exceed std::numeric_limits<Label>::max()
405  labels_size_ = static_cast<Label>(
406  std::min(max_labels_count, size_t(std::numeric_limits<Label>::max()))
407  );
408 
409  try {
410  labels_.reserve(labels_size_);
411  } catch (...) {
412  // ignore any exception
413  // perhaps the entire requested amount of memory will not be required
414  }
415 
416  // Label 0 is reserved for the background pixels, i.e. labels[0] is always 0
417  labels_ = {0};
418  next_free_ = 1;
419  }
420 
426  Label makeLabel()
427  {
428  // Check the next_free_ counter does not overflow.
429  if (next_free_ == labels_size_) {
430  throw LabelOverflow("EquivalenceLabelTrees: Can't create new label");
431  }
432  labels_.push_back(next_free_);
433  return next_free_++;
434  }
435 
443  Label unionTrees(Label i, Label j)
444  {
445  Label root = findRoot(i);
446 
447  if (i != j) {
448  Label root_j = findRoot(j);
449  root = std::min(root, root_j);
450  setRoot(j, root);
451  }
452  setRoot(i, root);
453  return root;
454  }
455 
463  const std::vector<Label> & getLabels()
464  {
465  Label k = 1;
466  for (Label i = 1; i < next_free_; ++i) {
467 
468  if (labels_[i] < i) {
469  labels_[i] = labels_[labels_[i]];
470  } else {
471  labels_[i] = k;
472  ++k;
473  }
474  }
475  labels_.resize(k);
476  return labels_;
477  }
478 
479 private:
487  static size_t maxLabels(const size_t rows, const size_t columns, ConnectivityType connectivity)
488  {
489  size_t max_labels{};
490 
491  if (connectivity == ConnectivityType::Way4) {
492  /* The maximum of individual components will be reached in the chessboard image,
493  * where the white cells correspond to obstacle pixels */
494  max_labels = (rows * columns) / 2 + 1;
495  } else {
496  /* The maximum of individual components will be reached in image like this:
497  * x.x.x.x~
498  * .......~
499  * x.x.x.x~
500  * .......~
501  * x.x.x.x~
502  * ~
503  * where 'x' - pixel with obstacle, '.' - background pixel,
504  * '~' - row continuation in the same style */
505  max_labels = (rows * columns) / 3 + 1;
506  }
507  ++max_labels; // add zero label
508  max_labels = std::min(max_labels, size_t(std::numeric_limits<Label>::max()));
509  return max_labels;
510  }
511 
513  Label findRoot(Label i)
514  {
515  Label root = i;
516  for (; labels_[root] < root; root = labels_[root]) { /*do nothing*/}
517  return root;
518  }
519 
521  void setRoot(Label i, Label root)
522  {
523  while (labels_[i] < i) {
524  auto j = labels_[i];
525  labels_[i] = root;
526  i = j;
527  }
528  labels_[i] = root;
529  }
530 
531 private:
541  std::vector<Label> labels_;
542  Label labels_size_{};
543  Label next_free_{};
544 };
545 
547 template<ConnectivityType connectivity>
549 
551 template<>
553 {
564  template<class ImageWindow, class LabelsWindow, class Label, class IsBg>
565  static void pass(
566  ImageWindow & image, LabelsWindow & label, EquivalenceLabelTrees<Label> & eq_trees,
567  IsBg && is_bg)
568  {
569  Label & current = label.e();
570 
571  //The decision tree traversal. See reference article for details
572  if (!is_bg(image.e())) {
573  if (label.b()) {
574  current = label.b();
575  } else {
576  if (!is_bg(image.c())) {
577  if (!is_bg(image.a())) {
578  current = eq_trees.unionTrees(label.c(), label.a());
579  } else {
580  if (!is_bg(image.d())) {
581  current = eq_trees.unionTrees(label.c(), label.d());
582  } else {
583  current = label.c();
584  }
585  }
586  } else {
587  if (!is_bg(image.a())) {
588  current = label.a();
589  } else {
590  if (!is_bg(image.d())) {
591  current = label.d();
592  } else {
593  current = eq_trees.makeLabel();
594  }
595  }
596  }
597  }
598  } else {
599  current = 0;
600  }
601  }
602 };
603 
605 template<>
607 {
618  template<class ImageWindow, class LabelsWindow, class Label, class IsBg>
619  static void pass(
620  ImageWindow & image, LabelsWindow & label, EquivalenceLabelTrees<Label> & eq_trees,
621  IsBg && is_bg)
622  {
623  Label & current = label.e();
624 
625  // Simplified decision tree traversal. See reference article for details
626  if (!is_bg(image.e())) {
627  if (!is_bg(image.b())) {
628  if (!is_bg(image.d())) {
629  current = eq_trees.unionTrees(label.d(), label.b());
630  } else {
631  current = label.b();
632  }
633  } else {
634  if (!is_bg(image.d())) {
635  current = label.d();
636  } else {
637  current = eq_trees.makeLabel();
638  }
639  }
640  } else {
641  current = 0;
642  }
643  }
644 };
645 
662 template<class Apply>
663 void probeRows(
664  const Image<uint8_t> & input, size_t first_input_row,
665  Image<uint8_t> & output, size_t first_output_row,
666  const uint8_t * shape, Apply touch_fn)
667 {
668  const size_t rows = input.rows() - std::max(first_input_row, first_output_row);
669  const size_t columns = input.columns();
670 
671  auto apply_shape = [&shape](uint8_t value, uint8_t index) -> uint8_t {
672  return value & shape[index];
673  };
674 
675  auto get_input_row = [&input, first_input_row](size_t row) {
676  return input.row(row + first_input_row);
677  };
678  auto get_output_row = [&output, first_output_row](size_t row) {
679  return output.row(row + first_output_row);
680  };
681 
682  if (columns == 1) {
683  for (size_t i = 0; i < rows; ++i) {
684  // process single column. Interpret pixel from column -1 and 1 as 0
685  auto overlay = {uint8_t(0), apply_shape(*get_input_row(i), 1), uint8_t(0)};
686  touch_fn(*get_output_row(i), overlay);
687  }
688  } else {
689  for (size_t i = 0; i < rows; ++i) {
690  const uint8_t * in = get_input_row(i);
691  const uint8_t * last_column_pixel = in + columns - 1;
692  uint8_t * out = get_output_row(i);
693 
694  // process first column. Interpret pixel from column -1 as 0
695  {
696  auto overlay = {uint8_t(0), apply_shape(*in, 1), apply_shape(*(in + 1), 2)};
697  touch_fn(*out, overlay);
698  ++in;
699  ++out;
700  }
701 
702  // process next columns up to last
703  for (; in != last_column_pixel; ++in, ++out) {
704  auto overlay = {
705  apply_shape(*(in - 1), 0),
706  apply_shape(*(in), 1),
707  apply_shape(*(in + 1), 2)
708  };
709  touch_fn(*out, overlay);
710  }
711 
712  // process last column
713  {
714  auto overlay = {apply_shape(*(in - 1), 0), apply_shape(*(in), 1), uint8_t(0)};
715  touch_fn(*out, overlay);
716  ++in;
717  ++out;
718  }
719  }
720  }
721 }
722 
737 template<class AggregateFn>
738 void morphologyOperation(
739  const Image<uint8_t> & input, Image<uint8_t> & output,
740  const Image<uint8_t> & shape, AggregateFn aggregate)
741 {
742  if (input.rows() != output.rows() || input.columns() != output.columns()) {
743  throw std::logic_error(
744  "morphologyOperation: the sizes of the input and output images are different");
745  }
746 
747  if (shape.rows() != 3 || shape.columns() != 3) {
748  throw std::logic_error("morphologyOperation: wrong shape size");
749  }
750 
751  if (input.empty()) {
752  return;
753  }
754 
755  // Simple write the pixel of the output image (first pass only)
756  auto set = [&](uint8_t & res, std::initializer_list<uint8_t> lst) {res = aggregate(lst);};
757  // Update the pixel of the output image
758  auto update = [&](uint8_t & res, std::initializer_list<uint8_t> lst) {
759  res = aggregate({res, aggregate(lst), 0});
760  };
761 
762  // Apply the central shape row.
763  // This operation is applicable to all rows of the image, because at any position of the sliding window,
764  // its central row is located on the image. So we start from the zero line of input and output
765  probeRows(input, 0, output, 0, shape.row(1), set);
766 
767  if (input.rows() > 1) {
768  // Apply the top shape row.
769  // In the uppermost position of the sliding window, its first row is outside the image border.
770  // Therefore, we start filling the output image starting from the line 1 and will process input.rows() - 1 lines in total
771  probeRows(input, 0, output, 1, shape.row(0), update);
772  // Apply the bottom shape row.
773  // Similarly, the input image starting from the line 1 and will process input.rows() - 1 lines in total
774  probeRows(input, 1, output, 0, shape.row(2), update);
775  }
776 }
777 
782 Image<uint8_t> createShape(ShapeBuffer3x3 & buffer, ConnectivityType connectivity)
783 {
789  static constexpr uint8_t u = 255;
790  static constexpr uint8_t i = 0;
791 
792  if (connectivity == ConnectivityType::Way8) {
793  buffer = {
794  u, u, u,
795  u, i, u,
796  u, u, u};
797  } else {
798  buffer = {
799  i, u, i,
800  u, i, u,
801  i, u, i};
802  }
803  return Image<uint8_t>(3, 3, buffer.data(), 3);
804 }
805 
810 template<ConnectivityType connectivity, class Label, class IsBg>
811 Label connectedComponentsImpl(
812  const Image<uint8_t> & image, Image<Label> & labels,
813  imgproc_impl::EquivalenceLabelTrees<Label> & label_trees, const IsBg & is_background)
814 {
815  using namespace imgproc_impl;
816  using PixelPass = ProcessPixel<connectivity>;
817 
818  // scanning phase
819  // scan row 0
820  {
821  auto img = makeSafeWindow<uint8_t>(nullptr, image.row(0), image.columns());
822  auto lbl = makeSafeWindow<Label>(nullptr, labels.row(0), image.columns());
823 
824  const uint8_t * first_row_end = image.row(0) + image.columns();
825 
826  for (; img.anchor() < first_row_end; img.next(), lbl.next()) {
827  PixelPass::pass(img, lbl, label_trees, is_background);
828  }
829  }
830 
831  // scan rows 1, 2, ...
832  for (size_t row = 0; row < image.rows() - 1; ++row) {
833  // we can safely ignore checks label_mask for first column
834  Window<Label, out_of_bounds_policy::DoNothing> label_mask{labels.row(row), labels.row(row + 1)};
835 
836  auto up = image.row(row);
837  auto current = image.row(row + 1);
838 
839  // scan column 0
840  {
841  auto img = makeSafeWindow(up, current, image.columns());
842  PixelPass::pass(img, label_mask, label_trees, is_background);
843  }
844 
845  // scan columns 1, 2... image.columns() - 2
846  label_mask.next();
847 
848  auto img = makeUnsafeWindow(std::next(up), std::next(current));
849  const uint8_t * current_row_last_element = current + image.columns() - 1;
850 
851  for (; img.anchor() < current_row_last_element; img.next(), label_mask.next()) {
852  PixelPass::pass(img, label_mask, label_trees, is_background);
853  }
854 
855  // scan last column
856  if (image.columns() > 1) {
857  auto last_img = makeSafeWindow(up, current, image.columns(), image.columns() - 1);
858  auto last_label = makeSafeWindow(
859  labels.row(row), labels.row(row + 1),
860  image.columns(), image.columns() - 1);
861  PixelPass::pass(last_img, last_label, label_trees, is_background);
862  }
863  }
864 
865  // analysis phase
866  const std::vector<Label> & labels_map = label_trees.getLabels();
867 
868  // labeling phase
869  labels.forEach(
870  [&](Label & l) {
871  l = labels_map[l];
872  });
873  return labels_map.size();
874 }
875 
882 {
883 public:
886  {
887  label_trees_ = std::make_unique<imgproc_impl::EquivalenceLabelTrees<uint16_t>>();
888  }
889 
901  template<class IsBg>
903  Image<uint8_t> & image, MemoryBuffer & buffer,
904  ConnectivityType group_connectivity_type, size_t minimal_group_size,
905  const IsBg & is_background) const
906  {
907  if (group_connectivity_type == ConnectivityType::Way4) {
908  removeGroupsPickLabelType<ConnectivityType::Way4>(
909  image, buffer, minimal_group_size,
910  is_background);
911  } else {
912  removeGroupsPickLabelType<ConnectivityType::Way8>(
913  image, buffer, minimal_group_size,
914  is_background);
915  }
916  }
917 
918 private:
926  template<ConnectivityType connectivity, class IsBg>
927  void removeGroupsPickLabelType(
928  Image<uint8_t> & image, MemoryBuffer & buffer,
929  size_t minimal_group_size, const IsBg & is_background) const
930  {
931  bool success{};
932  auto label_trees16 =
933  dynamic_cast<imgproc_impl::EquivalenceLabelTrees<uint16_t> *>(label_trees_.get());
934 
935  if (label_trees16) {
936  success = tryRemoveGroupsWithLabelType<connectivity>(
937  image, buffer, minimal_group_size,
938  *label_trees16, is_background, false);
939  }
940 
941  if (!success) {
942  auto label_trees32 =
943  dynamic_cast<imgproc_impl::EquivalenceLabelTrees<uint32_t> *>(label_trees_.get());
944 
945  if (!label_trees32) {
946  label_trees_ = std::make_unique<imgproc_impl::EquivalenceLabelTrees<uint32_t>>();
947  label_trees32 =
948  dynamic_cast<imgproc_impl::EquivalenceLabelTrees<uint32_t> *>(label_trees_.get());
949  }
950  tryRemoveGroupsWithLabelType<connectivity>(
951  image, buffer, minimal_group_size, *label_trees32,
952  is_background, true);
953  }
954  }
963  template<ConnectivityType connectivity, class Label, class IsBg>
964  bool tryRemoveGroupsWithLabelType(
965  Image<uint8_t> & image, MemoryBuffer & buffer, size_t minimal_group_size,
966  imgproc_impl::EquivalenceLabelTrees<Label> & label_trees,
967  const IsBg & is_background,
968  bool throw_on_label_overflow) const
969  {
970  bool success{};
971  try {
972  removeGroupsImpl<connectivity>(image, buffer, label_trees, minimal_group_size, is_background);
973  success = true;
974  } catch (imgproc_impl::LabelOverflow &) {
975  if (throw_on_label_overflow) {
976  throw;
977  }
978  }
979  return success;
980  }
982  template<ConnectivityType connectivity, class Label, class IsBg>
983  void removeGroupsImpl(
984  Image<uint8_t> & image, MemoryBuffer & buffer,
985  imgproc_impl::EquivalenceLabelTrees<Label> & label_trees, size_t minimal_group_size,
986  const IsBg & is_background) const
987  {
988  // Creates an image labels in which each obstacles group is labeled with a unique code
989  Label groups_count;
990  auto labels = connectedComponents<connectivity>(
991  image, buffer, label_trees,
992  is_background, groups_count);
993 
994  // Calculates the size of each group.
995  // Group size is equal to the number of pixels with the same label
996  const Label max_label_value = groups_count - 1; // It's safe. groups_count always non-zero
997  std::vector<size_t> groups_sizes = histogram(
998  labels, max_label_value, size_t(minimal_group_size + 1));
999 
1000  // The group of pixels labeled 0 corresponds to empty map cells.
1001  // Zero bin of the histogram is equal to the number of pixels in this group.
1002  // Because the values of empty map cells should not be changed, we will reset this bin
1003  groups_sizes.front() = 0; // don't change image background value
1004 
1005  // noise_labels_table[i] = true if group with label i is noise
1006  std::vector<bool> noise_labels_table(groups_sizes.size());
1007  auto transform_fn = [&minimal_group_size](size_t bin_value) {
1008  return bin_value < minimal_group_size;
1009  };
1010  std::transform(
1011  groups_sizes.begin(), groups_sizes.end(), noise_labels_table.begin(),
1012  transform_fn);
1013 
1014  // Replace the pixel values from the small groups to background code
1015  labels.convert(
1016  image, [&](Label src, uint8_t & trg) {
1017  if (!is_background(trg) && noise_labels_table[src]) {
1018  trg = 0;
1019  }
1020  });
1021  }
1022 
1023 private:
1024  mutable std::unique_ptr<imgproc_impl::EquivalenceLabelTreesBase> label_trees_;
1025 };
1026 
1027 } // namespace imgproc_impl
1028 
1029 template<ConnectivityType connectivity, class Label, class IsBg>
1030 Image<Label> connectedComponents(
1031  const Image<uint8_t> & image, MemoryBuffer & buffer,
1032  imgproc_impl::EquivalenceLabelTrees<Label> & label_trees,
1033  const IsBg & is_background,
1034  Label & total_labels)
1035 {
1036  using namespace imgproc_impl;
1037  const size_t pixels = image.rows() * image.columns();
1038 
1039  if (pixels == 0) {
1040  total_labels = 0;
1041  return Image<Label>{};
1042  }
1043 
1044  Label * image_buffer = buffer.get<Label>(pixels);
1045  Image<Label> labels(image.rows(), image.columns(), image_buffer, image.columns());
1046  label_trees.reset(image.rows(), image.columns(), connectivity);
1047  total_labels = connectedComponentsImpl<connectivity>(
1048  image, labels, label_trees,
1049  is_background);
1050  return labels;
1051 }
1052 
1053 } // namespace nav2_costmap_2d
1054 
1055 #endif // NAV2_COSTMAP_2D__DENOISE__IMAGE_PROCESSING_HPP_
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
T * row(size_t row)
Definition: image.hpp:145
size_t columns() const
Definition: image.hpp:64
size_t rows() const
Definition: image.hpp:61
A memory buffer that can grow to an upper-bounded capacity.
~MemoryBuffer()
Free memory allocated for the buffer.
T * get(std::size_t count)
Return a pointer to an uninitialized array of count elements Delete the old block of memory and alloc...
Union-find data structure Implementation of union-find data structure, described in reference article...
void reset(const size_t rows, const size_t columns, ConnectivityType connectivity)
Reset labels tree to initial state.
Label unionTrees(Label i, Label j)
Unite the two trees containing nodes i and j and return the new root See union function in reference ...
const std::vector< Label > & getLabels()
Convert union-find trees to labels lookup table.
Label makeLabel()
Creates new next unused label and returns it back.
Object to eliminate grouped noise on the image Stores a label tree that is reused.
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...
GroupsRemover()
Constructs the object and initializes the label tree.
Forward scan mask sliding window Provides an interface for access to neighborhood of the current pixe...
Window(T *up_row, T *down_row, Border< T > border={})
void next()
Shifts the window to the right.
Boundary case object. Used as parameter of class Window. Dereferences a pointer to a existing pixel....
ReplaceToZero(const T *up_row_start, const T *down_row_start, size_t columns)
Create an object that will replace pointers outside the specified range.
T & down(T *v)
Return ref to pixel or to zero value if the pointer is out of bounds.
T & up(T *v)
Return ref to pixel or to zero value if up_row_start_ is nullptr or the pointer is out of bounds.
@ 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.
std::pair< Image< Label >, Label > connectedComponents(const Image< uint8_t > &image, MemoryBuffer &buffer, imgproc_impl::EquivalenceLabelTrees< Label > &label_trees, IsBg &&is_background)
Compute the connected components labeled image of binary image Implements the SAUF algorithm (Two Str...
static void pass(ImageWindow &image, LabelsWindow &label, EquivalenceLabelTrees< Label > &eq_trees, IsBg &&is_bg)
Set the label of the current pixel image.e() based on labels in its neighborhood.
static void pass(ImageWindow &image, LabelsWindow &label, EquivalenceLabelTrees< Label > &eq_trees, IsBg &&is_bg)
Set the label of the current pixel image.e() based on labels in its neighborhood.
The specializations of this class provide the definition of the pixel label.
Boundary case object stub. Used as parameter of class Window. Dereferences a pointer to a pixel witho...