Skip to content

Commit

Permalink
Merge branch 'enh-pursue-chessboard-detection' into 'master'
Browse files Browse the repository at this point in the history
ENH: accelerate Harris's cornerness function and basic blocks for image processing

See merge request DO-CV/sara!397
  • Loading branch information
Odd Kiva committed Jul 22, 2022
2 parents 7b05103 + e9a6ab1 commit cd1a9cc
Show file tree
Hide file tree
Showing 26 changed files with 1,121 additions and 341 deletions.
61 changes: 49 additions & 12 deletions cpp/examples/Sara/ImageProcessing/find_aruco_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,21 +19,20 @@
#include <exception>

#include <DO/Sara/Core/TicToc.hpp>
#include <DO/Sara/Geometry.hpp>
#include <DO/Sara/Graphics.hpp>
#include <DO/Sara/ImageIO.hpp>
#include <DO/Sara/VideoIO.hpp>

#include <DO/Sara/FeatureDetectors/Harris.hpp>
#include <DO/Sara/Geometry.hpp>
#include <DO/Sara/ImageProcessing.hpp>
#include <DO/Sara/ImageProcessing/AdaptiveBinaryThresholding.hpp>
#include <DO/Sara/ImageProcessing/CartesianToPolarCoordinates.hpp>
#include <DO/Sara/ImageProcessing/EdgeShapeStatistics.hpp>
#include <DO/Sara/ImageProcessing/FastColorConversion.hpp>
#include <DO/Sara/ImageProcessing/JunctionRefinement.hpp>
#include <DO/Sara/ImageProcessing/LinearFiltering.hpp>
#include <DO/Sara/ImageProcessing/Otsu.hpp>
#include <DO/Sara/VideoIO.hpp>

#include <DO/Sara/VideoIO/VideoWriter.hpp>

#include "Chessboard/NonMaximumSuppression.hpp"


namespace sara = DO::Sara;
Expand All @@ -54,7 +53,7 @@ struct Corner
}
};

#define INSPECT_PATCH
// #define INSPECT_PATCH
#ifdef INSPECT_PATCH
static constexpr auto square_size = 20;
static constexpr auto square_padding = 4;
Expand Down Expand Up @@ -138,10 +137,21 @@ auto __main(int argc, char** argv) -> int
auto video_frame_copy = sara::Image<sara::Rgb8>{};
auto frame_number = -1;

auto video_writer = sara::VideoWriter{
"/Users/david/Desktop/aruco_test.mp4", //
video_stream.sizes(), //
30 //
};

auto f = sara::Image<float>{video_frame.sizes()};
auto f_blurred = sara::Image<float>{video_frame.sizes()};

auto grad_f = std::array{sara::Image<float>{f.sizes()},
sara::Image<float>{f.sizes()}};
auto grad_f_norm = sara::Image<float>{video_frame.sizes()};
auto grad_f_ori = sara::Image<float>{video_frame.sizes()};

auto cornerness = sara::Image<float>{video_frame.sizes()};
auto segmentation_map = sara::Image<std::uint8_t>{video_frame.sizes()};

while (video_stream.read())
Expand All @@ -150,7 +160,6 @@ auto __main(int argc, char** argv) -> int
if (frame_number % 3 != 0)
continue;


if (sara::active_window() == nullptr)
{
sara::create_window(video_frame.sizes());
Expand All @@ -164,19 +173,30 @@ auto __main(int argc, char** argv) -> int

sara::tic();
sara::apply_gaussian_filter(f, f_blurred, sigma_D);
const auto grad_f = f_blurred.compute<sara::Gradient>();

#ifdef SLOW_IMPL
grad_f = f_blurred.compute<sara::Gradient>();
const auto M =
grad_f.compute<sara::SecondMomentMatrix>().compute<sara::Gaussian>(
sigma_I);
auto cornerness = sara::Image<float>{M.sizes()};
cornerness = sara::Image<float>{M.sizes()};
std::transform(
#if __has_include(<execution>) && !defined(__APPLE__)
# if __has_include(<execution>) && !defined(__APPLE__)
std::execution::par_unseq,
#endif
# endif
M.begin(), M.end(), cornerness.begin(), [kappa](const auto& m) {
return m.determinant() - kappa * pow(m.trace(), 2);
});
sara::gradient_in_polar_coordinates(f_blurred, grad_f_norm, grad_f_ori);
#else
sara::gradient(f_blurred, grad_f[0], grad_f[1]);
sara::cartesian_to_polar_coordinates(grad_f[0], grad_f[1], //
grad_f_norm, grad_f_ori);

cornerness = sara::harris_cornerness(grad_f[0], grad_f[1], //
sigma_I, kappa);
#endif

#if __has_include(<execution>) && !defined(__APPLE__)
const auto grad_max = *std::max_element(
std::execution::par_unseq, grad_f_norm.begin(), grad_f_norm.end());
Expand Down Expand Up @@ -275,9 +295,22 @@ auto __main(int argc, char** argv) -> int
quad.begin(), quad.end(), quad.begin(),
[&grad_f, sigma_I](const Eigen::Vector2d& c) -> Eigen::Vector2d {
static const auto radius = static_cast<int>(std::round(sigma_I));
const auto w = grad_f[0].width();
const auto h = grad_f[0].height();
const Eigen::Vector2i ci = c.array().round().cast<int>();
const auto in_domain = //
radius <= ci.x() && ci.x() < w - radius && //
radius <= ci.y() && ci.y() < h - radius;
if (!in_domain)
return ci.cast<double>();

#ifdef SLOW_IMPL
const auto p = sara::refine_junction_location_unsafe( //
grad_f, ci, radius);
#else
const auto p = sara::refine_junction_location_unsafe( //
grad_f[0], grad_f[1], ci, radius);
#endif
return p.cast<double>();
});

Expand Down Expand Up @@ -395,6 +428,10 @@ auto __main(int argc, char** argv) -> int
}
#endif
sara::toc("Display");

sara::tic();
video_writer.write(disp);
sara::toc("Video write");
}
}
catch (std::exception& e)
Expand Down
185 changes: 158 additions & 27 deletions cpp/examples/Sara/ImageProcessing/find_chessboard_corners_3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,11 @@

#include <DO/Sara/Core/PhysicalQuantities.hpp>
#include <DO/Sara/Core/TicToc.hpp>
#include <DO/Sara/FeatureDescriptors.hpp>
#include <DO/Sara/FeatureDetectors.hpp>
#include <DO/Sara/Graphics.hpp>
#include <DO/Sara/ImageProcessing/AdaptiveBinaryThresholding.hpp>
#include <DO/Sara/ImageProcessing/CartesianToPolarCoordinates.hpp>
#include <DO/Sara/ImageProcessing/EdgeShapeStatistics.hpp>
#include <DO/Sara/ImageProcessing/FastColorConversion.hpp>
#include <DO/Sara/ImageProcessing/JunctionRefinement.hpp>
Expand Down Expand Up @@ -78,6 +80,66 @@ auto select(const sara::ImageView<float>& cornerness,
};


template <Eigen::Index N>
void compute_orientation_histogram(
Eigen::Array<float, N, 1>& orientation_histogram,
const sara::ImageView<float>& grad_f_norm,
const sara::ImageView<float>& grad_f_ori, //
const float x, const float y, const float s, //
const float patch_truncation_factor = 3.f, //
const float blur_factor = 1.5f)
{
// Weighted histogram of gradients.
orientation_histogram.setZero();

// Rounding of the coordinates.
static constexpr auto int_round = [](const float x) {
return static_cast<int>(std::round(x));
};
auto rounded_x = int_round(x);
auto rounded_y = int_round(y);

// std deviation of the gaussian weight (cf. [Lowe, IJCV 2004])
auto sigma = s * blur_factor;

// Patch radius on which the histogram of gradients is performed.
auto patch_radius = int_round(sigma * patch_truncation_factor);
const auto w = grad_f_norm.width();
const auto h = grad_f_norm.height();

const auto one_over_two_sigma_square = 1 / (2.f * sigma * sigma);

// Accumulate the histogram of orientations.
for (auto v = -patch_radius; v <= patch_radius; ++v)
{
for (auto u = -patch_radius; u <= patch_radius; ++u)
{
if (rounded_x + u < 0 || rounded_x + u >= w || //
rounded_y + v < 0 || rounded_y + v >= h)
continue;

const auto mag = grad_f_norm(rounded_x + u, rounded_y + v);
auto ori = grad_f_ori(rounded_x + u, rounded_y + v);

// ori is in \f$]-\pi, \pi]\f$, so translate ori by \f$2*\pi\f$ if it is
// negative.
static constexpr auto two_pi = static_cast<float>(2 * M_PI);
static constexpr auto normalization_factor = N / two_pi;

ori = ori < 0 ? ori + two_pi : ori;
auto bin_index = static_cast<int>(std::floor(ori * normalization_factor));
bin_index %= N;

// Give more emphasis to gradient orientations that lie closer to the
// keypoint location.
auto weight = exp(-(u * u + v * v) * one_over_two_sigma_square);
// Also give more emphasis to gradient with large magnitude.
orientation_histogram(bin_index) += weight * mag;
}
}
}


auto __main(int argc, char** argv) -> int
{
omp_set_num_threads(omp_get_max_threads());
Expand All @@ -95,7 +157,7 @@ auto __main(int argc, char** argv) -> int
// Harris cornerness parameters.
//
// Blur parameter before gradient calculation.
const auto sigma_D = argc < 3 ? 0.8f : std::stof(argv[2]);
const auto sigma_D = argc < 3 ? 1.f : std::stof(argv[2]);
// Integration domain of the second moment.
const auto sigma_I = argc < 4 ? 3.f : std::stof(argv[3]);
// Threshold parameter.
Expand Down Expand Up @@ -155,17 +217,16 @@ auto __main(int argc, char** argv) -> int
sara::toc("Downscale");

sara::tic();
ed(frame_gray_ds);
const auto f_ds_blurred = frame_gray_ds.compute<sara::Gaussian>(sigma_D);
ed(f_ds_blurred);
sara::toc("Curve detection");

sara::tic();
const auto cornerness = sara::scale_adapted_harris_cornerness( //
frame_gray_ds, //
sigma_I, sigma_D, //
kappa //
);
const auto grad_f =
frame_gray_ds.compute<sara::Gaussian>(0.5f).compute<sara::Gradient>();
auto grad_x = sara::Image<float>{f_ds_blurred.sizes()};
auto grad_y = sara::Image<float>{f_ds_blurred.sizes()};
sara::gradient(f_ds_blurred, grad_x, grad_y);
const auto cornerness =
sara::harris_cornerness(grad_x, grad_y, sigma_I, kappa);
static const auto border = static_cast<int>(std::round(sigma_I));
auto corners_int = select(cornerness, cornerness_adaptive_thres, border);
sara::toc("Corner detection");
Expand All @@ -174,14 +235,56 @@ auto __main(int argc, char** argv) -> int
auto corners = std::vector<Corner<float>>{};
std::transform(
corners_int.begin(), corners_int.end(), std::back_inserter(corners),
[&grad_f, sigma_I](const Corner<int>& c) -> Corner<float> {
[&grad_x, &grad_y, sigma_I](const Corner<int>& c) -> Corner<float> {
static const auto radius = static_cast<int>(std::round(sigma_I));
const auto p =
sara::refine_junction_location_unsafe(grad_f, c.coords, radius);
const auto p = sara::refine_junction_location_unsafe(
grad_x, grad_y, c.coords, radius);
return {p, c.score};
});
sara::toc("Corner refinement");

sara::tic();
const auto& grad_norm = ed.pipeline.gradient_magnitude;
const auto& grad_ori = ed.pipeline.gradient_orientation;

static constexpr auto N = 36;
auto hists = std::vector<Eigen::Array<float, N, 1>>{};
hists.resize(corners.size());
std::transform(
corners.begin(), corners.end(), hists.begin(),
[&grad_norm, &grad_ori, sigma_D](const Corner<float>& corner) {
auto h = Eigen::Array<float, N, 1>{};
compute_orientation_histogram<N>(h, grad_norm, grad_ori,
corner.coords.x(), corner.coords.y(),
sigma_D * 4.);
return h;
});
std::for_each(hists.begin(), hists.end(), [](auto& h) {
sara::lowe_smooth_histogram(h);
h.matrix().normalize();
});
sara::toc("Gradient histograms");

sara::tic();
auto gradient_peaks = std::vector<std::vector<int>>{};
gradient_peaks.resize(hists.size());
std::transform(hists.begin(), hists.end(), gradient_peaks.begin(),
[](const auto& h) { return sara::find_peaks(h, 0.5f); });
auto gradient_peaks_refined = std::vector<std::vector<float>>{};
gradient_peaks_refined.resize(gradient_peaks.size());
std::transform(gradient_peaks.begin(), gradient_peaks.end(), hists.begin(),
gradient_peaks_refined.begin(),
[](const auto& peaks, const auto& hist) {
auto peaks_ref = std::vector<float>{};
std::transform(peaks.begin(), peaks.end(),
std::back_inserter(peaks_ref),
[&hist](const auto& i) {
return sara::refine_peak(hist, i);
});
return peaks_ref;
});
sara::toc("Gradient Dominant Orientations");

sara::tic();
auto edge_label_map = sara::Image<int>{ed.pipeline.edge_map.sizes()};
edge_label_map.flat_array().fill(-1);
Expand Down Expand Up @@ -226,28 +329,55 @@ auto __main(int argc, char** argv) -> int
sara::toc("X-junction filter");

sara::tic();
#define SHOW_EDGE_MAP
#ifdef SHOW_EDGE_MAP
const auto display_u8 = sara::upscale(ed.pipeline.edge_map, 2);
auto display = sara::Image<sara::Rgb8>{video_frame.sizes()};
std::transform(display_u8.begin(), display_u8.end(), display.begin(),
[](const auto& v) {
return v != 0 ? sara::Rgb8(64, 64, 64) : sara::Black8;
});
#else
auto display = frame_gray.convert<sara::Rgb8>();
#endif

auto count = 0;
for (auto c = 0u; c < corners.size(); ++c)
{
const auto& p = corners[c];
const auto& edges = adjacent_edges[c];
if (edges.size() != 4)
continue;

for (const auto& curve_index : edges)
{
const auto& curve_simplified =
ed.pipeline.edges_simplified[curve_index];
const auto good = gradient_peaks_refined[c].size() == 4;
// if (edges.size() != 4)
// continue;

// const auto color = sara::Rgb8(rand() % 255, rand() % 255, rand() %
// 255);
const auto color = sara::Cyan8;
for (auto i = 0u; i < curve_simplified.size() - 1; ++i)
++count;

if (good)
{
for (const auto& curve_index : edges)
{
const auto a = curve_simplified[i].cast<float>() * downscale_factor;
const auto b =
curve_simplified[i + 1u].cast<float>() * downscale_factor;
sara::draw_line(display, a, b, color, 2);
const auto color =
sara::Rgb8(rand() % 255, rand() % 255, rand() % 255);
// const auto color = sara::Cyan8;
#if 0
const auto& curve = ed.pipeline.edges_simplified[curve_index];
for (auto i = 0u; i < curve.size() - 1; ++i)
{
const auto a = curve[i].cast<float>() * downscale_factor;
const auto b =
curve[i + 1u].cast<float>() * downscale_factor;
sara::draw_line(display, a, b, color, 2);
}
#else
const auto& curve = ed.pipeline.edges_as_list[curve_index];
for (const auto& p : curve)
display(p * downscale_factor) = color;
// sara::fill_circle(display, //
// downscale_factor * p.x(), //
// downscale_factor * p.y(), //
// 1, color);
#endif
}
}

Expand All @@ -260,8 +390,9 @@ auto __main(int argc, char** argv) -> int
display,
static_cast<int>(std::round(downscale_factor * p.coords.x())),
static_cast<int>(std::round(downscale_factor * p.coords.y())), 4,
sara::Red8, 2);
good ? sara::Red8 : sara::Blue8, 2);
}
SARA_CHECK(count);
sara::draw_text(display, 80, 80, std::to_string(frame_number), sara::White8,
60, 0, false, true);
sara::display(display);
Expand Down
Loading

0 comments on commit cd1a9cc

Please sign in to comment.