blob: c8b2d847fc45c0da80d8c76cc5a83f493d5f5f4d [file] [log] [blame]
Parker Schuh2a1447c2019-02-17 00:25:29 -08001#include "y2019/vision/target_finder.h"
2
3#include "ceres/ceres.h"
4
5#include <math.h>
6
7using ceres::NumericDiffCostFunction;
8using ceres::CENTRAL;
9using ceres::CostFunction;
10using ceres::Problem;
11using ceres::Solver;
12using ceres::Solve;
13
14namespace y2019 {
15namespace vision {
16
17static constexpr double kInchesToMeters = 0.0254;
18
19using namespace aos::vision;
20using aos::vision::Vector;
21
22Target Target::MakeTemplate() {
23 Target out;
24 // This is how off-vertical the tape is.
25 const double theta = 14.5 * M_PI / 180.0;
26
27 const double tape_offset = 4 * kInchesToMeters;
28 const double tape_width = 2 * kInchesToMeters;
29 const double tape_length = 5.5 * kInchesToMeters;
30
31 const double s = sin(theta);
32 const double c = cos(theta);
33 out.right.top = Vector<2>(tape_offset, 0.0);
34 out.right.inside = Vector<2>(tape_offset + tape_width * c, tape_width * s);
35 out.right.bottom = Vector<2>(tape_offset + tape_width * c + tape_length * s,
36 tape_width * s - tape_length * c);
37 out.right.outside =
38 Vector<2>(tape_offset + tape_length * s, -tape_length * c);
39
40 out.right.is_right = true;
41 out.left.top = Vector<2>(-out.right.top.x(), out.right.top.y());
42 out.left.inside = Vector<2>(-out.right.inside.x(), out.right.inside.y());
43 out.left.bottom = Vector<2>(-out.right.bottom.x(), out.right.bottom.y());
44 out.left.outside = Vector<2>(-out.right.outside.x(), out.right.outside.y());
45 return out;
46}
47
Austin Schuh2894e902019-03-03 21:12:46 -080048std::array<Vector<2>, 8> Target::ToPointList() const {
Parker Schuh2a1447c2019-02-17 00:25:29 -080049 return std::array<Vector<2>, 8>{{right.top, right.inside, right.bottom,
50 right.outside, left.top, left.inside,
51 left.bottom, left.outside}};
52}
53
54Vector<2> Project(Vector<2> pt, const IntrinsicParams &intrinsics,
55 const ExtrinsicParams &extrinsics) {
Austin Schuhcacc6922019-03-06 20:44:30 -080056 const double y = extrinsics.y;
57 const double z = extrinsics.z;
58 const double r1 = extrinsics.r1;
59 const double r2 = extrinsics.r2;
60 const double rup = intrinsics.mount_angle;
61 const double rbarrel = intrinsics.barrel_mount;
62 const double fl = intrinsics.focal_length;
Parker Schuh2a1447c2019-02-17 00:25:29 -080063
64 ::Eigen::Matrix<double, 1, 3> pts{pt.x(), pt.y() + y, 0.0};
65
66 {
Austin Schuhcacc6922019-03-06 20:44:30 -080067 const double theta = r1;
68 const double s = sin(theta);
69 const double c = cos(theta);
Parker Schuh2a1447c2019-02-17 00:25:29 -080070 pts = (::Eigen::Matrix<double, 3, 3>() << c, 0, -s, 0, 1, 0, s, 0,
71 c).finished() *
72 pts.transpose();
73 }
74
75 pts(2) += z;
76
77 {
Austin Schuhcacc6922019-03-06 20:44:30 -080078 const double theta = r2;
79 const double s = sin(theta);
80 const double c = cos(theta);
Parker Schuh2a1447c2019-02-17 00:25:29 -080081 pts = (::Eigen::Matrix<double, 3, 3>() << c, 0, -s, 0, 1, 0, s, 0,
82 c).finished() *
83 pts.transpose();
84 }
85
86 // TODO: Apply 15 degree downward rotation.
87 {
Austin Schuhcacc6922019-03-06 20:44:30 -080088 const double theta = rup;
89 const double s = sin(theta);
90 const double c = cos(theta);
Parker Schuh2a1447c2019-02-17 00:25:29 -080091
92 pts = (::Eigen::Matrix<double, 3, 3>() << 1, 0, 0, 0, c, -s, 0, s,
93 c).finished() *
94 pts.transpose();
95 }
96
Parker Schuh9e1d1692019-02-24 14:34:04 -080097 // TODO: Maybe barrel should be extrinsics to allow rocking?
98 // Also, in this case, barrel should go above the rotation above?
99 pts = ::Eigen::AngleAxis<double>(rbarrel, ::Eigen::Vector3d(0.0, 0.0, 1.0)) *
100 pts.transpose();
101
Parker Schuh2a1447c2019-02-17 00:25:29 -0800102 // TODO: Final image projection.
Austin Schuhcacc6922019-03-06 20:44:30 -0800103 const ::Eigen::Matrix<double, 1, 3> res = pts;
Parker Schuh2a1447c2019-02-17 00:25:29 -0800104
Austin Schuhcacc6922019-03-06 20:44:30 -0800105 const float scale = fl / res.z();
Parker Schuh2a1447c2019-02-17 00:25:29 -0800106 return Vector<2>(res.x() * scale + 320.0, 240.0 - res.y() * scale);
107}
108
109Target Project(const Target &target, const IntrinsicParams &intrinsics,
110 const ExtrinsicParams &extrinsics) {
111 auto project = [&](Vector<2> pt) {
112 return Project(pt, intrinsics, extrinsics);
113 };
114 Target new_targ;
115 new_targ.right.is_right = true;
116 new_targ.right.top = project(target.right.top);
117 new_targ.right.inside = project(target.right.inside);
118 new_targ.right.bottom = project(target.right.bottom);
119 new_targ.right.outside = project(target.right.outside);
120
121 new_targ.left.top = project(target.left.top);
122 new_targ.left.inside = project(target.left.inside);
123 new_targ.left.bottom = project(target.left.bottom);
124 new_targ.left.outside = project(target.left.outside);
125
126 return new_targ;
127}
128
129// Used at runtime on a single image given camera parameters.
130struct RuntimeCostFunctor {
131 RuntimeCostFunctor(Vector<2> result, Vector<2> template_pt,
132 IntrinsicParams intrinsics)
133 : result(result), template_pt(template_pt), intrinsics(intrinsics) {}
134
135 bool operator()(const double *const x, double *residual) const {
136 auto extrinsics = ExtrinsicParams::get(x);
137 auto pt = result - Project(template_pt, intrinsics, extrinsics);
138 residual[0] = pt.x();
139 residual[1] = pt.y();
140 return true;
141 }
142
143 Vector<2> result;
144 Vector<2> template_pt;
145 IntrinsicParams intrinsics;
146};
147
148IntermediateResult TargetFinder::ProcessTargetToResult(const Target &target,
149 bool verbose) {
150 // Memory for the ceres solver.
151 double params[ExtrinsicParams::kNumParams];
152 default_extrinsics_.set(&params[0]);
153
154 Problem problem;
155
Austin Schuh2894e902019-03-03 21:12:46 -0800156 ::std::array<aos::vision::Vector<2>, 8> target_value = target.ToPointList();
157 ::std::array<aos::vision::Vector<2>, 8> template_value =
158 target_template_.ToPointList();
Parker Schuh2a1447c2019-02-17 00:25:29 -0800159
160 for (size_t i = 0; i < 8; ++i) {
Austin Schuh2894e902019-03-03 21:12:46 -0800161 aos::vision::Vector<2> a = template_value[i];
162 aos::vision::Vector<2> b = target_value[i];
Parker Schuh2a1447c2019-02-17 00:25:29 -0800163
164 problem.AddResidualBlock(
165 new NumericDiffCostFunction<RuntimeCostFunctor, CENTRAL, 2, 4>(
166 new RuntimeCostFunctor(b, a, intrinsics_)),
167 NULL, &params[0]);
168 }
169
170 Solver::Options options;
171 options.minimizer_progress_to_stdout = false;
172 Solver::Summary summary;
173 Solve(options, &problem, &summary);
174
175 IntermediateResult IR;
176 IR.extrinsics = ExtrinsicParams::get(&params[0]);
177 IR.solver_error = summary.final_cost;
178
179 if (verbose) {
180 std::cout << summary.BriefReport() << "\n";
181 std::cout << "y = " << IR.extrinsics.y / kInchesToMeters << ";\n";
182 std::cout << "z = " << IR.extrinsics.z / kInchesToMeters << ";\n";
183 std::cout << "r1 = " << IR.extrinsics.r1 * 180 / M_PI << ";\n";
184 std::cout << "r2 = " << IR.extrinsics.r2 * 180 / M_PI << ";\n";
185 std::cout << "rup = " << intrinsics_.mount_angle * 180 / M_PI << ";\n";
186 std::cout << "fl = " << intrinsics_.focal_length << ";\n";
187 std::cout << "error = " << summary.final_cost << ";\n";
188 }
189 return IR;
190}
191
192} // namespace vision
193} // namespace y2019