blob: 24ac08701fe08efdcacb7071d269fbaceca51cd1 [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 {
Alex Perrybac3d3f2019-03-10 14:26:51 -070049 return std::array<Vector<2>, 8>{{right.top, right.outside, right.inside,
50 right.bottom, left.top, left.outside,
51 left.inside, left.bottom}};
Parker Schuh2a1447c2019-02-17 00:25:29 -080052}
53
54Vector<2> Project(Vector<2> pt, const IntrinsicParams &intrinsics,
55 const ExtrinsicParams &extrinsics) {
James Kuszmaul289756f2019-03-05 21:52:10 -080056 const double y = extrinsics.y; // height
57 const double z = extrinsics.z; // distance
58 const double r1 = extrinsics.r1; // skew
59 const double r2 = extrinsics.r2; // heading
Austin Schuhcacc6922019-03-06 20:44:30 -080060 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
James Kuszmaul289756f2019-03-05 21:52:10 -080064 // Start by translating point in target-space to be at correct height.
Parker Schuh2a1447c2019-02-17 00:25:29 -080065 ::Eigen::Matrix<double, 1, 3> pts{pt.x(), pt.y() + y, 0.0};
66
67 {
James Kuszmaul289756f2019-03-05 21:52:10 -080068 // Rotate to compensate for skew angle, to get into a frame still at the
69 // same (x, y) position as the target but rotated to be facing straight
70 // towards the camera.
Austin Schuhcacc6922019-03-06 20:44:30 -080071 const double theta = r1;
72 const double s = sin(theta);
73 const double c = cos(theta);
Parker Schuh2a1447c2019-02-17 00:25:29 -080074 pts = (::Eigen::Matrix<double, 3, 3>() << c, 0, -s, 0, 1, 0, s, 0,
75 c).finished() *
76 pts.transpose();
77 }
78
James Kuszmaul289756f2019-03-05 21:52:10 -080079 // Translate the coordinate frame to have (x, y) centered at the camera, but
80 // still oriented to be facing along the line from the camera to the target.
Parker Schuh2a1447c2019-02-17 00:25:29 -080081 pts(2) += z;
82
83 {
James Kuszmaul289756f2019-03-05 21:52:10 -080084 // Rotate out the heading so that the frame is oriented to line up with the
85 // camera's viewpoint in the yaw-axis.
Austin Schuhcacc6922019-03-06 20:44:30 -080086 const double theta = r2;
87 const double s = sin(theta);
88 const double c = cos(theta);
Parker Schuh2a1447c2019-02-17 00:25:29 -080089 pts = (::Eigen::Matrix<double, 3, 3>() << c, 0, -s, 0, 1, 0, s, 0,
90 c).finished() *
91 pts.transpose();
92 }
93
94 // TODO: Apply 15 degree downward rotation.
95 {
James Kuszmaul289756f2019-03-05 21:52:10 -080096 // Compensate for rotation in the pitch of the camera up/down to get into
97 // the coordinate frame lined up with the plane of the camera sensor.
Austin Schuhcacc6922019-03-06 20:44:30 -080098 const double theta = rup;
99 const double s = sin(theta);
100 const double c = cos(theta);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800101
102 pts = (::Eigen::Matrix<double, 3, 3>() << 1, 0, 0, 0, c, -s, 0, s,
103 c).finished() *
104 pts.transpose();
105 }
106
James Kuszmaul289756f2019-03-05 21:52:10 -0800107 // Compensate for rotation of the barrel of the camera, i.e. about the axis
108 // that points straight out from the camera lense, using an AngleAxis instead
109 // of manually constructing the rotation matrices because once you get into
110 // this frame you no longer need to be masochistic.
Parker Schuh9e1d1692019-02-24 14:34:04 -0800111 // TODO: Maybe barrel should be extrinsics to allow rocking?
112 // Also, in this case, barrel should go above the rotation above?
113 pts = ::Eigen::AngleAxis<double>(rbarrel, ::Eigen::Vector3d(0.0, 0.0, 1.0)) *
114 pts.transpose();
115
Parker Schuh2a1447c2019-02-17 00:25:29 -0800116 // TODO: Final image projection.
Austin Schuhcacc6922019-03-06 20:44:30 -0800117 const ::Eigen::Matrix<double, 1, 3> res = pts;
Parker Schuh2a1447c2019-02-17 00:25:29 -0800118
James Kuszmaul289756f2019-03-05 21:52:10 -0800119 // Finally, scale to account for focal length and translate to get into
120 // pixel-space.
Austin Schuhcacc6922019-03-06 20:44:30 -0800121 const float scale = fl / res.z();
Parker Schuh2a1447c2019-02-17 00:25:29 -0800122 return Vector<2>(res.x() * scale + 320.0, 240.0 - res.y() * scale);
123}
124
125Target Project(const Target &target, const IntrinsicParams &intrinsics,
126 const ExtrinsicParams &extrinsics) {
Parker Schuh2a1447c2019-02-17 00:25:29 -0800127 Target new_targ;
128 new_targ.right.is_right = true;
Austin Schuh4d6e9bd2019-03-08 19:54:17 -0800129 new_targ.right.top = Project(target.right.top, intrinsics, extrinsics);
130 new_targ.right.inside = Project(target.right.inside, intrinsics, extrinsics);
131 new_targ.right.bottom = Project(target.right.bottom, intrinsics, extrinsics);
132 new_targ.right.outside =
133 Project(target.right.outside, intrinsics, extrinsics);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800134
Austin Schuh4d6e9bd2019-03-08 19:54:17 -0800135 new_targ.left.top = Project(target.left.top, intrinsics, extrinsics);
136 new_targ.left.inside = Project(target.left.inside, intrinsics, extrinsics);
137 new_targ.left.bottom = Project(target.left.bottom, intrinsics, extrinsics);
138 new_targ.left.outside = Project(target.left.outside, intrinsics, extrinsics);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800139
140 return new_targ;
141}
142
143// Used at runtime on a single image given camera parameters.
Alex Perrybac3d3f2019-03-10 14:26:51 -0700144struct PointCostFunctor {
145 PointCostFunctor(Vector<2> result, Vector<2> template_pt,
Parker Schuh2a1447c2019-02-17 00:25:29 -0800146 IntrinsicParams intrinsics)
147 : result(result), template_pt(template_pt), intrinsics(intrinsics) {}
148
149 bool operator()(const double *const x, double *residual) const {
150 auto extrinsics = ExtrinsicParams::get(x);
151 auto pt = result - Project(template_pt, intrinsics, extrinsics);
152 residual[0] = pt.x();
153 residual[1] = pt.y();
154 return true;
155 }
156
157 Vector<2> result;
158 Vector<2> template_pt;
159 IntrinsicParams intrinsics;
160};
161
Alex Perrybac3d3f2019-03-10 14:26:51 -0700162// Find the distance from a lower target point to the 'vertical' line it should
163// be on.
164struct LineCostFunctor {
165 LineCostFunctor(Vector<2> result, Segment<2> template_seg,
166 IntrinsicParams intrinsics)
167 : result(result), template_seg(template_seg), intrinsics(intrinsics) {}
168
169 bool operator()(const double *const x, double *residual) const {
170 const auto extrinsics = ExtrinsicParams::get(x);
171 const auto p1 = Project(template_seg.A(), intrinsics, extrinsics);
172 const auto p2 = Project(template_seg.B(), intrinsics, extrinsics);
173 // distance from line (P1, P2) to point result
174 double dx = p2.x() - p1.x();
175 double dy = p2.y() - p1.y();
176 double denom = p2.DistanceTo(p1);
177 residual[0] = ::std::abs(dy * result.x() - dx * result.y() +
178 p2.x() * p1.y() - p2.y() * p1.x()) /
179 denom;
180 return true;
181 }
182
183 Vector<2> result;
184 Segment<2> template_seg;
185 IntrinsicParams intrinsics;
186};
187
Parker Schuh2a1447c2019-02-17 00:25:29 -0800188IntermediateResult TargetFinder::ProcessTargetToResult(const Target &target,
189 bool verbose) {
190 // Memory for the ceres solver.
Alex Perrybac3d3f2019-03-10 14:26:51 -0700191 double params_8point[ExtrinsicParams::kNumParams];
192 default_extrinsics_.set(&params_8point[0]);
193 double params_4point[ExtrinsicParams::kNumParams];
194 default_extrinsics_.set(&params_4point[0]);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800195
Alex Perrybac3d3f2019-03-10 14:26:51 -0700196 Problem problem_8point;
197 Problem problem_4point;
Parker Schuh2a1447c2019-02-17 00:25:29 -0800198
Austin Schuh2894e902019-03-03 21:12:46 -0800199 ::std::array<aos::vision::Vector<2>, 8> target_value = target.ToPointList();
200 ::std::array<aos::vision::Vector<2>, 8> template_value =
201 target_template_.ToPointList();
Parker Schuh2a1447c2019-02-17 00:25:29 -0800202
203 for (size_t i = 0; i < 8; ++i) {
Austin Schuh2894e902019-03-03 21:12:46 -0800204 aos::vision::Vector<2> a = template_value[i];
205 aos::vision::Vector<2> b = target_value[i];
Parker Schuh2a1447c2019-02-17 00:25:29 -0800206
Alex Perrybac3d3f2019-03-10 14:26:51 -0700207 if (i % 2 == 1) {
208 aos::vision::Vector<2> a2 = template_value[i-1];
209 aos::vision::Segment<2> line = Segment<2>(a, a2);
210
211 problem_4point.AddResidualBlock(
212 new NumericDiffCostFunction<LineCostFunctor, CENTRAL, 1, 4>(
213 new LineCostFunctor(b, line, intrinsics_)),
214 NULL, &params_8point[0]);
215 } else {
216 problem_4point.AddResidualBlock(
217 new NumericDiffCostFunction<PointCostFunctor, CENTRAL, 2, 4>(
218 new PointCostFunctor(b, a, intrinsics_)),
219 NULL, &params_8point[0]);
220 }
221
222 problem_8point.AddResidualBlock(
223 new NumericDiffCostFunction<PointCostFunctor, CENTRAL, 2, 4>(
224 new PointCostFunctor(b, a, intrinsics_)),
225 NULL, &params_4point[0]);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800226 }
227
228 Solver::Options options;
229 options.minimizer_progress_to_stdout = false;
Alex Perrybac3d3f2019-03-10 14:26:51 -0700230 Solver::Summary summary_8point;
231 Solve(options, &problem_8point, &summary_8point);
232 Solver::Summary summary_4point;
233 Solve(options, &problem_4point, &summary_4point);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800234
235 IntermediateResult IR;
Alex Perrybac3d3f2019-03-10 14:26:51 -0700236 IR.extrinsics = ExtrinsicParams::get(&params_8point[0]);
237 IR.solver_error = summary_8point.final_cost;
238 IR.backup_extrinsics = ExtrinsicParams::get(&params_4point[0]);
239 IR.backup_solver_error = summary_4point.final_cost;
Parker Schuh2a1447c2019-02-17 00:25:29 -0800240
241 if (verbose) {
Alex Perrybac3d3f2019-03-10 14:26:51 -0700242 std::cout << "rup = " << intrinsics_.mount_angle * 180 / M_PI << ";\n";
243 std::cout << "fl = " << intrinsics_.focal_length << ";\n";
244 std::cout << "8 points:\n";
245 std::cout << summary_8point.BriefReport() << "\n";
246 std::cout << "error = " << summary_8point.final_cost << ";\n";
Parker Schuh2a1447c2019-02-17 00:25:29 -0800247 std::cout << "y = " << IR.extrinsics.y / kInchesToMeters << ";\n";
248 std::cout << "z = " << IR.extrinsics.z / kInchesToMeters << ";\n";
249 std::cout << "r1 = " << IR.extrinsics.r1 * 180 / M_PI << ";\n";
250 std::cout << "r2 = " << IR.extrinsics.r2 * 180 / M_PI << ";\n";
Alex Perrybac3d3f2019-03-10 14:26:51 -0700251 std::cout << "4 points:\n";
252 std::cout << summary_4point.BriefReport() << "\n";
253 std::cout << "error = " << summary_4point.final_cost << ";\n\n";
254 std::cout << "y = " << IR.backup_extrinsics.y / kInchesToMeters << ";\n";
255 std::cout << "z = " << IR.backup_extrinsics.z / kInchesToMeters << ";\n";
256 std::cout << "r1 = " << IR.backup_extrinsics.r1 * 180 / M_PI << ";\n";
257 std::cout << "r2 = " << IR.backup_extrinsics.r2 * 180 / M_PI << ";\n";
Parker Schuh2a1447c2019-02-17 00:25:29 -0800258 }
259 return IR;
260}
261
262} // namespace vision
263} // namespace y2019