15 #ifndef NAV2_COSTMAP_2D__DENOISE__IMAGE_PROCESSING_HPP_
16 #define NAV2_COSTMAP_2D__DENOISE__IMAGE_PROCESSING_HPP_
58 T *
get(std::size_t count);
62 inline void allocate(
size_t bytes);
70 namespace imgproc_impl
73 class EquivalenceLabelTrees;
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);
80 using ShapeBuffer3x3 = std::array<uint8_t, 9>;
81 inline Image<uint8_t> createShape(ShapeBuffer3x3 & buffer,
ConnectivityType connectivity);
98 using namespace imgproc_impl;
99 ShapeBuffer3x3 shape_buffer;
101 morphologyOperation(input, output, shape, max_function);
128 template<ConnectivityType connectivity,
class Label,
class IsBg>
132 IsBg && is_background);
141 alignof(std::max_align_t) >=
alignof(T),
142 "T alignment is more than the fundamental alignment of the platform");
144 const size_t required_bytes =
sizeof(T) * count;
146 if (size_ < required_bytes) {
147 allocate(required_bytes);
149 return static_cast<T *
>(data_);
152 void MemoryBuffer::reset()
154 ::operator
delete(data_);
158 void MemoryBuffer::allocate(
size_t bytes)
161 data_ = ::operator
new(bytes);
165 namespace imgproc_impl
186 template<
class T,
class Bin>
188 histogram(
const Image<T> & image, T image_max, Bin bin_max)
193 std::vector<Bin> histogram(
size_t(image_max) + 1);
196 auto add_pixel_value = [&histogram, bin_max](T pixel) {
197 auto & h = histogram[pixel];
198 h = std::min(Bin(h + 1), bin_max);
201 image.forEach(add_pixel_value);
205 namespace out_of_bounds_policy
217 T & up(T * v)
const {
return *v;}
218 T & down(T * v)
const {
return *v;}
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} {}
247 if (up_row_start_ ==
nullptr) {
250 return replaceOutOfBounds(v, up_row_start_, up_row_end_);
259 return replaceOutOfBounds(v, down_row_start_, down_row_end_);
267 T & replaceOutOfBounds(T * v,
const T * begin,
const T * end)
269 if (v < begin || v >= end) {
275 const T * up_row_start_;
276 const T * up_row_end_;
277 const T * down_row_start_;
278 const T * down_row_end_;
295 template<
class T,
template<
class>
class Border>
305 inline Window(T * up_row, T * down_row, Border<T> border = {})
306 : up_row_{up_row}, down_row_{down_row}, border_{border} {}
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_;}
330 T * dropConst(
const T * ptr)
332 return const_cast<T *
>(ptr);
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)
353 dropConst(up_row) + offset, dropConst(down_row) + offset,
354 out_of_bounds_policy::ReplaceToZero<T>{up_row, down_row, columns}
367 Window<T, out_of_bounds_policy::DoNothing> makeUnsafeWindow(
const T * up_row,
const T * down_row)
369 return {dropConst(up_row), dropConst(down_row)};
380 : std::runtime_error(message) {}
390 template<
class Label>
403 const size_t max_labels_count = maxLabels(rows, columns, connectivity);
405 labels_size_ =
static_cast<Label
>(
406 std::min(max_labels_count,
size_t(std::numeric_limits<Label>::max()))
410 labels_.reserve(labels_size_);
429 if (next_free_ == labels_size_) {
430 throw LabelOverflow(
"EquivalenceLabelTrees: Can't create new label");
432 labels_.push_back(next_free_);
445 Label root = findRoot(i);
448 Label root_j = findRoot(j);
449 root = std::min(root, root_j);
466 for (Label i = 1; i < next_free_; ++i) {
468 if (labels_[i] < i) {
469 labels_[i] = labels_[labels_[i]];
487 static size_t maxLabels(
const size_t rows,
const size_t columns,
ConnectivityType connectivity)
494 max_labels = (rows * columns) / 2 + 1;
505 max_labels = (rows * columns) / 3 + 1;
508 max_labels = std::min(max_labels,
size_t(std::numeric_limits<Label>::max()));
513 Label findRoot(Label i)
516 for (; labels_[root] < root; root = labels_[root]) { }
521 void setRoot(Label i, Label root)
523 while (labels_[i] < i) {
541 std::vector<Label> labels_;
542 Label labels_size_{};
547 template<ConnectivityType connectivity>
564 template<
class ImageWindow,
class LabelsWindow,
class Label,
class IsBg>
569 Label & current = label.e();
572 if (!is_bg(image.e())) {
576 if (!is_bg(image.c())) {
577 if (!is_bg(image.a())) {
578 current = eq_trees.
unionTrees(label.c(), label.a());
580 if (!is_bg(image.d())) {
581 current = eq_trees.
unionTrees(label.c(), label.d());
587 if (!is_bg(image.a())) {
590 if (!is_bg(image.d())) {
618 template<
class ImageWindow,
class LabelsWindow,
class Label,
class IsBg>
623 Label & current = label.e();
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());
634 if (!is_bg(image.d())) {
662 template<
class Apply>
666 const uint8_t * shape, Apply touch_fn)
668 const size_t rows = input.
rows() - std::max(first_input_row, first_output_row);
669 const size_t columns = input.
columns();
671 auto apply_shape = [&shape](uint8_t value, uint8_t index) -> uint8_t {
672 return value & shape[index];
675 auto get_input_row = [&input, first_input_row](
size_t row) {
676 return input.
row(row + first_input_row);
678 auto get_output_row = [&output, first_output_row](
size_t row) {
679 return output.
row(row + first_output_row);
683 for (
size_t i = 0; i < rows; ++i) {
685 auto overlay = {uint8_t(0), apply_shape(*get_input_row(i), 1), uint8_t(0)};
686 touch_fn(*get_output_row(i), overlay);
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);
696 auto overlay = {uint8_t(0), apply_shape(*in, 1), apply_shape(*(in + 1), 2)};
697 touch_fn(*out, overlay);
703 for (; in != last_column_pixel; ++in, ++out) {
705 apply_shape(*(in - 1), 0),
706 apply_shape(*(in), 1),
707 apply_shape(*(in + 1), 2)
709 touch_fn(*out, overlay);
714 auto overlay = {apply_shape(*(in - 1), 0), apply_shape(*(in), 1), uint8_t(0)};
715 touch_fn(*out, overlay);
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)
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");
747 if (shape.rows() != 3 || shape.columns() != 3) {
748 throw std::logic_error(
"morphologyOperation: wrong shape size");
756 auto set = [&](uint8_t & res, std::initializer_list<uint8_t> lst) {res = aggregate(lst);};
758 auto update = [&](uint8_t & res, std::initializer_list<uint8_t> lst) {
759 res = aggregate({res, aggregate(lst), 0});
765 probeRows(input, 0, output, 0, shape.row(1), set);
767 if (input.rows() > 1) {
771 probeRows(input, 0, output, 1, shape.row(0), update);
774 probeRows(input, 1, output, 0, shape.row(2), update);
782 Image<uint8_t> createShape(ShapeBuffer3x3 & buffer,
ConnectivityType connectivity)
789 static constexpr uint8_t u = 255;
790 static constexpr uint8_t i = 0;
803 return Image<uint8_t>(3, 3, buffer.data(), 3);
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)
815 using namespace imgproc_impl;
816 using PixelPass = ProcessPixel<connectivity>;
821 auto img = makeSafeWindow<uint8_t>(
nullptr, image.row(0), image.columns());
822 auto lbl = makeSafeWindow<Label>(
nullptr, labels.row(0), image.columns());
824 const uint8_t * first_row_end = image.row(0) + image.columns();
826 for (; img.anchor() < first_row_end; img.next(), lbl.next()) {
827 PixelPass::pass(img, lbl, label_trees, is_background);
832 for (
size_t row = 0; row < image.rows() - 1; ++row) {
834 Window<Label, out_of_bounds_policy::DoNothing> label_mask{labels.row(row), labels.row(row + 1)};
836 auto up = image.row(row);
837 auto current = image.row(row + 1);
841 auto img = makeSafeWindow(up, current, image.columns());
842 PixelPass::pass(img, label_mask, label_trees, is_background);
848 auto img = makeUnsafeWindow(std::next(up), std::next(current));
849 const uint8_t * current_row_last_element = current + image.columns() - 1;
851 for (; img.anchor() < current_row_last_element; img.next(), label_mask.next()) {
852 PixelPass::pass(img, label_mask, label_trees, is_background);
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);
866 const std::vector<Label> & labels_map = label_trees.getLabels();
873 return labels_map.size();
887 label_trees_ = std::make_unique<imgproc_impl::EquivalenceLabelTrees<uint16_t>>();
905 const IsBg & is_background)
const
908 removeGroupsPickLabelType<ConnectivityType::Way4>(
909 image, buffer, minimal_group_size,
912 removeGroupsPickLabelType<ConnectivityType::Way8>(
913 image, buffer, minimal_group_size,
926 template<ConnectivityType connectivity,
class IsBg>
927 void removeGroupsPickLabelType(
929 size_t minimal_group_size,
const IsBg & is_background)
const
936 success = tryRemoveGroupsWithLabelType<connectivity>(
937 image, buffer, minimal_group_size,
938 *label_trees16, is_background,
false);
943 dynamic_cast<imgproc_impl::EquivalenceLabelTrees<uint32_t> *
>(label_trees_.get());
945 if (!label_trees32) {
946 label_trees_ = std::make_unique<imgproc_impl::EquivalenceLabelTrees<uint32_t>>();
948 dynamic_cast<imgproc_impl::EquivalenceLabelTrees<uint32_t> *
>(label_trees_.get());
950 tryRemoveGroupsWithLabelType<connectivity>(
951 image, buffer, minimal_group_size, *label_trees32,
952 is_background,
true);
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
972 removeGroupsImpl<connectivity>(image, buffer, label_trees, minimal_group_size, is_background);
974 }
catch (imgproc_impl::LabelOverflow &) {
975 if (throw_on_label_overflow) {
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
990 auto labels = connectedComponents<connectivity>(
991 image, buffer, label_trees,
992 is_background, groups_count);
996 const Label max_label_value = groups_count - 1;
997 std::vector<size_t> groups_sizes = histogram(
998 labels, max_label_value,
size_t(minimal_group_size + 1));
1003 groups_sizes.front() = 0;
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;
1011 groups_sizes.begin(), groups_sizes.end(), noise_labels_table.begin(),
1016 image, [&](Label src, uint8_t & trg) {
1017 if (!is_background(trg) && noise_labels_table[src]) {
1024 mutable std::unique_ptr<imgproc_impl::EquivalenceLabelTreesBase> label_trees_;
1029 template<ConnectivityType connectivity,
class Label,
class IsBg>
1031 const Image<uint8_t> & image, MemoryBuffer & buffer,
1032 imgproc_impl::EquivalenceLabelTrees<Label> & label_trees,
1033 const IsBg & is_background,
1034 Label & total_labels)
1036 using namespace imgproc_impl;
1037 const size_t pixels = image.rows() * image.columns();
1041 return Image<Label>{};
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,
Image with pixels of type T Сan own data, be a wrapper over some memory buffer, or refer to a fragmen...
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...