33#include "ceres/ceres.h"
51 static void SetScalar(
const T& scalar, T* t) { *t = scalar; }
59template <
typename T,
int N>
62 static T
GetScalar(
const Jet<T, N>& t) {
return t.a; }
63 static void SetScalar(
const T& scalar, Jet<T, N>* t) { t->a = scalar; }
69template <
typename FunctionType,
int kNumArgs,
typename ArgumentType>
71 static ArgumentType
Rule(
const FunctionType& f,
72 const FunctionType dfdx[kNumArgs],
73 const ArgumentType x[kNumArgs]) {
83template <
typename FunctionType,
int kNumArgs,
typename T,
int N>
84struct Chain<FunctionType, kNumArgs, Jet<T,
N>> {
85 static Jet<T, N>
Rule(
const FunctionType& f,
86 const FunctionType dfdx[kNumArgs],
87 const Jet<T, N> x[kNumArgs]) {
92 Eigen::Matrix<T, kNumArgs, N> dxdz;
93 for (
int i = 0; i < kNumArgs; ++i) {
94 dxdz.row(i) = x[i].v.transpose();
98 Eigen::Map<const Eigen::Matrix<FunctionType, 1, kNumArgs>> vector_dfdx(
105 jet_f.v = vector_dfdx.template
cast<T>() * dxdz;
121 minimum_correlation(0),
124 use_brute_initialization(
true),
125 use_normalized_intensities(
false),
128 regularization_coefficient(0.0),
129 minimum_corner_shift_tolerance_pixels(0.005),
137bool InBounds(
const FloatImage& image,
const T& x,
const T& y) {
138 return 0.0 <= x && x < image.Width() && 0.0 <= y && y < image.Height();
141bool AllInBounds(
const FloatImage& image,
const double* x,
const double* y) {
142 for (
int i = 0; i < 4; ++i) {
143 if (!InBounds(image, x[i], y[i])) {
154static T SampleWithDerivative(
const FloatImage& image_and_gradient,
175template <
typename Warp>
176class TerminationCheckingCallback :
public ceres::IterationCallback {
178 TerminationCheckingCallback(
const TrackRegionOptions&
options,
188 have_last_successful_step_(
false) {}
191 const ceres::IterationSummary& summary) {
193 if (!summary.step_is_successful) {
194 return ceres::SOLVER_CONTINUE;
199 for (
int i = 0; i < 4; ++i) {
200 warp_.Forward(warp_.parameters, x1_[i], y1_[i], x2 + i, y2 + i);
203 if (!AllInBounds(image2_, x2, y2)) {
204 LG <<
"Successful step fell outside of the pattern bounds; aborting.";
205 return ceres::SOLVER_ABORT;
214 if (have_last_successful_step_) {
217 double max_change_pixels = 0;
218 for (
int i = 0; i < 4; ++i) {
219 double dx = x2[i] - x2_last_successful_[i];
220 double dy = y2[i] - y2_last_successful_[i];
221 double change_pixels = dx * dx + dy * dy;
222 if (change_pixels > max_change_pixels) {
223 max_change_pixels = change_pixels;
226 max_change_pixels =
sqrt(max_change_pixels);
227 LG <<
"Max patch corner shift is " << max_change_pixels;
230 if (max_change_pixels < options_.minimum_corner_shift_tolerance_pixels) {
231 LG <<
"Max patch corner shift is " << max_change_pixels
232 <<
" from the last iteration; returning success.";
233 return ceres::SOLVER_TERMINATE_SUCCESSFULLY;
238 for (
int i = 0; i < 4; ++i) {
239 x2_last_successful_[i] = x2[i];
240 y2_last_successful_[i] = y2[i];
242 have_last_successful_step_ =
true;
243 return ceres::SOLVER_CONTINUE;
247 const TrackRegionOptions& options_;
253 bool have_last_successful_step_;
254 double x2_last_successful_[4];
255 double y2_last_successful_[4];
258template <
typename Warp>
259class PixelDifferenceCostFunctor {
261 PixelDifferenceCostFunctor(
const TrackRegionOptions&
options,
264 const Mat3& canonical_to_image1,
269 image_and_gradient1_(image_and_gradient1),
270 image_and_gradient2_(image_and_gradient2),
271 canonical_to_image1_(canonical_to_image1),
272 num_samples_x_(num_samples_x),
273 num_samples_y_(num_samples_y),
275 pattern_and_gradient_(num_samples_y_, num_samples_x_, 3),
276 pattern_positions_(num_samples_y_, num_samples_x_, 2),
277 pattern_mask_(num_samples_y_, num_samples_x_, 1) {
278 ComputeCanonicalPatchAndNormalizer();
281 void ComputeCanonicalPatchAndNormalizer() {
283 double num_samples = 0.0;
284 for (
int r = 0; r < num_samples_y_; ++r) {
285 for (
int c = 0; c < num_samples_x_; ++c) {
287 Vec3 image_position = canonical_to_image1_ *
Vec3(c, r, 1);
288 image_position /= image_position(2);
289 pattern_positions_(r, c, 0) = image_position(0);
290 pattern_positions_(r, c, 1) = image_position(1);
296 &pattern_and_gradient_(r, c, 0));
299 double mask_value = 1.0;
300 if (options_.image1_mask !=
NULL) {
304 &pattern_mask_(r, c, 0));
305 mask_value = pattern_mask_(r, c);
307 src_mean_ += pattern_and_gradient_(r, c, 0) * mask_value;
308 num_samples += mask_value;
311 src_mean_ /= num_samples;
314 template <
typename T>
315 bool operator()(
const T* warp_parameters, T* residuals)
const {
316 if (options_.image1_mask !=
NULL) {
317 VLOG(2) <<
"Using a mask.";
319 for (
int i = 0; i < Warp::NUM_PARAMETERS; ++i) {
320 VLOG(2) <<
"warp_parameters[" << i <<
"]: " << warp_parameters[i];
324 if (options_.use_normalized_intensities) {
325 ComputeNormalizingCoefficient(warp_parameters, &dst_mean);
329 for (
int r = 0; r < num_samples_y_; ++r) {
330 for (
int c = 0; c < num_samples_x_; ++c) {
332 Vec2 image1_position(pattern_positions_(r, c, 0),
333 pattern_positions_(r, c, 1));
347 double mask_value = 1.0;
348 if (options_.image1_mask !=
NULL) {
349 mask_value = pattern_mask_(r, c);
350 if (mask_value == 0.0) {
351 residuals[cursor++] =
T(0.0);
357 T image2_position[2];
358 warp_.Forward(warp_parameters,
359 T(image1_position[0]),
360 T(image1_position[1]),
362 &image2_position[1]);
365 T dst_sample = SampleWithDerivative(
366 image_and_gradient2_, image2_position[0], image2_position[1]);
375 T image1_position_jet[2] = {
387 &pattern_and_gradient_(r, c, 1),
388 image1_position_jet);
397 src_sample =
T(pattern_and_gradient_(r, c));
404 if (options_.use_normalized_intensities) {
405 src_sample /=
T(src_mean_);
406 dst_sample /= dst_mean;
410 T
error = src_sample - dst_sample;
413 if (options_.image1_mask !=
NULL) {
416 residuals[cursor++] =
error;
423 template <
typename T>
424 void ComputeNormalizingCoefficient(
const T* warp_parameters,
427 double num_samples = 0.0;
428 for (
int r = 0; r < num_samples_y_; ++r) {
429 for (
int c = 0; c < num_samples_x_; ++c) {
431 Vec2 image1_position(pattern_positions_(r, c, 0),
432 pattern_positions_(r, c, 1));
436 double mask_value = 1.0;
437 if (options_.image1_mask !=
NULL) {
438 mask_value = pattern_mask_(r, c);
439 if (mask_value == 0.0) {
445 T image2_position[2];
446 warp_.Forward(warp_parameters,
447 T(image1_position[0]),
448 T(image1_position[1]),
450 &image2_position[1]);
456 T dst_sample = SampleWithDerivative(
457 image_and_gradient2_, image2_position[0], image2_position[1]);
460 if (options_.image1_mask !=
NULL) {
461 dst_sample *=
T(mask_value);
464 *dst_mean += dst_sample;
465 num_samples += mask_value;
468 *dst_mean /=
T(num_samples);
469 LG <<
"Normalization for dst:" << *dst_mean;
473 double PearsonProductMomentCorrelationCoefficient(
474 const double* warp_parameters)
const {
475 for (
int i = 0; i < Warp::NUM_PARAMETERS; ++i) {
476 VLOG(2) <<
"Correlation warp_parameters[" << i
477 <<
"]: " << warp_parameters[i];
482 double sX = 0, sY = 0, sXX = 0, sYY = 0, sXY = 0;
486 double num_samples = 0;
488 for (
int r = 0; r < num_samples_y_; ++r) {
489 for (
int c = 0; c < num_samples_x_; ++c) {
491 Vec2 image1_position(pattern_positions_(r, c, 0),
492 pattern_positions_(r, c, 1));
494 double mask_value = 1.0;
495 if (options_.image1_mask !=
NULL) {
496 mask_value = pattern_mask_(r, c);
497 if (mask_value == 0.0) {
503 double image2_position[2];
504 warp_.Forward(warp_parameters,
508 &image2_position[1]);
510 double x = pattern_and_gradient_(r, c);
516 if (options_.image1_mask !=
NULL) {
519 num_samples += mask_value;
537 double var_x = sXX - sX * sX;
538 double var_y = sYY - sY * sY;
539 double covariance_xy = sXY - sX * sY;
541 double correlation = covariance_xy /
sqrt(var_x * var_y);
542 LG <<
"Covariance xy: " << covariance_xy <<
", var 1: " << var_x
543 <<
", var 2: " << var_y <<
", correlation: " << correlation;
548 const TrackRegionOptions& options_;
551 const Mat3& canonical_to_image1_;
566template <
typename Warp>
567class WarpRegularizingCostFunctor {
569 WarpRegularizingCostFunctor(
const TrackRegionOptions&
options,
572 const double* x2_original,
573 const double* y2_original,
585 for (
int i = 0; i < 4; ++i) {
593 template <
typename T>
594 bool operator()(
const T* warp_parameters, T* residuals)
const {
595 T dst_centroid[2] = {
T(0.0),
T(0.0)};
596 for (
int i = 0; i < 4; ++i) {
597 T image1_position[2] = {
T(x1_[i]),
T(y1_[i])};
598 T image2_position[2];
599 warp_.Forward(warp_parameters,
603 &image2_position[1]);
606 residuals[2 * i + 0] = image2_position[0] - image1_position[0];
607 residuals[2 * i + 1] = image2_position[1] - image1_position[1];
610 dst_centroid[0] += image2_position[0];
611 dst_centroid[1] += image2_position[1];
613 dst_centroid[0] /=
T(4.0);
614 dst_centroid[1] /=
T(4.0);
617 for (
int i = 0; i < 4; ++i) {
618 residuals[2 * i + 0] +=
T(original_centroid_[0]) - dst_centroid[0];
619 residuals[2 * i + 1] +=
T(original_centroid_[1]) - dst_centroid[1];
623 for (
int i = 0; i < 8; ++i) {
624 residuals[i] *=
T(options_.regularization_coefficient);
630 const TrackRegionOptions& options_;
641Mat3 ComputeCanonicalHomography(
const double* x1,
646 canonical << 0, num_samples_x, num_samples_x, 0, 0, 0, num_samples_y,
651 xy1 << x1[0], x1[1], x1[2], x1[3],
652 y1[0], y1[1], y1[2], y1[3];
657 LG <<
"Couldn't construct homography.";
664 Quad(
const double* x,
const double* y) :
x_(x),
y_(y) {
666 centroid_ =
Vec2(0.0, 0.0);
667 for (
int i = 0; i < 4; ++i) {
668 centroid_ +=
Vec2(x_[i], y_[i]);
674 const Vec2& Centroid()
const {
return centroid_; }
677 double Scale()
const {
679 for (
int i = 0; i < 4; ++i) {
680 scale += (
Vec2(x_[i], y_[i]) - Centroid()).
norm();
685 Vec2 CornerRelativeToCentroid(
int i)
const {
686 return Vec2(x_[i], y_[i]) - centroid_;
695struct TranslationWarp {
696 TranslationWarp(
const double* x1,
700 Vec2 t = Quad(x2, y2).Centroid() - Quad(x1, y1).Centroid();
705 template <
typename T>
707 const T* warp_parameters,
const T& x1,
const T& y1, T* x2, T* y2)
const {
708 *x2 = x1 + warp_parameters[0];
709 *y2 = y1 + warp_parameters[1];
713 enum { NUM_PARAMETERS = 2 };
717struct TranslationScaleWarp {
718 TranslationScaleWarp(
const double* x1,
726 Vec2 t = q2.Centroid() -
q1.Centroid();
737 template <
typename T>
739 const T* warp_parameters,
const T& x1,
const T& y1, T* x2, T* y2)
const {
741 const T x1_origin = x1 -
q1.Centroid()(0);
742 const T y1_origin = y1 -
q1.Centroid()(1);
745 const T scale = 1.0 + warp_parameters[2];
746 const T x1_origin_scaled = scale * x1_origin;
747 const T y1_origin_scaled = scale * y1_origin;
750 const T x1_scaled = x1_origin_scaled +
q1.Centroid()(0);
751 const T y1_scaled = y1_origin_scaled +
q1.Centroid()(1);
754 *x2 = x1_scaled + warp_parameters[0];
755 *y2 = y1_scaled + warp_parameters[1];
759 enum { NUM_PARAMETERS = 3 };
766Mat2 OrthogonalProcrustes(
const Mat2& correlation_matrix) {
767 Eigen::JacobiSVD<Mat2> svd(correlation_matrix,
768 Eigen::ComputeFullU | Eigen::ComputeFullV);
769 return svd.matrixV() * svd.matrixU().transpose();
772struct TranslationRotationWarp {
773 TranslationRotationWarp(
const double* x1,
781 Vec2 t = q2.Centroid() -
q1.Centroid();
786 Mat2 correlation_matrix = Mat2::Zero();
787 for (
int i = 0; i < 4; ++i) {
788 correlation_matrix +=
q1.CornerRelativeToCentroid(i) *
789 q2.CornerRelativeToCentroid(i).transpose();
791 Mat2 R = OrthogonalProcrustes(correlation_matrix);
794 LG <<
"Correlation_matrix:\n" << correlation_matrix;
809 template <
typename T>
811 const T* warp_parameters,
const T& x1,
const T& y1, T* x2, T* y2)
const {
813 const T x1_origin = x1 -
q1.Centroid()(0);
814 const T y1_origin = y1 -
q1.Centroid()(1);
817 const T theta = warp_parameters[2];
818 const T costheta =
cos(theta);
819 const T sintheta =
sin(theta);
820 const T x1_origin_rotated = costheta * x1_origin - sintheta * y1_origin;
821 const T y1_origin_rotated = sintheta * x1_origin + costheta * y1_origin;
824 const T x1_rotated = x1_origin_rotated +
q1.Centroid()(0);
825 const T y1_rotated = y1_origin_rotated +
q1.Centroid()(1);
828 *x2 = x1_rotated + warp_parameters[0];
829 *y2 = y1_rotated + warp_parameters[1];
833 enum { NUM_PARAMETERS = 3 };
839struct TranslationRotationScaleWarp {
840 TranslationRotationScaleWarp(
const double* x1,
848 Vec2 t = q2.Centroid() -
q1.Centroid();
856 Mat2 correlation_matrix = Mat2::Zero();
857 for (
int i = 0; i < 4; ++i) {
858 correlation_matrix +=
q1.CornerRelativeToCentroid(i) *
859 q2.CornerRelativeToCentroid(i).transpose();
861 Mat2 R = OrthogonalProcrustes(correlation_matrix);
864 LG <<
"Correlation_matrix:\n" << correlation_matrix;
879 template <
typename T>
881 const T* warp_parameters,
const T& x1,
const T& y1, T* x2, T* y2)
const {
883 const T x1_origin = x1 -
q1.Centroid()(0);
884 const T y1_origin = y1 -
q1.Centroid()(1);
887 const T theta = warp_parameters[3];
888 const T costheta =
cos(theta);
889 const T sintheta =
sin(theta);
890 const T x1_origin_rotated = costheta * x1_origin - sintheta * y1_origin;
891 const T y1_origin_rotated = sintheta * x1_origin + costheta * y1_origin;
894 const T scale = 1.0 + warp_parameters[2];
895 const T x1_origin_rotated_scaled = scale * x1_origin_rotated;
896 const T y1_origin_rotated_scaled = scale * y1_origin_rotated;
899 const T x1_rotated_scaled = x1_origin_rotated_scaled +
q1.Centroid()(0);
900 const T y1_rotated_scaled = y1_origin_rotated_scaled +
q1.Centroid()(1);
903 *x2 = x1_rotated_scaled + warp_parameters[0];
904 *y2 = y1_rotated_scaled + warp_parameters[1];
909 enum { NUM_PARAMETERS = 4 };
916 AffineWarp(
const double* x1,
924 Vec2 t = q2.Centroid() -
q1.Centroid();
931 for (
int i = 0; i < 4; ++i) {
932 Vec2 v1 =
q1.CornerRelativeToCentroid(i);
933 Vec2
v2 = q2.CornerRelativeToCentroid(i);
935 Q1.row(2 * i + 0) << v1[0], v1[1], 0, 0;
936 Q1.row(2 * i + 1) << 0, 0, v1[0], v1[1];
938 Q2(2 * i + 0) =
v2[0];
939 Q2(2 * i + 1) =
v2[1];
943 Vec4 a = Q1.jacobiSvd(Eigen::ComputeThinU | Eigen::ComputeThinV).solve(Q2);
949 LG <<
"a:" << a.transpose();
950 LG <<
"t:" << t.transpose();
954 template <
typename T>
955 void Forward(
const T* p,
const T& x1,
const T& y1, T* x2, T* y2)
const {
957 const T x1_origin = x1 -
q1.Centroid()(0);
958 const T y1_origin = y1 -
q1.Centroid()(1);
961 const T x1_origin_affine = p[2] * x1_origin + p[3] * y1_origin;
962 const T y1_origin_affine = p[4] * x1_origin + p[5] * y1_origin;
965 const T x1_affine = x1_origin_affine +
q1.Centroid()(0);
966 const T y1_affine = y1_origin_affine +
q1.Centroid()(1);
969 *x2 = x1_affine + p[0];
970 *y2 = y1_affine + p[1];
975 enum { NUM_PARAMETERS = 6 };
981struct HomographyWarp {
982 HomographyWarp(
const double* x1,
988 quad1 << x1[0], x1[1], x1[2], x1[3],
989 y1[0], y1[1], y1[2], y1[3];
994 quad2 << x2[0], x2[1], x2[2], x2[3],
995 y2[0], y2[1], y2[2], y2[3];
1000 LG <<
"Couldn't construct homography.";
1011 for (
int i = 0; i < 8; ++i) {
1017 template <
typename T>
1018 static void Forward(
const T* p,
const T& x1,
const T& y1, T* x2, T* y2) {
1020 const T xx2 = (1.0 + p[0]) * x1 + p[1] * y1 + p[2];
1021 const T yy2 = p[3] * x1 + (1.0 + p[4]) * y1 + p[5];
1022 const T zz2 = p[6] * x1 + p[7] * y1 + 1.0;
1027 enum { NUM_PARAMETERS = 8 };
1038void PickSampling(
const double* x1,
1043 int* num_samples_y) {
1047 Vec2 a0(x1[0], y1[0]);
1048 Vec2 a1(x1[1], y1[1]);
1049 Vec2 a2(x1[2], y1[2]);
1050 Vec2 a3(x1[3], y1[3]);
1052 Vec2 b0(x1[0], y1[0]);
1053 Vec2 b1(x1[1], y1[1]);
1054 Vec2 b2(x1[2], y1[2]);
1055 Vec2 b3(x1[3], y1[3]);
1057 double x_dimensions[4] = {
1060 double y_dimensions[4] = {
1062 const double kScaleFactor = 1.0;
1063 *num_samples_x =
static_cast<int>(
1064 kScaleFactor * *std::max_element(x_dimensions, x_dimensions + 4));
1065 *num_samples_y =
static_cast<int>(
1066 kScaleFactor * *std::max_element(y_dimensions, y_dimensions + 4));
1067 LG <<
"Automatic num_samples_x: " << *num_samples_x
1068 <<
", num_samples_y: " << *num_samples_y;
1071bool SearchAreaTooBigForDescent(
const FloatImage& image2,
1082bool PointOnRightHalfPlane(
const Vec2& a,
const Vec2&
b,
double x,
double y) {
1100bool PointInQuad(
const double* xs,
const double* ys,
double x,
double y) {
1101 Vec2 a0(xs[0], ys[0]);
1102 Vec2 a1(xs[1], ys[1]);
1103 Vec2 a2(xs[2], ys[2]);
1104 Vec2 a3(xs[3], ys[3]);
1106 return PointOnRightHalfPlane(a0, a1, x, y) &&
1107 PointOnRightHalfPlane(a1, a2, x, y) &&
1108 PointOnRightHalfPlane(a2, a3, x, y) &&
1109 PointOnRightHalfPlane(a3, a0, x, y);
1114typedef Eigen::Array<float, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>
1119template <
typename Warp>
1120void CreateBrutePattern(
const double* x1,
1126 FloatArray* pattern,
1131 int min_x =
static_cast<int>(
floor(*std::min_element(x2, x2 + 4)));
1132 int min_y =
static_cast<int>(
floor(*std::min_element(y2, y2 + 4)));
1133 int max_x =
static_cast<int>(
ceil(*std::max_element(x2, x2 + 4)));
1134 int max_y =
static_cast<int>(
ceil(*std::max_element(y2, y2 + 4)));
1136 int w = max_x - min_x;
1137 int h = max_y - min_y;
1139 pattern->resize(h,
w);
1142 Warp inverse_warp(x2, y2, x1, y1);
1145 for (
int r = min_y; r < max_y; ++r) {
1146 for (
int c = min_x; c < max_x; ++c) {
1155 inverse_warp.Forward(
1156 inverse_warp.parameters, dst_x, dst_y, &src_x, &src_y);
1158 if (PointInQuad(x1, y1, src_x, src_y)) {
1160 (*mask)(i, j) = 1.0;
1162 (*mask)(i, j) =
SampleLinear(*image1_mask, src_y, src_x);
1165 (*pattern)(i, j) = 0.0;
1166 (*mask)(i, j) = 0.0;
1191template <
typename Warp>
1192bool BruteTranslationOnlyInitialize(
const FloatImage& image1,
1195 const int num_extra_points,
1196 const bool use_normalized_intensities,
1206 int origin_x = -1, origin_y = -1;
1207 CreateBrutePattern<Warp>(x1,
1219 double mask_sum = 1.0;
1220 if (use_normalized_intensities) {
1221 mask_sum = mask.sum();
1222 double inverse_pattern_mean = mask_sum / ((mask * pattern).
sum());
1223 pattern *= inverse_pattern_mean;
1227 Map<const FloatArray> search(image2.Data(), image2.Height(), image2.Width());
1241 double best_sad = std::numeric_limits<double>::max();
1244 int w = pattern.cols();
1245 int h = pattern.rows();
1247 for (
int r = 0; r < (image2.Height() - h); ++r) {
1248 for (
int c = 0; c < (image2.Width() -
w); ++c) {
1253 if (use_normalized_intensities) {
1257 double inverse_search_mean =
1258 mask_sum / ((mask * search.block(r, c, h,
w)).
sum());
1260 (pattern - (search.block(r, c, h,
w) * inverse_search_mean)))
1264 sad = (mask * (pattern - search.block(r, c, h,
w))).abs().sum();
1266 if (sad < best_sad) {
1276 if (best_r == -1 || best_c == -1) {
1280 LG <<
"Brute force translation found a shift. "
1281 <<
"best_c: " << best_c <<
", best_r: " << best_r <<
", "
1282 <<
"origin_x: " << origin_x <<
", origin_y: " << origin_y <<
", "
1283 <<
"dc: " << (best_c - origin_x) <<
", "
1284 <<
"dr: " << (best_r - origin_y) <<
", tried "
1285 << ((image2.Height() - h) * (image2.Width() -
w)) <<
" shifts.";
1288 for (
int i = 0; i < 4 + num_extra_points; ++i) {
1289 x2[i] += best_c - origin_x;
1290 y2[i] += best_r - origin_y;
1295void CopyQuad(
double* src_x,
1299 int num_extra_points) {
1300 for (
int i = 0; i < 4 + num_extra_points; ++i) {
1301 dst_x[i] = src_x[i];
1302 dst_y[i] = src_y[i];
1308template <
typename Warp>
1317 for (
int i = 0; i < 4 +
options.num_extra_points; ++i) {
1318 LG <<
"P" << i <<
": (" << x1[i] <<
", " << y1[i] <<
"); guess (" << x2[i]
1319 <<
", " << y2[i] <<
"); (dx, dy): (" << (x2[i] - x1[i]) <<
", "
1320 << (y2[i] - y1[i]) <<
").";
1326 if (
options.attempt_refine_before_brute) {
1331 double x2_first_try[5];
1332 double y2_first_try[5];
1333 CopyQuad(x2, y2, x2_first_try, y2_first_try,
options.num_extra_points);
1350 LG <<
"Terminated with first try at refinement; no brute needed.";
1352 CopyQuad(x2_first_try, y2_first_try, x2, y2,
options.num_extra_points);
1353 LG <<
"Early termination correlation: " << result->correlation;
1356 LG <<
"Initial eager-refinement failed; retrying normally.";
1360 if (
options.use_normalized_intensities) {
1361 LG <<
"Using normalized intensities.";
1365 if (!AllInBounds(image1, x1, y1)) {
1369 if (!AllInBounds(image2, x2, y2)) {
1376 double x2_original[4];
1377 double y2_original[4];
1378 for (
int i = 0; i < 4; ++i) {
1379 x2_original[i] = x2[i];
1380 y2_original[i] = y2[i];
1387 image1,
options.sigma, &image_and_gradient1);
1389 image2,
options.sigma, &image_and_gradient2);
1392 if (SearchAreaTooBigForDescent(image2, x2, y2) &&
1393 options.use_brute_initialization) {
1394 LG <<
"Running brute initialization...";
1395 bool found_any_alignment =
1396 BruteTranslationOnlyInitialize<Warp>(image_and_gradient1,
1400 options.use_normalized_intensities,
1405 if (!found_any_alignment) {
1406 LG <<
"Brute failed to find an alignment; pattern too small. "
1407 <<
"Failing entire track operation.";
1411 for (
int i = 0; i < 4; ++i) {
1412 LG <<
"P" << i <<
": (" << x1[i] <<
", " << y1[i] <<
"); brute (" << x2[i]
1413 <<
", " << y2[i] <<
"); (dx, dy): (" << (x2[i] - x1[i]) <<
", "
1414 << (y2[i] - y1[i]) <<
").";
1421 Warp
warp(x1, y1, x2, y2);
1426 PickSampling(x1, y1, x2, y2, &num_samples_x, &num_samples_y);
1429 Mat3 canonical_homography =
1430 ComputeCanonicalHomography(x1, y1, num_samples_x, num_samples_y);
1432 ceres::Problem problem;
1435 PixelDifferenceCostFunctor<Warp>* pixel_difference_cost_function =
1436 new PixelDifferenceCostFunctor<Warp>(
options,
1437 image_and_gradient1,
1438 image_and_gradient2,
1439 canonical_homography,
1443 problem.AddResidualBlock(
1444 new ceres::AutoDiffCostFunction<PixelDifferenceCostFunctor<Warp>,
1446 Warp::NUM_PARAMETERS>(
1447 pixel_difference_cost_function, num_samples_x * num_samples_y),
1452 if (
options.regularization_coefficient != 0.0) {
1453 WarpRegularizingCostFunctor<Warp>* regularizing_warp_cost_function =
1454 new WarpRegularizingCostFunctor<Warp>(
1455 options, x1, y2, x2_original, y2_original, warp);
1457 problem.AddResidualBlock(
1458 new ceres::AutoDiffCostFunction<WarpRegularizingCostFunctor<Warp>,
1460 Warp::NUM_PARAMETERS>(
1461 regularizing_warp_cost_function),
1467 ceres::Solver::Options solver_options;
1468 solver_options.linear_solver_type = ceres::DENSE_QR;
1469 solver_options.max_num_iterations =
options.max_iterations;
1470 solver_options.update_state_every_iteration =
true;
1471 solver_options.parameter_tolerance = 1
e-16;
1472 solver_options.function_tolerance = 1
e-16;
1476 TerminationCheckingCallback<Warp>
callback(
options, image2, warp, x1, y1);
1477 solver_options.callbacks.push_back(&
callback);
1480 ceres::Solver::Summary summary;
1481 ceres::Solve(solver_options, &problem, &summary);
1483 LG <<
"Summary:\n" << summary.FullReport();
1489 for (
int i = 0; i < 4 +
options.num_extra_points; ++i) {
1490 warp.Forward(warp.parameters, x1[i], y1[i], x2 + i, y2 + i);
1491 LG <<
"Warped point " << i <<
": (" << x1[i] <<
", " << y1[i] <<
") -> ("
1492 << x2[i] <<
", " << y2[i] <<
"); (dx, dy): (" << (x2[i] - x1[i]) <<
", "
1493 << (y2[i] - y1[i]) <<
").";
1499 if (summary.termination_type == ceres::USER_FAILURE) {
1504#define HANDLE_TERMINATION(termination_enum) \
1505 if (summary.termination_type == ceres::termination_enum) { \
1506 result->termination = TrackRegionResult::termination_enum; \
1514 if (
options.minimum_correlation > 0.0) {
1515 result->correlation =
1516 pixel_difference_cost_function
1517 ->PearsonProductMomentCorrelationCoefficient(warp.parameters);
1518 if (result->correlation <
options.minimum_correlation) {
1519 LG <<
"Failing with insufficient correlation.";
1530 if (summary.termination_type == ceres::USER_SUCCESS) {
1537#undef HANDLE_TERMINATION
1549#define HANDLE_MODE(mode_enum, mode_type) \
1550 if (options.mode == TrackRegionOptions::mode_enum) { \
1551 TemplatedTrackRegion<mode_type>( \
1552 image1, image2, x1, y1, options, x2, y2, result); \
1556 HANDLE_MODE(TRANSLATION_SCALE, TranslationScaleWarp);
1557 HANDLE_MODE(TRANSLATION_ROTATION, TranslationRotationWarp);
1558 HANDLE_MODE(TRANSLATION_ROTATION_SCALE, TranslationRotationScaleWarp);
1571 double* warped_position_x,
1572 double* warped_position_y) {
1574 if (!AllInBounds(image, xs, ys)) {
1575 LG <<
"Can't sample patch: out of bounds.";
1580 patch->
Resize(num_samples_y, num_samples_x, image.Depth());
1583 Mat3 canonical_homography =
1584 ComputeCanonicalHomography(xs, ys, num_samples_x, num_samples_y);
1588 for (
int r = 0; r < num_samples_y; ++r) {
1589 for (
int c = 0; c < num_samples_x; ++c) {
1590 Vec3 image_position = canonical_homography *
Vec3(c, r, 1);
1591 image_position /= image_position(2);
1593 image, image_position(1), image_position(0), &(*patch)(r, c, 0));
1596 SampleLinear(*mask, image_position(1), image_position(0), 0);
1598 for (
int d = 0; d < image.Depth(); d++) {
1599 (*patch)(r, c, d) *= mask_value;
1605 Vec3 warped_position = canonical_homography.inverse() *
Vec3(xs[4], ys[4], 1);
1606 warped_position /= warped_position(2);
1608 *warped_position_x = warped_position(0);
1609 *warped_position_y = warped_position(1);
ATTR_WARN_UNUSED_RESULT const BMVert * v2
ATTR_WARN_UNUSED_RESULT const BMVert const BMEdge * e
void warp(const btVector3 &origin)
btMatrix3x3 transpose() const
Return the transpose of the matrix.
SIMD_FORCE_INLINE const btScalar & w() const
Return the w value.
static T sum(const btAlignedObjectArray< T > &items)
SIMD_FORCE_INLINE btScalar norm() const
Return the norm (length) of the vector.
3D array (row, column, channel).
void Resize(int height, int width, int depth=1)
local_group_size(16, 16) .push_constant(Type b
CCL_NAMESPACE_BEGIN struct Options options
DEGForeachIDComponentCallback callback
#define HANDLE_MODE(mode_enum, mode_type)
double parameters[NUM_PARAMETERS]
double original_centroid_[2]
const double * y2_original_
const double * x2_original_
#define HANDLE_TERMINATION(termination_enum)
ccl_device_inline float2 floor(const float2 a)
ccl_device_inline float3 ceil(const float3 a)
ccl_device_inline float3 cos(float3 v)
ccl_device_inline float4 mask(const int4 mask, const float4 a)
ccl_device_inline int4 cast(const float4 a)
static void error(const char *str)
T atan2(const T &y, const T &x)
T sin(const AngleRadianBase< T > &a)
void TemplatedTrackRegion(const FloatImage &image1, const FloatImage &image2, const double *x1, const double *y1, const TrackRegionOptions &options, double *x2, double *y2, TrackRegionResult *result)
void TrackRegion(const FloatImage &image1, const FloatImage &image2, const double *x1, const double *y1, const TrackRegionOptions &options, double *x2, double *y2, TrackRegionResult *result)
Eigen::Matrix< double, 3, 3 > Mat3
T SampleLinear(const Array3D< T > &image, float y, float x, int v=0)
Linear interpolation.
void BlurredImageAndDerivativesChannels(const Array3Df &in, double sigma, Array3Df *blurred_and_gradxy)
bool Homography2DFromCorrespondencesLinear(const Mat &x1, const Mat &x2, Mat3 *H, double expected_precision)
bool SamplePlanarPatch(const FloatImage &image, const double *xs, const double *ys, int num_samples_x, int num_samples_y, FloatImage *mask, FloatImage *patch, double *warped_position_x, double *warped_position_y)
Eigen::Matrix< double, 2, 2 > Mat2
static Jet< T, N > Rule(const FunctionType &f, const FunctionType dfdx[kNumArgs], const Jet< T, N > x[kNumArgs])
static ArgumentType Rule(const FunctionType &f, const FunctionType dfdx[kNumArgs], const ArgumentType x[kNumArgs])
static T GetScalar(const Jet< T, N > &t)
static void ScaleDerivative(double scale_by, Jet< T, N > *value)
static void SetScalar(const T &scalar, Jet< T, N > *t)
static T GetScalar(const T &t)
static void ScaleDerivative(double scale_by, T *value)
static void SetScalar(const T &scalar, T *t)
bool use_brute_initialization
bool attempt_refine_before_brute
@ INSUFFICIENT_PATTERN_AREA
@ INSUFFICIENT_CORRELATION
@ DESTINATION_OUT_OF_BOUNDS
ccl_device_inline int abs(int x)