Nav2 Navigation Stack - rolling  main
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_.clear();
420  labels_.resize(1, 0);
421  next_free_ = 1;
422  }
423 
429  Label makeLabel()
430  {
431  // Check the next_free_ counter does not overflow.
432  if (next_free_ == labels_size_) {
433  throw LabelOverflow("EquivalenceLabelTrees: Can't create new label");
434  }
435  labels_.push_back(next_free_);
436  return next_free_++;
437  }
438 
446  Label unionTrees(Label i, Label j)
447  {
448  Label root = findRoot(i);
449 
450  if (i != j) {
451  Label root_j = findRoot(j);
452  root = std::min(root, root_j);
453  setRoot(j, root);
454  }
455  setRoot(i, root);
456  return root;
457  }
458 
466  const std::vector<Label> & getLabels()
467  {
468  Label k = 1;
469  for (Label i = 1; i < next_free_; ++i) {
470  if (labels_[i] < i) {
471  labels_[i] = labels_[labels_[i]];
472  } else {
473  labels_[i] = k;
474  ++k;
475  }
476  }
477  labels_.resize(k);
478  return labels_;
479  }
480 
481 private:
489  static size_t maxLabels(const size_t rows, const size_t columns, ConnectivityType connectivity)
490  {
491  size_t max_labels{};
492 
493  if (connectivity == ConnectivityType::Way4) {
494  /* The maximum of individual components will be reached in the chessboard image,
495  * where the white cells correspond to obstacle pixels */
496  max_labels = (rows * columns) / 2 + 1;
497  } else {
498  /* The maximum of individual components will be reached in image like this:
499  * x.x.x.x~
500  * .......~
501  * x.x.x.x~
502  * .......~
503  * x.x.x.x~
504  * ~
505  * where 'x' - pixel with obstacle, '.' - background pixel,
506  * '~' - row continuation in the same style */
507  max_labels = (rows * columns) / 3 + 1;
508  }
509  ++max_labels; // add zero label
510  max_labels = std::min(max_labels, size_t(std::numeric_limits<Label>::max()));
511  return max_labels;
512  }
513 
515  Label findRoot(Label i)
516  {
517  Label root = i;
518  for (; labels_[root] < root; root = labels_[root]) { /*do nothing*/}
519  return root;
520  }
521 
523  void setRoot(Label i, Label root)
524  {
525  while (labels_[i] < i) {
526  auto j = labels_[i];
527  labels_[i] = root;
528  i = j;
529  }
530  labels_[i] = root;
531  }
532 
533 private:
543  std::vector<Label> labels_;
544  Label labels_size_{};
545  Label next_free_{};
546 };
547 
549 template<ConnectivityType connectivity>
551 
553 template<>
555 {
566  template<class ImageWindow, class LabelsWindow, class Label, class IsBg>
567  static void pass(
568  ImageWindow & image, LabelsWindow & label, EquivalenceLabelTrees<Label> & eq_trees,
569  IsBg && is_bg)
570  {
571  Label & current = label.e();
572 
573  // The decision tree traversal. See reference article for details
574  if (!is_bg(image.e())) {
575  if (label.b()) {
576  current = label.b();
577  } else {
578  if (!is_bg(image.c())) {
579  if (!is_bg(image.a())) {
580  current = eq_trees.unionTrees(label.c(), label.a());
581  } else {
582  if (!is_bg(image.d())) {
583  current = eq_trees.unionTrees(label.c(), label.d());
584  } else {
585  current = label.c();
586  }
587  }
588  } else {
589  if (!is_bg(image.a())) {
590  current = label.a();
591  } else {
592  if (!is_bg(image.d())) {
593  current = label.d();
594  } else {
595  current = eq_trees.makeLabel();
596  }
597  }
598  }
599  }
600  } else {
601  current = 0;
602  }
603  }
604 };
605 
607 template<>
609 {
620  template<class ImageWindow, class LabelsWindow, class Label, class IsBg>
621  static void pass(
622  ImageWindow & image, LabelsWindow & label, EquivalenceLabelTrees<Label> & eq_trees,
623  IsBg && is_bg)
624  {
625  Label & current = label.e();
626 
627  // Simplified decision tree traversal. See reference article for details
628  if (!is_bg(image.e())) {
629  if (!is_bg(image.b())) {
630  if (!is_bg(image.d())) {
631  current = eq_trees.unionTrees(label.d(), label.b());
632  } else {
633  current = label.b();
634  }
635  } else {
636  if (!is_bg(image.d())) {
637  current = label.d();
638  } else {
639  current = eq_trees.makeLabel();
640  }
641  }
642  } else {
643  current = 0;
644  }
645  }
646 };
647 
664 template<class Apply>
665 void probeRows(
666  const Image<uint8_t> & input, size_t first_input_row,
667  Image<uint8_t> & output, size_t first_output_row,
668  const uint8_t * shape, Apply touch_fn)
669 {
670  const size_t rows = input.rows() - std::max(first_input_row, first_output_row);
671  const size_t columns = input.columns();
672 
673  auto apply_shape = [&shape](uint8_t value, uint8_t index) -> uint8_t {
674  return value & shape[index];
675  };
676 
677  auto get_input_row = [&input, first_input_row](size_t row) {
678  return input.row(row + first_input_row);
679  };
680  auto get_output_row = [&output, first_output_row](size_t row) {
681  return output.row(row + first_output_row);
682  };
683 
684  if (columns == 1) {
685  for (size_t i = 0; i < rows; ++i) {
686  // process single column. Interpret pixel from column -1 and 1 as 0
687  auto overlay = {uint8_t(0), apply_shape(*get_input_row(i), 1), uint8_t(0)};
688  touch_fn(*get_output_row(i), overlay);
689  }
690  } else {
691  for (size_t i = 0; i < rows; ++i) {
692  const uint8_t * in = get_input_row(i);
693  const uint8_t * last_column_pixel = in + columns - 1;
694  uint8_t * out = get_output_row(i);
695 
696  // process first column. Interpret pixel from column -1 as 0
697  {
698  auto overlay = {uint8_t(0), apply_shape(*in, 1), apply_shape(*(in + 1), 2)};
699  touch_fn(*out, overlay);
700  ++in;
701  ++out;
702  }
703 
704  // process next columns up to last
705  for (; in != last_column_pixel; ++in, ++out) {
706  auto overlay = {
707  apply_shape(*(in - 1), 0),
708  apply_shape(*(in), 1),
709  apply_shape(*(in + 1), 2)
710  };
711  touch_fn(*out, overlay);
712  }
713 
714  // process last column
715  {
716  auto overlay = {apply_shape(*(in - 1), 0), apply_shape(*(in), 1), uint8_t(0)};
717  touch_fn(*out, overlay);
718  ++in;
719  ++out;
720  }
721  }
722  }
723 }
724 
739 template<class AggregateFn>
740 void morphologyOperation(
741  const Image<uint8_t> & input, Image<uint8_t> & output,
742  const Image<uint8_t> & shape, AggregateFn aggregate)
743 {
744  if (input.rows() != output.rows() || input.columns() != output.columns()) {
745  throw std::logic_error(
746  "morphologyOperation: the sizes of the input and output images are different");
747  }
748 
749  if (shape.rows() != 3 || shape.columns() != 3) {
750  throw std::logic_error("morphologyOperation: wrong shape size");
751  }
752 
753  if (input.empty()) {
754  return;
755  }
756 
757  // Simple write the pixel of the output image (first pass only)
758  auto set = [&](uint8_t & res, std::initializer_list<uint8_t> lst) {res = aggregate(lst);};
759  // Update the pixel of the output image
760  auto update = [&](uint8_t & res, std::initializer_list<uint8_t> lst) {
761  res = aggregate({res, aggregate(lst), 0});
762  };
763 
764  // Apply the central shape row.
765  // This operation is applicable to all rows of the image,
766  // because at any position of the sliding window,
767  // its central row is located on the image. So we start from the zero line of input and output
768  probeRows(input, 0, output, 0, shape.row(1), set);
769 
770  if (input.rows() > 1) {
771  // Apply the top shape row.
772  // In the uppermost position of the sliding window, its first row is outside the image border.
773  // Therefore, we start filling the output image starting from the line 1 and will process
774  // input.rows() - 1 lines in total
775  probeRows(input, 0, output, 1, shape.row(0), update);
776  // Apply the bottom shape row.
777  // Similarly, the input image starting from the line 1 and will process
778  // input.rows() - 1 lines in total
779  probeRows(input, 1, output, 0, shape.row(2), update);
780  }
781 }
782 
787 Image<uint8_t> createShape(ShapeBuffer3x3 & buffer, ConnectivityType connectivity)
788 {
794  static constexpr uint8_t u = 255;
795  static constexpr uint8_t i = 0;
796 
797  if (connectivity == ConnectivityType::Way8) {
798  buffer = {
799  u, u, u,
800  u, i, u,
801  u, u, u};
802  } else {
803  buffer = {
804  i, u, i,
805  u, i, u,
806  i, u, i};
807  }
808  return Image<uint8_t>(3, 3, buffer.data(), 3);
809 }
810 
815 template<ConnectivityType connectivity, class Label, class IsBg>
816 Label connectedComponentsImpl(
817  const Image<uint8_t> & image, Image<Label> & labels,
818  imgproc_impl::EquivalenceLabelTrees<Label> & label_trees, const IsBg & is_background)
819 {
820  using namespace imgproc_impl; // NOLINT
821  using PixelPass = ProcessPixel<connectivity>; // NOLINT
822 
823  // scanning phase
824  // scan row 0
825  {
826  auto img = makeSafeWindow<uint8_t>(nullptr, image.row(0), image.columns());
827  auto lbl = makeSafeWindow<Label>(nullptr, labels.row(0), image.columns());
828 
829  const uint8_t * first_row_end = image.row(0) + image.columns();
830 
831  for (; img.anchor() < first_row_end; img.next(), lbl.next()) {
832  PixelPass::pass(img, lbl, label_trees, is_background);
833  }
834  }
835 
836  // scan rows 1, 2, ...
837  for (size_t row = 0; row < image.rows() - 1; ++row) {
838  // we can safely ignore checks label_mask for first column
839  Window<Label, out_of_bounds_policy::DoNothing> label_mask{labels.row(row), labels.row(row + 1)};
840 
841  auto up = image.row(row);
842  auto current = image.row(row + 1);
843 
844  // scan column 0
845  {
846  auto img = makeSafeWindow(up, current, image.columns());
847  PixelPass::pass(img, label_mask, label_trees, is_background);
848  }
849 
850  // scan columns 1, 2... image.columns() - 2
851  label_mask.next();
852 
853  auto img = makeUnsafeWindow(std::next(up), std::next(current));
854  const uint8_t * current_row_last_element = current + image.columns() - 1;
855 
856  for (; img.anchor() < current_row_last_element; img.next(), label_mask.next()) {
857  PixelPass::pass(img, label_mask, label_trees, is_background);
858  }
859 
860  // scan last column
861  if (image.columns() > 1) {
862  auto last_img = makeSafeWindow(up, current, image.columns(), image.columns() - 1);
863  auto last_label = makeSafeWindow(
864  labels.row(row), labels.row(row + 1),
865  image.columns(), image.columns() - 1);
866  PixelPass::pass(last_img, last_label, label_trees, is_background);
867  }
868  }
869 
870  // analysis phase
871  const std::vector<Label> & labels_map = label_trees.getLabels();
872 
873  // labeling phase
874  labels.forEach(
875  [&](Label & l) {
876  l = labels_map[l];
877  });
878  return labels_map.size();
879 }
880 
887 {
888 public:
891  {
892  label_trees_ = std::make_unique<imgproc_impl::EquivalenceLabelTrees<uint16_t>>();
893  }
894 
906  template<class IsBg>
908  Image<uint8_t> & image, MemoryBuffer & buffer,
909  ConnectivityType group_connectivity_type, size_t minimal_group_size,
910  const IsBg & is_background) const
911  {
912  if (group_connectivity_type == ConnectivityType::Way4) {
913  removeGroupsPickLabelType<ConnectivityType::Way4>(
914  image, buffer, minimal_group_size,
915  is_background);
916  } else {
917  removeGroupsPickLabelType<ConnectivityType::Way8>(
918  image, buffer, minimal_group_size,
919  is_background);
920  }
921  }
922 
923 private:
931  template<ConnectivityType connectivity, class IsBg>
932  void removeGroupsPickLabelType(
933  Image<uint8_t> & image, MemoryBuffer & buffer,
934  size_t minimal_group_size, const IsBg & is_background) const
935  {
936  bool success{};
937  auto label_trees16 =
938  dynamic_cast<imgproc_impl::EquivalenceLabelTrees<uint16_t> *>(label_trees_.get());
939 
940  if (label_trees16) {
941  success = tryRemoveGroupsWithLabelType<connectivity>(
942  image, buffer, minimal_group_size,
943  *label_trees16, is_background, false);
944  }
945 
946  if (!success) {
947  auto label_trees32 =
948  dynamic_cast<imgproc_impl::EquivalenceLabelTrees<uint32_t> *>(label_trees_.get());
949 
950  if (!label_trees32) {
951  label_trees_ = std::make_unique<imgproc_impl::EquivalenceLabelTrees<uint32_t>>();
952  label_trees32 =
953  dynamic_cast<imgproc_impl::EquivalenceLabelTrees<uint32_t> *>(label_trees_.get());
954  }
955  tryRemoveGroupsWithLabelType<connectivity>(
956  image, buffer, minimal_group_size, *label_trees32,
957  is_background, true);
958  }
959  }
968  template<ConnectivityType connectivity, class Label, class IsBg>
969  bool tryRemoveGroupsWithLabelType(
970  Image<uint8_t> & image, MemoryBuffer & buffer, size_t minimal_group_size,
971  imgproc_impl::EquivalenceLabelTrees<Label> & label_trees,
972  const IsBg & is_background,
973  bool throw_on_label_overflow) const
974  {
975  bool success{};
976  try {
977  removeGroupsImpl<connectivity>(image, buffer, label_trees, minimal_group_size, is_background);
978  success = true;
979  } catch (imgproc_impl::LabelOverflow &) {
980  if (throw_on_label_overflow) {
981  throw;
982  }
983  }
984  return success;
985  }
987  template<ConnectivityType connectivity, class Label, class IsBg>
988  void removeGroupsImpl(
989  Image<uint8_t> & image, MemoryBuffer & buffer,
990  imgproc_impl::EquivalenceLabelTrees<Label> & label_trees, size_t minimal_group_size,
991  const IsBg & is_background) const
992  {
993  // Creates an image labels in which each obstacles group is labeled with a unique code
994  Label groups_count;
995  auto labels = connectedComponents<connectivity>(
996  image, buffer, label_trees,
997  is_background, groups_count);
998 
999  // Calculates the size of each group.
1000  // Group size is equal to the number of pixels with the same label
1001  const Label max_label_value = groups_count - 1; // It's safe. groups_count always non-zero
1002  std::vector<size_t> groups_sizes = histogram(
1003  labels, max_label_value, size_t(minimal_group_size + 1));
1004 
1005  // The group of pixels labeled 0 corresponds to empty map cells.
1006  // Zero bin of the histogram is equal to the number of pixels in this group.
1007  // Because the values of empty map cells should not be changed, we will reset this bin
1008  if (!groups_sizes.empty()) {
1009  groups_sizes.front() = 0; // don't change image background value
1010  }
1011 
1012 
1013  // noise_labels_table[i] = true if group with label i is noise
1014  std::vector<bool> noise_labels_table(groups_sizes.size());
1015  auto transform_fn = [&minimal_group_size](size_t bin_value) {
1016  return bin_value < minimal_group_size;
1017  };
1018  std::transform(
1019  groups_sizes.begin(), groups_sizes.end(), noise_labels_table.begin(),
1020  transform_fn);
1021 
1022  // Replace the pixel values from the small groups to background code
1023  labels.convert(
1024  image, [&](Label src, uint8_t & trg) {
1025  if (!is_background(trg) && noise_labels_table[src]) {
1026  trg = 0;
1027  }
1028  });
1029  }
1030 
1031 private:
1032  mutable std::unique_ptr<imgproc_impl::EquivalenceLabelTreesBase> label_trees_;
1033 };
1034 
1035 } // namespace imgproc_impl
1036 
1037 template<ConnectivityType connectivity, class Label, class IsBg>
1038 Image<Label> connectedComponents(
1039  const Image<uint8_t> & image, MemoryBuffer & buffer,
1040  imgproc_impl::EquivalenceLabelTrees<Label> & label_trees,
1041  const IsBg & is_background,
1042  Label & total_labels)
1043 {
1044  using namespace imgproc_impl; // NOLINT
1045  const size_t pixels = image.rows() * image.columns();
1046 
1047  if (pixels == 0) {
1048  total_labels = 0;
1049  return Image<Label>{};
1050  }
1051 
1052  Label * image_buffer = buffer.get<Label>(pixels);
1053  Image<Label> labels(image.rows(), image.columns(), image_buffer, image.columns());
1054  label_trees.reset(image.rows(), image.columns(), connectivity);
1055  total_labels = connectedComponentsImpl<connectivity>(
1056  image, labels, label_trees,
1057  is_background);
1058  return labels;
1059 }
1060 
1061 } // namespace nav2_costmap_2d
1062 
1063 #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...