blob: 212759aa7ecc136511f424fae2e1610e8df3ce6f [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
Alex Perryb6f334d2019-03-23 13:10:45 -07007#include "aos/util/math.h"
8
Parker Schuh2a1447c2019-02-17 00:25:29 -08009using ceres::CENTRAL;
10using ceres::CostFunction;
11using ceres::Problem;
12using ceres::Solver;
13using ceres::Solve;
14
15namespace y2019 {
16namespace vision {
17
18static constexpr double kInchesToMeters = 0.0254;
19
20using namespace aos::vision;
21using aos::vision::Vector;
22
23Target Target::MakeTemplate() {
24 Target out;
25 // This is how off-vertical the tape is.
26 const double theta = 14.5 * M_PI / 180.0;
27
28 const double tape_offset = 4 * kInchesToMeters;
29 const double tape_width = 2 * kInchesToMeters;
30 const double tape_length = 5.5 * kInchesToMeters;
31
32 const double s = sin(theta);
33 const double c = cos(theta);
34 out.right.top = Vector<2>(tape_offset, 0.0);
35 out.right.inside = Vector<2>(tape_offset + tape_width * c, tape_width * s);
36 out.right.bottom = Vector<2>(tape_offset + tape_width * c + tape_length * s,
37 tape_width * s - tape_length * c);
38 out.right.outside =
39 Vector<2>(tape_offset + tape_length * s, -tape_length * c);
40
41 out.right.is_right = true;
42 out.left.top = Vector<2>(-out.right.top.x(), out.right.top.y());
43 out.left.inside = Vector<2>(-out.right.inside.x(), out.right.inside.y());
44 out.left.bottom = Vector<2>(-out.right.bottom.x(), out.right.bottom.y());
45 out.left.outside = Vector<2>(-out.right.outside.x(), out.right.outside.y());
46 return out;
47}
48
Austin Schuh2894e902019-03-03 21:12:46 -080049std::array<Vector<2>, 8> Target::ToPointList() const {
Austin Schuhe6cfbe32019-03-10 18:05:57 -070050 // Note, the even points are fit with the line solver in the 4 point solution
51 // while the odds are fit with the point matcher.
Alex Perrybac3d3f2019-03-10 14:26:51 -070052 return std::array<Vector<2>, 8>{{right.top, right.outside, right.inside,
53 right.bottom, left.top, left.outside,
54 left.inside, left.bottom}};
Parker Schuh2a1447c2019-02-17 00:25:29 -080055}
56
Parker Schuh2a1447c2019-02-17 00:25:29 -080057Target Project(const Target &target, const IntrinsicParams &intrinsics,
58 const ExtrinsicParams &extrinsics) {
Parker Schuh2a1447c2019-02-17 00:25:29 -080059 Target new_targ;
60 new_targ.right.is_right = true;
Austin Schuh4d6e9bd2019-03-08 19:54:17 -080061 new_targ.right.top = Project(target.right.top, intrinsics, extrinsics);
62 new_targ.right.inside = Project(target.right.inside, intrinsics, extrinsics);
63 new_targ.right.bottom = Project(target.right.bottom, intrinsics, extrinsics);
64 new_targ.right.outside =
65 Project(target.right.outside, intrinsics, extrinsics);
Parker Schuh2a1447c2019-02-17 00:25:29 -080066
Austin Schuh4d6e9bd2019-03-08 19:54:17 -080067 new_targ.left.top = Project(target.left.top, intrinsics, extrinsics);
68 new_targ.left.inside = Project(target.left.inside, intrinsics, extrinsics);
69 new_targ.left.bottom = Project(target.left.bottom, intrinsics, extrinsics);
70 new_targ.left.outside = Project(target.left.outside, intrinsics, extrinsics);
Parker Schuh2a1447c2019-02-17 00:25:29 -080071
72 return new_targ;
73}
74
75// Used at runtime on a single image given camera parameters.
Alex Perrybac3d3f2019-03-10 14:26:51 -070076struct PointCostFunctor {
77 PointCostFunctor(Vector<2> result, Vector<2> template_pt,
Parker Schuh2a1447c2019-02-17 00:25:29 -080078 IntrinsicParams intrinsics)
79 : result(result), template_pt(template_pt), intrinsics(intrinsics) {}
80
Alex Perry3d0abf22019-04-06 19:52:24 -070081 template <typename T>
82 bool operator()(const T *const x, T *residual) const {
83 const auto extrinsics = TemplatedExtrinsicParams<T>::get(x);
84 ::Eigen::Matrix<T, 2, 1> pt =
85 Project<T>(ToEigenMatrix<T>(template_pt), intrinsics, extrinsics);
86 residual[0] = result.x() - pt(0, 0);
Alex Perry670d5ac2019-04-07 14:20:31 -070087 residual[1] = result.y() - pt(1, 0);
Parker Schuh2a1447c2019-02-17 00:25:29 -080088 return true;
89 }
90
91 Vector<2> result;
92 Vector<2> template_pt;
93 IntrinsicParams intrinsics;
94};
95
Alex Perrybac3d3f2019-03-10 14:26:51 -070096// Find the distance from a lower target point to the 'vertical' line it should
97// be on.
98struct LineCostFunctor {
99 LineCostFunctor(Vector<2> result, Segment<2> template_seg,
100 IntrinsicParams intrinsics)
101 : result(result), template_seg(template_seg), intrinsics(intrinsics) {}
102
Alex Perry3d0abf22019-04-06 19:52:24 -0700103 template <typename T>
104 bool operator()(const T *const x, T *residual) const {
105 const auto extrinsics = TemplatedExtrinsicParams<T>::get(x);
106 const ::Eigen::Matrix<T, 2, 1> p1 =
107 Project<T>(ToEigenMatrix<T>(template_seg.A()), intrinsics, extrinsics);
108 const ::Eigen::Matrix<T, 2, 1> p2 =
109 Project<T>(ToEigenMatrix<T>(template_seg.B()), intrinsics, extrinsics);
110 // Distance from line(P1, P2) to point result
111 T dx = p2.x() - p1.x();
112 T dy = p2.y() - p1.y();
113 T denom = (p2-p1).norm();
114 residual[0] = ceres::abs(dy * result.x() - dx * result.y() +
Alex Perrybac3d3f2019-03-10 14:26:51 -0700115 p2.x() * p1.y() - p2.y() * p1.x()) /
116 denom;
117 return true;
118 }
119
120 Vector<2> result;
121 Segment<2> template_seg;
122 IntrinsicParams intrinsics;
123};
124
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700125// Find the distance that the bottom point is outside the target and penalize
126// that linearly.
127class BottomPointCostFunctor {
128 public:
129 BottomPointCostFunctor(::Eigen::Vector2f bottom_point,
130 Segment<2> template_seg, IntrinsicParams intrinsics)
131 : bottom_point_(bottom_point.x(), bottom_point.y()),
132 template_seg_(template_seg),
133 intrinsics_(intrinsics) {}
134
Alex Perry3d0abf22019-04-06 19:52:24 -0700135 template <typename T>
136 bool operator()(const T *const x, T *residual) const {
137 const auto extrinsics = TemplatedExtrinsicParams<T>::get(x);
138 const ::Eigen::Matrix<T, 2, 1> p1 = Project<T>(
139 ToEigenMatrix<T>(template_seg_.A()), intrinsics_, extrinsics);
140 const ::Eigen::Matrix<T, 2, 1> p2 = Project<T>(
141 ToEigenMatrix<T>(template_seg_.B()), intrinsics_, extrinsics);
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700142
143 // Construct a vector pointed perpendicular to the line. This vector is
144 // pointed down out the bottom of the target.
Alex Perry3d0abf22019-04-06 19:52:24 -0700145 ::Eigen::Matrix<T, 2, 1> down_axis;
146 down_axis << -(p1.y() - p2.y()), p1.x() - p2.x();
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700147 down_axis.normalize();
148
149 // Positive means out.
Alex Perry3d0abf22019-04-06 19:52:24 -0700150 const T component =
151 down_axis.transpose() * (bottom_point_ - p1);
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700152
Alex Perry3d0abf22019-04-06 19:52:24 -0700153 if (component > T(0)) {
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700154 residual[0] = component * 1.0;
155 } else {
Alex Perry3d0abf22019-04-06 19:52:24 -0700156 residual[0] = T(0);
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700157 }
158 return true;
159 }
160
161 private:
162 ::Eigen::Vector2d bottom_point_;
163 Segment<2> template_seg_;
164
165 IntrinsicParams intrinsics_;
166};
167
Parker Schuh2a1447c2019-02-17 00:25:29 -0800168IntermediateResult TargetFinder::ProcessTargetToResult(const Target &target,
169 bool verbose) {
170 // Memory for the ceres solver.
Alex Perrybac3d3f2019-03-10 14:26:51 -0700171 double params_8point[ExtrinsicParams::kNumParams];
172 default_extrinsics_.set(&params_8point[0]);
173 double params_4point[ExtrinsicParams::kNumParams];
174 default_extrinsics_.set(&params_4point[0]);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800175
Brian Silverman63236772019-03-23 22:02:44 -0700176 Problem::Options problem_options;
177 problem_options.context = ceres_context_.get();
178 Problem problem_8point(problem_options);
179 Problem problem_4point(problem_options);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800180
Austin Schuh2894e902019-03-03 21:12:46 -0800181 ::std::array<aos::vision::Vector<2>, 8> target_value = target.ToPointList();
182 ::std::array<aos::vision::Vector<2>, 8> template_value =
183 target_template_.ToPointList();
Parker Schuh2a1447c2019-02-17 00:25:29 -0800184
185 for (size_t i = 0; i < 8; ++i) {
Austin Schuh2894e902019-03-03 21:12:46 -0800186 aos::vision::Vector<2> a = template_value[i];
187 aos::vision::Vector<2> b = target_value[i];
Parker Schuh2a1447c2019-02-17 00:25:29 -0800188
Alex Perrybac3d3f2019-03-10 14:26:51 -0700189 if (i % 2 == 1) {
190 aos::vision::Vector<2> a2 = template_value[i-1];
191 aos::vision::Segment<2> line = Segment<2>(a, a2);
192
193 problem_4point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700194 new ceres::AutoDiffCostFunction<LineCostFunctor, 1, 4>(
Alex Perrybac3d3f2019-03-10 14:26:51 -0700195 new LineCostFunctor(b, line, intrinsics_)),
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700196 NULL, &params_4point[0]);
Alex Perrybac3d3f2019-03-10 14:26:51 -0700197 } else {
198 problem_4point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700199 new ceres::AutoDiffCostFunction<PointCostFunctor, 2, 4>(
Alex Perrybac3d3f2019-03-10 14:26:51 -0700200 new PointCostFunctor(b, a, intrinsics_)),
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700201 NULL, &params_4point[0]);
Alex Perrybac3d3f2019-03-10 14:26:51 -0700202 }
203
204 problem_8point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700205 new ceres::AutoDiffCostFunction<PointCostFunctor, 2, 4>(
Alex Perrybac3d3f2019-03-10 14:26:51 -0700206 new PointCostFunctor(b, a, intrinsics_)),
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700207 NULL, &params_8point[0]);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800208 }
209
Austin Schuhbb2ac922019-03-11 01:09:57 -0700210 Solver::Options options;
211 options.minimizer_progress_to_stdout = false;
212 Solver::Summary summary_8point;
213 Solve(options, &problem_8point, &summary_8point);
214
215
216 // So, let's sneak up on it. Start by warm-starting it with where we got on the 8 point solution.
217 ExtrinsicParams::get(&params_8point[0]).set(&params_4point[0]);
218 // Then solve without the bottom constraint.
219 Solver::Summary summary_4point1;
220 Solve(options, &problem_4point, &summary_4point1);
221
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700222 // Now, add a large cost for the bottom point being below the bottom line.
223 problem_4point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700224 new ceres::AutoDiffCostFunction<BottomPointCostFunctor, 1, 4>(
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700225 new BottomPointCostFunctor(target.left.bottom_point,
226 Segment<2>(target_template_.left.outside,
227 target_template_.left.bottom),
228 intrinsics_)),
229 NULL, &params_4point[0]);
230 // Make sure to point the segment the other way so when we do a -pi/2 rotation
231 // on the line, it points down in target space.
232 problem_4point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700233 new ceres::AutoDiffCostFunction<BottomPointCostFunctor, 1, 4>(
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700234 new BottomPointCostFunctor(target.right.bottom_point,
235 Segment<2>(target_template_.right.bottom,
236 target_template_.right.outside),
237 intrinsics_)),
238 NULL, &params_4point[0]);
239
Austin Schuhbb2ac922019-03-11 01:09:57 -0700240 // And then re-solve.
241 Solver::Summary summary_4point2;
242 Solve(options, &problem_4point, &summary_4point2);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800243
244 IntermediateResult IR;
Alex Perrybac3d3f2019-03-10 14:26:51 -0700245 IR.extrinsics = ExtrinsicParams::get(&params_8point[0]);
246 IR.solver_error = summary_8point.final_cost;
247 IR.backup_extrinsics = ExtrinsicParams::get(&params_4point[0]);
Austin Schuhbb2ac922019-03-11 01:09:57 -0700248 IR.backup_solver_error = summary_4point2.final_cost;
Parker Schuh2a1447c2019-02-17 00:25:29 -0800249
Alex Perryb6f334d2019-03-23 13:10:45 -0700250 // Normalize all angles to (-M_PI, M_PI]
251 IR.extrinsics.r1 = ::aos::math::NormalizeAngle(IR.extrinsics.r1);
252 IR.extrinsics.r2 = ::aos::math::NormalizeAngle(IR.extrinsics.r2);
Austin Schuh45639882019-03-24 19:20:42 -0700253 IR.backup_extrinsics.r1 =
254 ::aos::math::NormalizeAngle(IR.backup_extrinsics.r1);
255 IR.backup_extrinsics.r2 =
256 ::aos::math::NormalizeAngle(IR.backup_extrinsics.r2);
Alex Perry5b1e8e32019-04-07 13:25:31 -0700257 IR.target_width = target.width();
Austin Schuh45639882019-03-24 19:20:42 -0700258
259 // Ok, let's look at how perpendicular the corners are.
260 // Vector from the outside to inside along the top on the left.
261 const ::Eigen::Vector2d top_left_vector =
262 (target.left.top.GetData() - target.left.inside.GetData())
263 .transpose()
264 .normalized();
265 // Vector up the outside of the left target.
266 const ::Eigen::Vector2d outer_left_vector =
267 (target.left.top.GetData() - target.left.outside.GetData())
268 .transpose()
269 .normalized();
270 // Vector up the inside of the left target.
271 const ::Eigen::Vector2d inner_left_vector =
272 (target.left.inside.GetData() - target.left.bottom.GetData())
273 .transpose()
274 .normalized();
275
276 // Vector from the outside to inside along the top on the right.
277 const ::Eigen::Vector2d top_right_vector =
278 (target.right.top.GetData() - target.right.inside.GetData())
279 .transpose()
280 .normalized();
281 // Vector up the outside of the right target.
282 const ::Eigen::Vector2d outer_right_vector =
283 (target.right.top.GetData() - target.right.outside.GetData())
284 .transpose()
285 .normalized();
286 // Vector up the inside of the right target.
287 const ::Eigen::Vector2d inner_right_vector =
288 (target.right.inside.GetData() - target.right.bottom.GetData())
289 .transpose()
290 .normalized();
291
292 // Now dot the vectors and use that to compute angles.
293 // Left side, outside corner.
294 const double left_outer_corner_dot =
295 (outer_left_vector.transpose() * top_left_vector)(0);
296 // Left side, inside corner.
297 const double left_inner_corner_dot =
298 (inner_left_vector.transpose() * top_left_vector)(0);
299 // Right side, outside corner.
300 const double right_outer_corner_dot =
301 (outer_right_vector.transpose() * top_right_vector)(0);
302 // Right side, inside corner.
303 const double right_inner_corner_dot =
304 (inner_right_vector.transpose() * top_right_vector)(0);
305
306 constexpr double kCornerThreshold = 0.35;
307 if (::std::abs(left_outer_corner_dot) < kCornerThreshold &&
308 ::std::abs(left_inner_corner_dot) < kCornerThreshold &&
309 ::std::abs(right_outer_corner_dot) < kCornerThreshold &&
310 ::std::abs(right_inner_corner_dot) < kCornerThreshold) {
311 IR.good_corners = true;
312 } else {
313 IR.good_corners = false;
314 }
Alex Perryb6f334d2019-03-23 13:10:45 -0700315
Parker Schuh2a1447c2019-02-17 00:25:29 -0800316 if (verbose) {
Alex Perrybac3d3f2019-03-10 14:26:51 -0700317 std::cout << "rup = " << intrinsics_.mount_angle * 180 / M_PI << ";\n";
318 std::cout << "fl = " << intrinsics_.focal_length << ";\n";
319 std::cout << "8 points:\n";
320 std::cout << summary_8point.BriefReport() << "\n";
321 std::cout << "error = " << summary_8point.final_cost << ";\n";
Parker Schuh2a1447c2019-02-17 00:25:29 -0800322 std::cout << "y = " << IR.extrinsics.y / kInchesToMeters << ";\n";
323 std::cout << "z = " << IR.extrinsics.z / kInchesToMeters << ";\n";
324 std::cout << "r1 = " << IR.extrinsics.r1 * 180 / M_PI << ";\n";
325 std::cout << "r2 = " << IR.extrinsics.r2 * 180 / M_PI << ";\n";
Alex Perrybac3d3f2019-03-10 14:26:51 -0700326 std::cout << "4 points:\n";
Austin Schuhbb2ac922019-03-11 01:09:57 -0700327 std::cout << summary_4point1.BriefReport() << "\n";
328 std::cout << "error = " << summary_4point1.final_cost << ";\n\n";
329 std::cout << "4 points:\n";
330 std::cout << summary_4point2.BriefReport() << "\n";
331 std::cout << "error = " << summary_4point2.final_cost << ";\n\n";
Alex Perrybac3d3f2019-03-10 14:26:51 -0700332 std::cout << "y = " << IR.backup_extrinsics.y / kInchesToMeters << ";\n";
333 std::cout << "z = " << IR.backup_extrinsics.z / kInchesToMeters << ";\n";
334 std::cout << "r1 = " << IR.backup_extrinsics.r1 * 180 / M_PI << ";\n";
335 std::cout << "r2 = " << IR.backup_extrinsics.r2 * 180 / M_PI << ";\n";
Austin Schuh45639882019-03-24 19:20:42 -0700336
337
338 printf("left upper outer corner angle: %f, top (%f, %f), outer (%f, %f)\n",
339 (outer_left_vector.transpose() * top_left_vector)(0),
340 top_left_vector(0, 0), top_left_vector(1, 0),
341 outer_left_vector(0, 0), outer_left_vector(1, 0));
342 printf("left upper inner corner angle: %f\n",
343 (inner_left_vector.transpose() * top_left_vector)(0));
344
345 printf("right upper outer corner angle: %f, top (%f, %f), outer (%f, %f)\n",
346 (outer_right_vector.transpose() * top_right_vector)(0),
347 top_right_vector(0, 0), top_right_vector(1, 0),
348 outer_right_vector(0, 0), outer_right_vector(1, 0));
349 printf("right upper inner corner angle: %f\n",
350 (inner_right_vector.transpose() * top_right_vector)(0));
Parker Schuh2a1447c2019-02-17 00:25:29 -0800351 }
352 return IR;
353}
354
355} // namespace vision
356} // namespace y2019