15 #ifndef NAV2_COSTMAP_2D__DENOISE__IMAGE_PROCESSING_HPP_
16 #define NAV2_COSTMAP_2D__DENOISE__IMAGE_PROCESSING_HPP_
60 T *
get(std::size_t count);
64 inline void allocate(
size_t bytes);
72 namespace imgproc_impl
75 class EquivalenceLabelTrees;
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);
82 using ShapeBuffer3x3 = std::array<uint8_t, 9>;
83 inline Image<uint8_t> createShape(ShapeBuffer3x3 & buffer,
ConnectivityType connectivity);
100 using namespace imgproc_impl;
101 ShapeBuffer3x3 shape_buffer;
103 morphologyOperation(input, output, shape, max_function);
130 template<ConnectivityType connectivity,
class Label,
class IsBg>
134 IsBg && is_background);
143 alignof(std::max_align_t) >=
alignof(T),
144 "T alignment is more than the fundamental alignment of the platform");
146 const size_t required_bytes =
sizeof(T) * count;
148 if (size_ < required_bytes) {
149 allocate(required_bytes);
151 return static_cast<T *
>(data_);
154 void MemoryBuffer::reset()
156 ::operator
delete(data_);
160 void MemoryBuffer::allocate(
size_t bytes)
163 data_ = ::operator
new(bytes);
167 namespace imgproc_impl
188 template<
class T,
class Bin>
190 histogram(
const Image<T> & image, T image_max, Bin bin_max)
195 std::vector<Bin> histogram(
size_t(image_max) + 1);
198 auto add_pixel_value = [&histogram, bin_max](T pixel) {
199 auto & h = histogram[pixel];
200 h = std::min(Bin(h + 1), bin_max);
203 image.forEach(add_pixel_value);
207 namespace out_of_bounds_policy
219 T & up(T * v)
const {
return *v;}
220 T & down(T * v)
const {
return *v;}
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} {}
249 if (up_row_start_ ==
nullptr) {
252 return replaceOutOfBounds(v, up_row_start_, up_row_end_);
261 return replaceOutOfBounds(v, down_row_start_, down_row_end_);
269 T & replaceOutOfBounds(T * v,
const T * begin,
const T * end)
271 if (v < begin || v >= end) {
277 const T * up_row_start_;
278 const T * up_row_end_;
279 const T * down_row_start_;
280 const T * down_row_end_;
297 template<
class T,
template<
class>
class Border>
307 inline Window(T * up_row, T * down_row, Border<T> border = {})
308 : up_row_{up_row}, down_row_{down_row}, border_{border} {}
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_;}
332 T * dropConst(
const T * ptr)
334 return const_cast<T *
>(ptr);
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)
355 dropConst(up_row) + offset, dropConst(down_row) + offset,
356 out_of_bounds_policy::ReplaceToZero<T>{up_row, down_row, columns}
369 Window<T, out_of_bounds_policy::DoNothing> makeUnsafeWindow(
const T * up_row,
const T * down_row)
371 return {dropConst(up_row), dropConst(down_row)};
382 : std::runtime_error(message) {}
392 template<
class Label>
405 const size_t max_labels_count = maxLabels(rows, columns, connectivity);
407 labels_size_ =
static_cast<Label
>(
408 std::min(max_labels_count,
size_t(std::numeric_limits<Label>::max()))
412 labels_.reserve(labels_size_);
420 labels_.resize(1, 0);
432 if (next_free_ == labels_size_) {
433 throw LabelOverflow(
"EquivalenceLabelTrees: Can't create new label");
435 labels_.push_back(next_free_);
448 Label root = findRoot(i);
451 Label root_j = findRoot(j);
452 root = std::min(root, root_j);
469 for (Label i = 1; i < next_free_; ++i) {
470 if (labels_[i] < i) {
471 labels_[i] = labels_[labels_[i]];
489 static size_t maxLabels(
const size_t rows,
const size_t columns,
ConnectivityType connectivity)
496 max_labels = (rows * columns) / 2 + 1;
507 max_labels = (rows * columns) / 3 + 1;
510 max_labels = std::min(max_labels,
size_t(std::numeric_limits<Label>::max()));
515 Label findRoot(Label i)
518 for (; labels_[root] < root; root = labels_[root]) { }
523 void setRoot(Label i, Label root)
525 while (labels_[i] < i) {
543 std::vector<Label> labels_;
544 Label labels_size_{};
549 template<ConnectivityType connectivity>
566 template<
class ImageWindow,
class LabelsWindow,
class Label,
class IsBg>
571 Label & current = label.e();
574 if (!is_bg(image.e())) {
578 if (!is_bg(image.c())) {
579 if (!is_bg(image.a())) {
580 current = eq_trees.
unionTrees(label.c(), label.a());
582 if (!is_bg(image.d())) {
583 current = eq_trees.
unionTrees(label.c(), label.d());
589 if (!is_bg(image.a())) {
592 if (!is_bg(image.d())) {
620 template<
class ImageWindow,
class LabelsWindow,
class Label,
class IsBg>
625 Label & current = label.e();
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());
636 if (!is_bg(image.d())) {
664 template<
class Apply>
668 const uint8_t * shape, Apply touch_fn)
670 const size_t rows = input.
rows() - std::max(first_input_row, first_output_row);
671 const size_t columns = input.
columns();
673 auto apply_shape = [&shape](uint8_t value, uint8_t index) -> uint8_t {
674 return value & shape[index];
677 auto get_input_row = [&input, first_input_row](
size_t row) {
678 return input.
row(row + first_input_row);
680 auto get_output_row = [&output, first_output_row](
size_t row) {
681 return output.
row(row + first_output_row);
685 for (
size_t i = 0; i < rows; ++i) {
687 auto overlay = {uint8_t(0), apply_shape(*get_input_row(i), 1), uint8_t(0)};
688 touch_fn(*get_output_row(i), overlay);
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);
698 auto overlay = {uint8_t(0), apply_shape(*in, 1), apply_shape(*(in + 1), 2)};
699 touch_fn(*out, overlay);
705 for (; in != last_column_pixel; ++in, ++out) {
707 apply_shape(*(in - 1), 0),
708 apply_shape(*(in), 1),
709 apply_shape(*(in + 1), 2)
711 touch_fn(*out, overlay);
716 auto overlay = {apply_shape(*(in - 1), 0), apply_shape(*(in), 1), uint8_t(0)};
717 touch_fn(*out, overlay);
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)
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");
749 if (shape.rows() != 3 || shape.columns() != 3) {
750 throw std::logic_error(
"morphologyOperation: wrong shape size");
758 auto set = [&](uint8_t & res, std::initializer_list<uint8_t> lst) {res = aggregate(lst);};
760 auto update = [&](uint8_t & res, std::initializer_list<uint8_t> lst) {
761 res = aggregate({res, aggregate(lst), 0});
768 probeRows(input, 0, output, 0, shape.row(1), set);
770 if (input.rows() > 1) {
775 probeRows(input, 0, output, 1, shape.row(0), update);
779 probeRows(input, 1, output, 0, shape.row(2), update);
787 Image<uint8_t> createShape(ShapeBuffer3x3 & buffer,
ConnectivityType connectivity)
794 static constexpr uint8_t u = 255;
795 static constexpr uint8_t i = 0;
808 return Image<uint8_t>(3, 3, buffer.data(), 3);
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)
820 using namespace imgproc_impl;
821 using PixelPass = ProcessPixel<connectivity>;
826 auto img = makeSafeWindow<uint8_t>(
nullptr, image.row(0), image.columns());
827 auto lbl = makeSafeWindow<Label>(
nullptr, labels.row(0), image.columns());
829 const uint8_t * first_row_end = image.row(0) + image.columns();
831 for (; img.anchor() < first_row_end; img.next(), lbl.next()) {
832 PixelPass::pass(img, lbl, label_trees, is_background);
837 for (
size_t row = 0; row < image.rows() - 1; ++row) {
839 Window<Label, out_of_bounds_policy::DoNothing> label_mask{labels.row(row), labels.row(row + 1)};
841 auto up = image.row(row);
842 auto current = image.row(row + 1);
846 auto img = makeSafeWindow(up, current, image.columns());
847 PixelPass::pass(img, label_mask, label_trees, is_background);
853 auto img = makeUnsafeWindow(std::next(up), std::next(current));
854 const uint8_t * current_row_last_element = current + image.columns() - 1;
856 for (; img.anchor() < current_row_last_element; img.next(), label_mask.next()) {
857 PixelPass::pass(img, label_mask, label_trees, is_background);
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);
871 const std::vector<Label> & labels_map = label_trees.getLabels();
878 return labels_map.size();
892 label_trees_ = std::make_unique<imgproc_impl::EquivalenceLabelTrees<uint16_t>>();
910 const IsBg & is_background)
const
913 removeGroupsPickLabelType<ConnectivityType::Way4>(
914 image, buffer, minimal_group_size,
917 removeGroupsPickLabelType<ConnectivityType::Way8>(
918 image, buffer, minimal_group_size,
931 template<ConnectivityType connectivity,
class IsBg>
932 void removeGroupsPickLabelType(
934 size_t minimal_group_size,
const IsBg & is_background)
const
941 success = tryRemoveGroupsWithLabelType<connectivity>(
942 image, buffer, minimal_group_size,
943 *label_trees16, is_background,
false);
948 dynamic_cast<imgproc_impl::EquivalenceLabelTrees<uint32_t> *
>(label_trees_.get());
950 if (!label_trees32) {
951 label_trees_ = std::make_unique<imgproc_impl::EquivalenceLabelTrees<uint32_t>>();
953 dynamic_cast<imgproc_impl::EquivalenceLabelTrees<uint32_t> *
>(label_trees_.get());
955 tryRemoveGroupsWithLabelType<connectivity>(
956 image, buffer, minimal_group_size, *label_trees32,
957 is_background,
true);
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
977 removeGroupsImpl<connectivity>(image, buffer, label_trees, minimal_group_size, is_background);
979 }
catch (imgproc_impl::LabelOverflow &) {
980 if (throw_on_label_overflow) {
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
995 auto labels = connectedComponents<connectivity>(
996 image, buffer, label_trees,
997 is_background, groups_count);
1001 const Label max_label_value = groups_count - 1;
1002 std::vector<size_t> groups_sizes = histogram(
1003 labels, max_label_value,
size_t(minimal_group_size + 1));
1008 if (!groups_sizes.empty()) {
1009 groups_sizes.front() = 0;
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;
1019 groups_sizes.begin(), groups_sizes.end(), noise_labels_table.begin(),
1024 image, [&](Label src, uint8_t & trg) {
1025 if (!is_background(trg) && noise_labels_table[src]) {
1032 mutable std::unique_ptr<imgproc_impl::EquivalenceLabelTreesBase> label_trees_;
1037 template<ConnectivityType connectivity,
class Label,
class IsBg>
1039 const Image<uint8_t> & image, MemoryBuffer & buffer,
1040 imgproc_impl::EquivalenceLabelTrees<Label> & label_trees,
1041 const IsBg & is_background,
1042 Label & total_labels)
1044 using namespace imgproc_impl;
1045 const size_t pixels = image.rows() * image.columns();
1049 return Image<Label>{};
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,
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...