Nav2 Navigation Stack - jazzy  jazzy
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 #include <string>
25 #include <utility>
26 
27 namespace nav2_costmap_2d
28 {
29 
35 enum class ConnectivityType : int
36 {
38  Way4 = 4,
40  Way8 = 8
41 };
42 
47 {
48 public:
50  inline ~MemoryBuffer() {reset();}
59  template<class T>
60  T * get(std::size_t count);
61 
62 private:
63  inline void reset();
64  inline void allocate(size_t bytes);
65 
66 private:
67  void * data_{};
68  size_t size_{};
69 };
70 
71 // forward declarations
72 namespace imgproc_impl
73 {
74 template<class Label>
75 class EquivalenceLabelTrees;
76 
77 template<class AggregateFn>
78 void morphologyOperation(
79  const Image<uint8_t> & input, Image<uint8_t> & output,
80  const Image<uint8_t> & shape, AggregateFn aggregate);
81 
82 using ShapeBuffer3x3 = std::array<uint8_t, 9>; // NOLINT
83 inline Image<uint8_t> createShape(ShapeBuffer3x3 & buffer, ConnectivityType connectivity);
84 } // namespace imgproc_impl
85 
95 template<class Max>
96 inline void dilate(
97  const Image<uint8_t> & input, Image<uint8_t> & output,
98  ConnectivityType connectivity, Max && max_function)
99 {
100  using namespace imgproc_impl; // NOLINT
101  ShapeBuffer3x3 shape_buffer;
102  Image<uint8_t> shape = createShape(shape_buffer, connectivity);
103  morphologyOperation(input, output, shape, max_function);
104 }
105 
130 template<ConnectivityType connectivity, class Label, class IsBg>
131 std::pair<Image<Label>, Label> connectedComponents(
132  const Image<uint8_t> & image, MemoryBuffer & buffer,
134  IsBg && is_background);
135 
136 // Implementation
137 
138 template<class T>
139 T * MemoryBuffer::get(std::size_t count)
140 {
141  // Check the memory allocated by ::operator new can be used to store the type T
142  static_assert(
143  alignof(std::max_align_t) >= alignof(T),
144  "T alignment is more than the fundamental alignment of the platform");
145 
146  const size_t required_bytes = sizeof(T) * count;
147 
148  if (size_ < required_bytes) {
149  allocate(required_bytes);
150  }
151  return static_cast<T *>(data_);
152 }
153 
154 void MemoryBuffer::reset()
155 {
156  ::operator delete(data_);
157  size_ = 0;
158 }
159 
160 void MemoryBuffer::allocate(size_t bytes)
161 {
162  reset();
163  data_ = ::operator new(bytes);
164  size_ = bytes;
165 }
166 
167 namespace imgproc_impl
168 {
169 
188 template<class T, class Bin>
189 std::vector<Bin>
190 histogram(const Image<T> & image, T image_max, Bin bin_max)
191 {
192  if (image.empty()) {
193  return {};
194  }
195  std::vector<Bin> histogram(size_t(image_max) + 1);
196 
197  // Increases the bin value corresponding to the pixel by one
198  auto add_pixel_value = [&histogram, bin_max](T pixel) {
199  auto & h = histogram[pixel];
200  h = std::min(Bin(h + 1), bin_max);
201  };
202 
203  image.forEach(add_pixel_value);
204  return histogram;
205 }
206 
207 namespace out_of_bounds_policy
208 {
209 
216 template<class T>
217 struct DoNothing
218 {
219  T & up(T * v) const {return *v;}
220  T & down(T * v) const {return *v;}
221 };
222 
229 template<class T>
231 {
232 public:
239  ReplaceToZero(const T * up_row_start, const T * down_row_start, size_t columns)
240  : up_row_start_{up_row_start}, up_row_end_{up_row_start + columns},
241  down_row_start_{down_row_start}, down_row_end_{down_row_start + columns} {}
242 
247  T & up(T * v)
248  {
249  if (up_row_start_ == nullptr) {
250  return zero_;
251  }
252  return replaceOutOfBounds(v, up_row_start_, up_row_end_);
253  }
254 
259  T & down(T * v)
260  {
261  return replaceOutOfBounds(v, down_row_start_, down_row_end_);
262  }
263 
264 private:
269  T & replaceOutOfBounds(T * v, const T * begin, const T * end)
270  {
271  if (v < begin || v >= end) {
272  return zero_;
273  }
274  return *v;
275  }
276 
277  const T * up_row_start_;
278  const T * up_row_end_;
279  const T * down_row_start_;
280  const T * down_row_end_;
281  T zero_{};
282 };
283 
284 } // namespace out_of_bounds_policy
285 
297 template<class T, template<class> class Border>
298 class Window
299 {
300 public:
307  inline Window(T * up_row, T * down_row, Border<T> border = {})
308  : up_row_{up_row}, down_row_{down_row}, border_{border} {}
309 
310  inline T & a() {return border_.up(up_row_ - 1);}
311  inline T & b() {return border_.up(up_row_);}
312  inline T & c() {return border_.up(up_row_ + 1);}
313  inline T & d() {return border_.down(down_row_ - 1);}
314  inline T & e() {return *down_row_;}
315  inline const T * anchor() const {return down_row_;}
316 
318  inline void next()
319  {
320  ++up_row_;
321  ++down_row_;
322  }
323 
324 private:
325  T * up_row_;
326  T * down_row_;
327  Border<T> border_;
328 };
329 
331 template<class T>
332 T * dropConst(const T * ptr)
333 {
334  return const_cast<T *>(ptr);
335 }
336 
350 template<class T>
351 Window<T, out_of_bounds_policy::ReplaceToZero> makeSafeWindow(
352  const T * up_row, const T * down_row, size_t columns, size_t offset = 0)
353 {
354  return {
355  dropConst(up_row) + offset, dropConst(down_row) + offset,
356  out_of_bounds_policy::ReplaceToZero<T>{up_row, down_row, columns}
357  };
358 }
359 
368 template<class T>
369 Window<T, out_of_bounds_policy::DoNothing> makeUnsafeWindow(const T * up_row, const T * down_row)
370 {
371  return {dropConst(up_row), dropConst(down_row)};
372 }
373 
375 {
376  virtual ~EquivalenceLabelTreesBase() = default;
377 };
378 
379 struct LabelOverflow : public std::runtime_error
380 {
381  explicit LabelOverflow(const std::string & message)
382  : std::runtime_error(message) {}
383 };
384 
392 template<class Label>
394 {
395 public:
402  void reset(const size_t rows, const size_t columns, ConnectivityType connectivity)
403  {
404  // Trying to reserve memory with a margin
405  const size_t max_labels_count = maxLabels(rows, columns, connectivity);
406  // Number of labels cannot exceed std::numeric_limits<Label>::max()
407  labels_size_ = static_cast<Label>(
408  std::min(max_labels_count, size_t(std::numeric_limits<Label>::max()))
409  );
410 
411  try {
412  labels_.reserve(labels_size_);
413  } catch (...) {
414  // ignore any exception
415  // perhaps the entire requested amount of memory will not be required
416  }
417 
418  // Label 0 is reserved for the background pixels, i.e. labels[0] is always 0
419  labels_ = {0};
420  next_free_ = 1;
421  }
422 
428  Label makeLabel()
429  {
430  // Check the next_free_ counter does not overflow.
431  if (next_free_ == labels_size_) {
432  throw LabelOverflow("EquivalenceLabelTrees: Can't create new label");
433  }
434  labels_.push_back(next_free_);
435  return next_free_++;
436  }
437 
445  Label unionTrees(Label i, Label j)
446  {
447  Label root = findRoot(i);
448 
449  if (i != j) {
450  Label root_j = findRoot(j);
451  root = std::min(root, root_j);
452  setRoot(j, root);
453  }
454  setRoot(i, root);
455  return root;
456  }
457 
465  const std::vector<Label> & getLabels()
466  {
467  Label k = 1;
468  for (Label i = 1; i < next_free_; ++i) {
469  if (labels_[i] < i) {
470  labels_[i] = labels_[labels_[i]];
471  } else {
472  labels_[i] = k;
473  ++k;
474  }
475  }
476  labels_.resize(k);
477  return labels_;
478  }
479 
480 private:
488  static size_t maxLabels(const size_t rows, const size_t columns, ConnectivityType connectivity)
489  {
490  size_t max_labels{};
491 
492  if (connectivity == ConnectivityType::Way4) {
493  /* The maximum of individual components will be reached in the chessboard image,
494  * where the white cells correspond to obstacle pixels */
495  max_labels = (rows * columns) / 2 + 1;
496  } else {
497  /* The maximum of individual components will be reached in image like this:
498  * x.x.x.x~
499  * .......~
500  * x.x.x.x~
501  * .......~
502  * x.x.x.x~
503  * ~
504  * where 'x' - pixel with obstacle, '.' - background pixel,
505  * '~' - row continuation in the same style */
506  max_labels = (rows * columns) / 3 + 1;
507  }
508  ++max_labels; // add zero label
509  max_labels = std::min(max_labels, size_t(std::numeric_limits<Label>::max()));
510  return max_labels;
511  }
512 
514  Label findRoot(Label i)
515  {
516  Label root = i;
517  for (; labels_[root] < root; root = labels_[root]) { /*do nothing*/}
518  return root;
519  }
520 
522  void setRoot(Label i, Label root)
523  {
524  while (labels_[i] < i) {
525  auto j = labels_[i];
526  labels_[i] = root;
527  i = j;
528  }
529  labels_[i] = root;
530  }
531 
532 private:
542  std::vector<Label> labels_;
543  Label labels_size_{};
544  Label next_free_{};
545 };
546 
548 template<ConnectivityType connectivity>
550 
552 template<>
554 {
565  template<class ImageWindow, class LabelsWindow, class Label, class IsBg>
566  static void pass(
567  ImageWindow & image, LabelsWindow & label, EquivalenceLabelTrees<Label> & eq_trees,
568  IsBg && is_bg)
569  {
570  Label & current = label.e();
571 
572  // The decision tree traversal. See reference article for details
573  if (!is_bg(image.e())) {
574  if (label.b()) {
575  current = label.b();
576  } else {
577  if (!is_bg(image.c())) {
578  if (!is_bg(image.a())) {
579  current = eq_trees.unionTrees(label.c(), label.a());
580  } else {
581  if (!is_bg(image.d())) {
582  current = eq_trees.unionTrees(label.c(), label.d());
583  } else {
584  current = label.c();
585  }
586  }
587  } else {
588  if (!is_bg(image.a())) {
589  current = label.a();
590  } else {
591  if (!is_bg(image.d())) {
592  current = label.d();
593  } else {
594  current = eq_trees.makeLabel();
595  }
596  }
597  }
598  }
599  } else {
600  current = 0;
601  }
602  }
603 };
604 
606 template<>
608 {
619  template<class ImageWindow, class LabelsWindow, class Label, class IsBg>
620  static void pass(
621  ImageWindow & image, LabelsWindow & label, EquivalenceLabelTrees<Label> & eq_trees,
622  IsBg && is_bg)
623  {
624  Label & current = label.e();
625 
626  // Simplified decision tree traversal. See reference article for details
627  if (!is_bg(image.e())) {
628  if (!is_bg(image.b())) {
629  if (!is_bg(image.d())) {
630  current = eq_trees.unionTrees(label.d(), label.b());
631  } else {
632  current = label.b();
633  }
634  } else {
635  if (!is_bg(image.d())) {
636  current = label.d();
637  } else {
638  current = eq_trees.makeLabel();
639  }
640  }
641  } else {
642  current = 0;
643  }
644  }
645 };
646 
663 template<class Apply>
664 void probeRows(
665  const Image<uint8_t> & input, size_t first_input_row,
666  Image<uint8_t> & output, size_t first_output_row,
667  const uint8_t * shape, Apply touch_fn)
668 {
669  const size_t rows = input.rows() - std::max(first_input_row, first_output_row);
670  const size_t columns = input.columns();
671 
672  auto apply_shape = [&shape](uint8_t value, uint8_t index) -> uint8_t {
673  return value & shape[index];
674  };
675 
676  auto get_input_row = [&input, first_input_row](size_t row) {
677  return input.row(row + first_input_row);
678  };
679  auto get_output_row = [&output, first_output_row](size_t row) {
680  return output.row(row + first_output_row);
681  };
682 
683  if (columns == 1) {
684  for (size_t i = 0; i < rows; ++i) {
685  // process single column. Interpret pixel from column -1 and 1 as 0
686  auto overlay = {uint8_t(0), apply_shape(*get_input_row(i), 1), uint8_t(0)};
687  touch_fn(*get_output_row(i), overlay);
688  }
689  } else {
690  for (size_t i = 0; i < rows; ++i) {
691  const uint8_t * in = get_input_row(i);
692  const uint8_t * last_column_pixel = in + columns - 1;
693  uint8_t * out = get_output_row(i);
694 
695  // process first column. Interpret pixel from column -1 as 0
696  {
697  auto overlay = {uint8_t(0), apply_shape(*in, 1), apply_shape(*(in + 1), 2)};
698  touch_fn(*out, overlay);
699  ++in;
700  ++out;
701  }
702 
703  // process next columns up to last
704  for (; in != last_column_pixel; ++in, ++out) {
705  auto overlay = {
706  apply_shape(*(in - 1), 0),
707  apply_shape(*(in), 1),
708  apply_shape(*(in + 1), 2)
709  };
710  touch_fn(*out, overlay);
711  }
712 
713  // process last column
714  {
715  auto overlay = {apply_shape(*(in - 1), 0), apply_shape(*(in), 1), uint8_t(0)};
716  touch_fn(*out, overlay);
717  ++in;
718  ++out;
719  }
720  }
721  }
722 }
723 
738 template<class AggregateFn>
739 void morphologyOperation(
740  const Image<uint8_t> & input, Image<uint8_t> & output,
741  const Image<uint8_t> & shape, AggregateFn aggregate)
742 {
743  if (input.rows() != output.rows() || input.columns() != output.columns()) {
744  throw std::logic_error(
745  "morphologyOperation: the sizes of the input and output images are different");
746  }
747 
748  if (shape.rows() != 3 || shape.columns() != 3) {
749  throw std::logic_error("morphologyOperation: wrong shape size");
750  }
751 
752  if (input.empty()) {
753  return;
754  }
755 
756  // Simple write the pixel of the output image (first pass only)
757  auto set = [&](uint8_t & res, std::initializer_list<uint8_t> lst) {res = aggregate(lst);};
758  // Update the pixel of the output image
759  auto update = [&](uint8_t & res, std::initializer_list<uint8_t> lst) {
760  res = aggregate({res, aggregate(lst), 0});
761  };
762 
763  // Apply the central shape row.
764  // This operation is applicable to all rows of the image,
765  // because at any position of the sliding window,
766  // its central row is located on the image. So we start from the zero line of input and output
767  probeRows(input, 0, output, 0, shape.row(1), set);
768 
769  if (input.rows() > 1) {
770  // Apply the top shape row.
771  // In the uppermost position of the sliding window, its first row is outside the image border.
772  // Therefore, we start filling the output image starting from the line 1 and will process
773  // input.rows() - 1 lines in total
774  probeRows(input, 0, output, 1, shape.row(0), update);
775  // Apply the bottom shape row.
776  // Similarly, the input image starting from the line 1 and will process
777  // input.rows() - 1 lines in total
778  probeRows(input, 1, output, 0, shape.row(2), update);
779  }
780 }
781 
786 Image<uint8_t> createShape(ShapeBuffer3x3 & buffer, ConnectivityType connectivity)
787 {
793  static constexpr uint8_t u = 255;
794  static constexpr uint8_t i = 0;
795 
796  if (connectivity == ConnectivityType::Way8) {
797  buffer = {
798  u, u, u,
799  u, i, u,
800  u, u, u};
801  } else {
802  buffer = {
803  i, u, i,
804  u, i, u,
805  i, u, i};
806  }
807  return Image<uint8_t>(3, 3, buffer.data(), 3);
808 }
809 
814 template<ConnectivityType connectivity, class Label, class IsBg>
815 Label connectedComponentsImpl(
816  const Image<uint8_t> & image, Image<Label> & labels,
817  imgproc_impl::EquivalenceLabelTrees<Label> & label_trees, const IsBg & is_background)
818 {
819  using namespace imgproc_impl; // NOLINT
820  using PixelPass = ProcessPixel<connectivity>; // NOLINT
821 
822  // scanning phase
823  // scan row 0
824  {
825  auto img = makeSafeWindow<uint8_t>(nullptr, image.row(0), image.columns());
826  auto lbl = makeSafeWindow<Label>(nullptr, labels.row(0), image.columns());
827 
828  const uint8_t * first_row_end = image.row(0) + image.columns();
829 
830  for (; img.anchor() < first_row_end; img.next(), lbl.next()) {
831  PixelPass::pass(img, lbl, label_trees, is_background);
832  }
833  }
834 
835  // scan rows 1, 2, ...
836  for (size_t row = 0; row < image.rows() - 1; ++row) {
837  // we can safely ignore checks label_mask for first column
838  Window<Label, out_of_bounds_policy::DoNothing> label_mask{labels.row(row), labels.row(row + 1)};
839 
840  auto up = image.row(row);
841  auto current = image.row(row + 1);
842 
843  // scan column 0
844  {
845  auto img = makeSafeWindow(up, current, image.columns());
846  PixelPass::pass(img, label_mask, label_trees, is_background);
847  }
848 
849  // scan columns 1, 2... image.columns() - 2
850  label_mask.next();
851 
852  auto img = makeUnsafeWindow(std::next(up), std::next(current));
853  const uint8_t * current_row_last_element = current + image.columns() - 1;
854 
855  for (; img.anchor() < current_row_last_element; img.next(), label_mask.next()) {
856  PixelPass::pass(img, label_mask, label_trees, is_background);
857  }
858 
859  // scan last column
860  if (image.columns() > 1) {
861  auto last_img = makeSafeWindow(up, current, image.columns(), image.columns() - 1);
862  auto last_label = makeSafeWindow(
863  labels.row(row), labels.row(row + 1),
864  image.columns(), image.columns() - 1);
865  PixelPass::pass(last_img, last_label, label_trees, is_background);
866  }
867  }
868 
869  // analysis phase
870  const std::vector<Label> & labels_map = label_trees.getLabels();
871 
872  // labeling phase
873  labels.forEach(
874  [&](Label & l) {
875  l = labels_map[l];
876  });
877  return labels_map.size();
878 }
879 
886 {
887 public:
890  {
891  label_trees_ = std::make_unique<imgproc_impl::EquivalenceLabelTrees<uint16_t>>();
892  }
893 
905  template<class IsBg>
907  Image<uint8_t> & image, MemoryBuffer & buffer,
908  ConnectivityType group_connectivity_type, size_t minimal_group_size,
909  const IsBg & is_background) const
910  {
911  if (group_connectivity_type == ConnectivityType::Way4) {
912  removeGroupsPickLabelType<ConnectivityType::Way4>(
913  image, buffer, minimal_group_size,
914  is_background);
915  } else {
916  removeGroupsPickLabelType<ConnectivityType::Way8>(
917  image, buffer, minimal_group_size,
918  is_background);
919  }
920  }
921 
922 private:
930  template<ConnectivityType connectivity, class IsBg>
931  void removeGroupsPickLabelType(
932  Image<uint8_t> & image, MemoryBuffer & buffer,
933  size_t minimal_group_size, const IsBg & is_background) const
934  {
935  bool success{};
936  auto label_trees16 =
937  dynamic_cast<imgproc_impl::EquivalenceLabelTrees<uint16_t> *>(label_trees_.get());
938 
939  if (label_trees16) {
940  success = tryRemoveGroupsWithLabelType<connectivity>(
941  image, buffer, minimal_group_size,
942  *label_trees16, is_background, false);
943  }
944 
945  if (!success) {
946  auto label_trees32 =
947  dynamic_cast<imgproc_impl::EquivalenceLabelTrees<uint32_t> *>(label_trees_.get());
948 
949  if (!label_trees32) {
950  label_trees_ = std::make_unique<imgproc_impl::EquivalenceLabelTrees<uint32_t>>();
951  label_trees32 =
952  dynamic_cast<imgproc_impl::EquivalenceLabelTrees<uint32_t> *>(label_trees_.get());
953  }
954  tryRemoveGroupsWithLabelType<connectivity>(
955  image, buffer, minimal_group_size, *label_trees32,
956  is_background, true);
957  }
958  }
967  template<ConnectivityType connectivity, class Label, class IsBg>
968  bool tryRemoveGroupsWithLabelType(
969  Image<uint8_t> & image, MemoryBuffer & buffer, size_t minimal_group_size,
970  imgproc_impl::EquivalenceLabelTrees<Label> & label_trees,
971  const IsBg & is_background,
972  bool throw_on_label_overflow) const
973  {
974  bool success{};
975  try {
976  removeGroupsImpl<connectivity>(image, buffer, label_trees, minimal_group_size, is_background);
977  success = true;
978  } catch (imgproc_impl::LabelOverflow &) {
979  if (throw_on_label_overflow) {
980  throw;
981  }
982  }
983  return success;
984  }
986  template<ConnectivityType connectivity, class Label, class IsBg>
987  void removeGroupsImpl(
988  Image<uint8_t> & image, MemoryBuffer & buffer,
989  imgproc_impl::EquivalenceLabelTrees<Label> & label_trees, size_t minimal_group_size,
990  const IsBg & is_background) const
991  {
992  // Creates an image labels in which each obstacles group is labeled with a unique code
993  Label groups_count;
994  auto labels = connectedComponents<connectivity>(
995  image, buffer, label_trees,
996  is_background, groups_count);
997 
998  // Calculates the size of each group.
999  // Group size is equal to the number of pixels with the same label
1000  const Label max_label_value = groups_count - 1; // It's safe. groups_count always non-zero
1001  std::vector<size_t> groups_sizes = histogram(
1002  labels, max_label_value, size_t(minimal_group_size + 1));
1003 
1004  // The group of pixels labeled 0 corresponds to empty map cells.
1005  // Zero bin of the histogram is equal to the number of pixels in this group.
1006  // Because the values of empty map cells should not be changed, we will reset this bin
1007  if (!groups_sizes.empty()) {
1008  groups_sizes.front() = 0; // don't change image background value
1009  }
1010 
1011 
1012  // noise_labels_table[i] = true if group with label i is noise
1013  std::vector<bool> noise_labels_table(groups_sizes.size());
1014  auto transform_fn = [&minimal_group_size](size_t bin_value) {
1015  return bin_value < minimal_group_size;
1016  };
1017  std::transform(
1018  groups_sizes.begin(), groups_sizes.end(), noise_labels_table.begin(),
1019  transform_fn);
1020 
1021  // Replace the pixel values from the small groups to background code
1022  labels.convert(
1023  image, [&](Label src, uint8_t & trg) {
1024  if (!is_background(trg) && noise_labels_table[src]) {
1025  trg = 0;
1026  }
1027  });
1028  }
1029 
1030 private:
1031  mutable std::unique_ptr<imgproc_impl::EquivalenceLabelTreesBase> label_trees_;
1032 };
1033 
1034 } // namespace imgproc_impl
1035 
1036 template<ConnectivityType connectivity, class Label, class IsBg>
1037 Image<Label> connectedComponents(
1038  const Image<uint8_t> & image, MemoryBuffer & buffer,
1039  imgproc_impl::EquivalenceLabelTrees<Label> & label_trees,
1040  const IsBg & is_background,
1041  Label & total_labels)
1042 {
1043  using namespace imgproc_impl; // NOLINT
1044  const size_t pixels = image.rows() * image.columns();
1045 
1046  if (pixels == 0) {
1047  total_labels = 0;
1048  return Image<Label>{};
1049  }
1050 
1051  Label * image_buffer = buffer.get<Label>(pixels);
1052  Image<Label> labels(image.rows(), image.columns(), image_buffer, image.columns());
1053  label_trees.reset(image.rows(), image.columns(), connectivity);
1054  total_labels = connectedComponentsImpl<connectivity>(
1055  image, labels, label_trees,
1056  is_background);
1057  return labels;
1058 }
1059 
1060 } // namespace nav2_costmap_2d
1061 
1062 #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...