blob: e562f49b06f31167ac9df3fa2224d588ad2becdd [file] [log] [blame]
Tyler Chatowbf0609c2021-07-31 16:13:27 -07001#include <cmath>
Parker Schuh2a1447c2019-02-17 00:25:29 -08002
Tyler Chatowbf0609c2021-07-31 16:13:27 -07003#include "ceres/ceres.h"
Philipp Schrader790cb542023-07-05 21:06:52 -07004
5#include "aos/util/math.h"
Tyler Chatowbf0609c2021-07-31 16:13:27 -07006#include "y2019/vision/target_finder.h"
Alex Perryb6f334d2019-03-23 13:10:45 -07007
Parker Schuh2a1447c2019-02-17 00:25:29 -08008using ceres::CENTRAL;
9using ceres::CostFunction;
10using ceres::Problem;
Parker Schuh2a1447c2019-02-17 00:25:29 -080011using ceres::Solve;
Tyler Chatowbf0609c2021-07-31 16:13:27 -070012using ceres::Solver;
Parker Schuh2a1447c2019-02-17 00:25:29 -080013
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 {
Austin Schuhe6cfbe32019-03-10 18:05:57 -070049 // Note, the even points are fit with the line solver in the 4 point solution
50 // while the odds are fit with the point matcher.
Alex Perrybac3d3f2019-03-10 14:26:51 -070051 return std::array<Vector<2>, 8>{{right.top, right.outside, right.inside,
52 right.bottom, left.top, left.outside,
53 left.inside, left.bottom}};
Parker Schuh2a1447c2019-02-17 00:25:29 -080054}
55
Parker Schuh2a1447c2019-02-17 00:25:29 -080056Target Project(const Target &target, const IntrinsicParams &intrinsics,
57 const ExtrinsicParams &extrinsics) {
Parker Schuh2a1447c2019-02-17 00:25:29 -080058 Target new_targ;
59 new_targ.right.is_right = true;
Austin Schuh4d6e9bd2019-03-08 19:54:17 -080060 new_targ.right.top = Project(target.right.top, intrinsics, extrinsics);
61 new_targ.right.inside = Project(target.right.inside, intrinsics, extrinsics);
62 new_targ.right.bottom = Project(target.right.bottom, intrinsics, extrinsics);
63 new_targ.right.outside =
64 Project(target.right.outside, intrinsics, extrinsics);
Parker Schuh2a1447c2019-02-17 00:25:29 -080065
Austin Schuh4d6e9bd2019-03-08 19:54:17 -080066 new_targ.left.top = Project(target.left.top, intrinsics, extrinsics);
67 new_targ.left.inside = Project(target.left.inside, intrinsics, extrinsics);
68 new_targ.left.bottom = Project(target.left.bottom, intrinsics, extrinsics);
69 new_targ.left.outside = Project(target.left.outside, intrinsics, extrinsics);
Parker Schuh2a1447c2019-02-17 00:25:29 -080070
71 return new_targ;
72}
73
74// Used at runtime on a single image given camera parameters.
Alex Perrybac3d3f2019-03-10 14:26:51 -070075struct PointCostFunctor {
76 PointCostFunctor(Vector<2> result, Vector<2> template_pt,
Tyler Chatowbf0609c2021-07-31 16:13:27 -070077 IntrinsicParams intrinsics)
Parker Schuh2a1447c2019-02-17 00:25:29 -080078 : result(result), template_pt(template_pt), intrinsics(intrinsics) {}
79
Alex Perry3d0abf22019-04-06 19:52:24 -070080 template <typename T>
81 bool operator()(const T *const x, T *residual) const {
82 const auto extrinsics = TemplatedExtrinsicParams<T>::get(x);
83 ::Eigen::Matrix<T, 2, 1> pt =
84 Project<T>(ToEigenMatrix<T>(template_pt), intrinsics, extrinsics);
85 residual[0] = result.x() - pt(0, 0);
Alex Perry670d5ac2019-04-07 14:20:31 -070086 residual[1] = result.y() - pt(1, 0);
Parker Schuh2a1447c2019-02-17 00:25:29 -080087 return true;
88 }
89
90 Vector<2> result;
91 Vector<2> template_pt;
92 IntrinsicParams intrinsics;
93};
94
Alex Perrybac3d3f2019-03-10 14:26:51 -070095// Find the distance from a lower target point to the 'vertical' line it should
96// be on.
97struct LineCostFunctor {
98 LineCostFunctor(Vector<2> result, Segment<2> template_seg,
99 IntrinsicParams intrinsics)
100 : result(result), template_seg(template_seg), intrinsics(intrinsics) {}
101
Alex Perry3d0abf22019-04-06 19:52:24 -0700102 template <typename T>
103 bool operator()(const T *const x, T *residual) const {
104 const auto extrinsics = TemplatedExtrinsicParams<T>::get(x);
105 const ::Eigen::Matrix<T, 2, 1> p1 =
106 Project<T>(ToEigenMatrix<T>(template_seg.A()), intrinsics, extrinsics);
107 const ::Eigen::Matrix<T, 2, 1> p2 =
108 Project<T>(ToEigenMatrix<T>(template_seg.B()), intrinsics, extrinsics);
109 // Distance from line(P1, P2) to point result
110 T dx = p2.x() - p1.x();
111 T dy = p2.y() - p1.y();
Tyler Chatowbf0609c2021-07-31 16:13:27 -0700112 T denom = (p2 - p1).norm();
Alex Perry3d0abf22019-04-06 19:52:24 -0700113 residual[0] = ceres::abs(dy * result.x() - dx * result.y() +
Alex Perrybac3d3f2019-03-10 14:26:51 -0700114 p2.x() * p1.y() - p2.y() * p1.x()) /
115 denom;
116 return true;
117 }
118
119 Vector<2> result;
120 Segment<2> template_seg;
121 IntrinsicParams intrinsics;
122};
123
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700124// Find the distance that the bottom point is outside the target and penalize
125// that linearly.
126class BottomPointCostFunctor {
127 public:
128 BottomPointCostFunctor(::Eigen::Vector2f bottom_point,
129 Segment<2> template_seg, IntrinsicParams intrinsics)
130 : bottom_point_(bottom_point.x(), bottom_point.y()),
131 template_seg_(template_seg),
132 intrinsics_(intrinsics) {}
133
Alex Perry3d0abf22019-04-06 19:52:24 -0700134 template <typename T>
135 bool operator()(const T *const x, T *residual) const {
136 const auto extrinsics = TemplatedExtrinsicParams<T>::get(x);
137 const ::Eigen::Matrix<T, 2, 1> p1 = Project<T>(
138 ToEigenMatrix<T>(template_seg_.A()), intrinsics_, extrinsics);
139 const ::Eigen::Matrix<T, 2, 1> p2 = Project<T>(
140 ToEigenMatrix<T>(template_seg_.B()), intrinsics_, extrinsics);
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700141
142 // Construct a vector pointed perpendicular to the line. This vector is
143 // pointed down out the bottom of the target.
Alex Perry3d0abf22019-04-06 19:52:24 -0700144 ::Eigen::Matrix<T, 2, 1> down_axis;
145 down_axis << -(p1.y() - p2.y()), p1.x() - p2.x();
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700146 down_axis.normalize();
147
148 // Positive means out.
Tyler Chatowbf0609c2021-07-31 16:13:27 -0700149 const T component = down_axis.transpose() * (bottom_point_ - p1);
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700150
Alex Perry3d0abf22019-04-06 19:52:24 -0700151 if (component > T(0)) {
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700152 residual[0] = component * 1.0;
153 } else {
Alex Perry3d0abf22019-04-06 19:52:24 -0700154 residual[0] = T(0);
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700155 }
156 return true;
157 }
158
159 private:
160 ::Eigen::Vector2d bottom_point_;
161 Segment<2> template_seg_;
162
163 IntrinsicParams intrinsics_;
164};
165
Parker Schuh2a1447c2019-02-17 00:25:29 -0800166IntermediateResult TargetFinder::ProcessTargetToResult(const Target &target,
167 bool verbose) {
168 // Memory for the ceres solver.
Alex Perrybac3d3f2019-03-10 14:26:51 -0700169 double params_8point[ExtrinsicParams::kNumParams];
170 default_extrinsics_.set(&params_8point[0]);
171 double params_4point[ExtrinsicParams::kNumParams];
172 default_extrinsics_.set(&params_4point[0]);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800173
Brian Silverman63236772019-03-23 22:02:44 -0700174 Problem::Options problem_options;
175 problem_options.context = ceres_context_.get();
176 Problem problem_8point(problem_options);
177 Problem problem_4point(problem_options);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800178
Austin Schuh2894e902019-03-03 21:12:46 -0800179 ::std::array<aos::vision::Vector<2>, 8> target_value = target.ToPointList();
180 ::std::array<aos::vision::Vector<2>, 8> template_value =
181 target_template_.ToPointList();
Parker Schuh2a1447c2019-02-17 00:25:29 -0800182
183 for (size_t i = 0; i < 8; ++i) {
Austin Schuh2894e902019-03-03 21:12:46 -0800184 aos::vision::Vector<2> a = template_value[i];
185 aos::vision::Vector<2> b = target_value[i];
Parker Schuh2a1447c2019-02-17 00:25:29 -0800186
Alex Perrybac3d3f2019-03-10 14:26:51 -0700187 if (i % 2 == 1) {
Tyler Chatowbf0609c2021-07-31 16:13:27 -0700188 aos::vision::Vector<2> a2 = template_value[i - 1];
Alex Perrybac3d3f2019-03-10 14:26:51 -0700189 aos::vision::Segment<2> line = Segment<2>(a, a2);
190
191 problem_4point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700192 new ceres::AutoDiffCostFunction<LineCostFunctor, 1, 4>(
Alex Perrybac3d3f2019-03-10 14:26:51 -0700193 new LineCostFunctor(b, line, intrinsics_)),
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700194 NULL, &params_4point[0]);
Alex Perrybac3d3f2019-03-10 14:26:51 -0700195 } else {
196 problem_4point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700197 new ceres::AutoDiffCostFunction<PointCostFunctor, 2, 4>(
Alex Perrybac3d3f2019-03-10 14:26:51 -0700198 new PointCostFunctor(b, a, intrinsics_)),
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700199 NULL, &params_4point[0]);
Alex Perrybac3d3f2019-03-10 14:26:51 -0700200 }
201
202 problem_8point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700203 new ceres::AutoDiffCostFunction<PointCostFunctor, 2, 4>(
Alex Perrybac3d3f2019-03-10 14:26:51 -0700204 new PointCostFunctor(b, a, intrinsics_)),
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700205 NULL, &params_8point[0]);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800206 }
207
Austin Schuhbb2ac922019-03-11 01:09:57 -0700208 Solver::Options options;
209 options.minimizer_progress_to_stdout = false;
210 Solver::Summary summary_8point;
211 Solve(options, &problem_8point, &summary_8point);
212
Tyler Chatowbf0609c2021-07-31 16:13:27 -0700213 // So, let's sneak up on it. Start by warm-starting it with where we got on
214 // the 8 point solution.
Austin Schuhbb2ac922019-03-11 01:09:57 -0700215 ExtrinsicParams::get(&params_8point[0]).set(&params_4point[0]);
216 // Then solve without the bottom constraint.
217 Solver::Summary summary_4point1;
218 Solve(options, &problem_4point, &summary_4point1);
219
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700220 // Now, add a large cost for the bottom point being below the bottom line.
221 problem_4point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700222 new ceres::AutoDiffCostFunction<BottomPointCostFunctor, 1, 4>(
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700223 new BottomPointCostFunctor(target.left.bottom_point,
224 Segment<2>(target_template_.left.outside,
225 target_template_.left.bottom),
226 intrinsics_)),
227 NULL, &params_4point[0]);
228 // Make sure to point the segment the other way so when we do a -pi/2 rotation
229 // on the line, it points down in target space.
230 problem_4point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700231 new ceres::AutoDiffCostFunction<BottomPointCostFunctor, 1, 4>(
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700232 new BottomPointCostFunctor(target.right.bottom_point,
233 Segment<2>(target_template_.right.bottom,
234 target_template_.right.outside),
235 intrinsics_)),
236 NULL, &params_4point[0]);
237
Austin Schuhbb2ac922019-03-11 01:09:57 -0700238 // And then re-solve.
239 Solver::Summary summary_4point2;
240 Solve(options, &problem_4point, &summary_4point2);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800241
242 IntermediateResult IR;
Alex Perrybac3d3f2019-03-10 14:26:51 -0700243 IR.extrinsics = ExtrinsicParams::get(&params_8point[0]);
244 IR.solver_error = summary_8point.final_cost;
245 IR.backup_extrinsics = ExtrinsicParams::get(&params_4point[0]);
Austin Schuhbb2ac922019-03-11 01:09:57 -0700246 IR.backup_solver_error = summary_4point2.final_cost;
Parker Schuh2a1447c2019-02-17 00:25:29 -0800247
Alex Perryb6f334d2019-03-23 13:10:45 -0700248 // Normalize all angles to (-M_PI, M_PI]
249 IR.extrinsics.r1 = ::aos::math::NormalizeAngle(IR.extrinsics.r1);
250 IR.extrinsics.r2 = ::aos::math::NormalizeAngle(IR.extrinsics.r2);
Austin Schuh45639882019-03-24 19:20:42 -0700251 IR.backup_extrinsics.r1 =
252 ::aos::math::NormalizeAngle(IR.backup_extrinsics.r1);
253 IR.backup_extrinsics.r2 =
254 ::aos::math::NormalizeAngle(IR.backup_extrinsics.r2);
Alex Perry5b1e8e32019-04-07 13:25:31 -0700255 IR.target_width = target.width();
Austin Schuh45639882019-03-24 19:20:42 -0700256
257 // Ok, let's look at how perpendicular the corners are.
258 // Vector from the outside to inside along the top on the left.
259 const ::Eigen::Vector2d top_left_vector =
260 (target.left.top.GetData() - target.left.inside.GetData())
261 .transpose()
262 .normalized();
263 // Vector up the outside of the left target.
264 const ::Eigen::Vector2d outer_left_vector =
265 (target.left.top.GetData() - target.left.outside.GetData())
266 .transpose()
267 .normalized();
268 // Vector up the inside of the left target.
269 const ::Eigen::Vector2d inner_left_vector =
270 (target.left.inside.GetData() - target.left.bottom.GetData())
271 .transpose()
272 .normalized();
273
274 // Vector from the outside to inside along the top on the right.
275 const ::Eigen::Vector2d top_right_vector =
276 (target.right.top.GetData() - target.right.inside.GetData())
277 .transpose()
278 .normalized();
279 // Vector up the outside of the right target.
280 const ::Eigen::Vector2d outer_right_vector =
281 (target.right.top.GetData() - target.right.outside.GetData())
282 .transpose()
283 .normalized();
284 // Vector up the inside of the right target.
285 const ::Eigen::Vector2d inner_right_vector =
286 (target.right.inside.GetData() - target.right.bottom.GetData())
287 .transpose()
288 .normalized();
289
290 // Now dot the vectors and use that to compute angles.
291 // Left side, outside corner.
292 const double left_outer_corner_dot =
293 (outer_left_vector.transpose() * top_left_vector)(0);
294 // Left side, inside corner.
295 const double left_inner_corner_dot =
296 (inner_left_vector.transpose() * top_left_vector)(0);
297 // Right side, outside corner.
298 const double right_outer_corner_dot =
299 (outer_right_vector.transpose() * top_right_vector)(0);
300 // Right side, inside corner.
301 const double right_inner_corner_dot =
302 (inner_right_vector.transpose() * top_right_vector)(0);
303
304 constexpr double kCornerThreshold = 0.35;
305 if (::std::abs(left_outer_corner_dot) < kCornerThreshold &&
306 ::std::abs(left_inner_corner_dot) < kCornerThreshold &&
307 ::std::abs(right_outer_corner_dot) < kCornerThreshold &&
308 ::std::abs(right_inner_corner_dot) < kCornerThreshold) {
309 IR.good_corners = true;
310 } else {
311 IR.good_corners = false;
312 }
Alex Perryb6f334d2019-03-23 13:10:45 -0700313
Parker Schuh2a1447c2019-02-17 00:25:29 -0800314 if (verbose) {
Alex Perrybac3d3f2019-03-10 14:26:51 -0700315 std::cout << "rup = " << intrinsics_.mount_angle * 180 / M_PI << ";\n";
316 std::cout << "fl = " << intrinsics_.focal_length << ";\n";
317 std::cout << "8 points:\n";
318 std::cout << summary_8point.BriefReport() << "\n";
319 std::cout << "error = " << summary_8point.final_cost << ";\n";
Parker Schuh2a1447c2019-02-17 00:25:29 -0800320 std::cout << "y = " << IR.extrinsics.y / kInchesToMeters << ";\n";
321 std::cout << "z = " << IR.extrinsics.z / kInchesToMeters << ";\n";
322 std::cout << "r1 = " << IR.extrinsics.r1 * 180 / M_PI << ";\n";
323 std::cout << "r2 = " << IR.extrinsics.r2 * 180 / M_PI << ";\n";
Alex Perrybac3d3f2019-03-10 14:26:51 -0700324 std::cout << "4 points:\n";
Austin Schuhbb2ac922019-03-11 01:09:57 -0700325 std::cout << summary_4point1.BriefReport() << "\n";
326 std::cout << "error = " << summary_4point1.final_cost << ";\n\n";
327 std::cout << "4 points:\n";
328 std::cout << summary_4point2.BriefReport() << "\n";
329 std::cout << "error = " << summary_4point2.final_cost << ";\n\n";
Alex Perrybac3d3f2019-03-10 14:26:51 -0700330 std::cout << "y = " << IR.backup_extrinsics.y / kInchesToMeters << ";\n";
331 std::cout << "z = " << IR.backup_extrinsics.z / kInchesToMeters << ";\n";
332 std::cout << "r1 = " << IR.backup_extrinsics.r1 * 180 / M_PI << ";\n";
333 std::cout << "r2 = " << IR.backup_extrinsics.r2 * 180 / M_PI << ";\n";
Austin Schuh45639882019-03-24 19:20:42 -0700334
Austin Schuh45639882019-03-24 19:20:42 -0700335 printf("left upper outer corner angle: %f, top (%f, %f), outer (%f, %f)\n",
336 (outer_left_vector.transpose() * top_left_vector)(0),
337 top_left_vector(0, 0), top_left_vector(1, 0),
338 outer_left_vector(0, 0), outer_left_vector(1, 0));
339 printf("left upper inner corner angle: %f\n",
340 (inner_left_vector.transpose() * top_left_vector)(0));
341
342 printf("right upper outer corner angle: %f, top (%f, %f), outer (%f, %f)\n",
343 (outer_right_vector.transpose() * top_right_vector)(0),
344 top_right_vector(0, 0), top_right_vector(1, 0),
345 outer_right_vector(0, 0), outer_right_vector(1, 0));
346 printf("right upper inner corner angle: %f\n",
347 (inner_right_vector.transpose() * top_right_vector)(0));
Parker Schuh2a1447c2019-02-17 00:25:29 -0800348 }
349 return IR;
350}
351
352} // namespace vision
353} // namespace y2019