blob: 86ead34232d2e911907f1062f4d56ff010f6b91e [file] [log] [blame]
Tyler Chatowbf0609c2021-07-31 16:13:27 -07001#include <cmath>
Parker Schuh2a1447c2019-02-17 00:25:29 -08002
Alex Perryb6f334d2019-03-23 13:10:45 -07003#include "aos/util/math.h"
Tyler Chatowbf0609c2021-07-31 16:13:27 -07004#include "ceres/ceres.h"
5#include "y2019/vision/target_finder.h"
Alex Perryb6f334d2019-03-23 13:10:45 -07006
Parker Schuh2a1447c2019-02-17 00:25:29 -08007using ceres::CENTRAL;
8using ceres::CostFunction;
9using ceres::Problem;
Parker Schuh2a1447c2019-02-17 00:25:29 -080010using ceres::Solve;
Tyler Chatowbf0609c2021-07-31 16:13:27 -070011using ceres::Solver;
Parker Schuh2a1447c2019-02-17 00:25:29 -080012
13namespace y2019 {
14namespace vision {
15
16static constexpr double kInchesToMeters = 0.0254;
17
18using namespace aos::vision;
19using aos::vision::Vector;
20
21Target Target::MakeTemplate() {
22 Target out;
23 // This is how off-vertical the tape is.
24 const double theta = 14.5 * M_PI / 180.0;
25
26 const double tape_offset = 4 * kInchesToMeters;
27 const double tape_width = 2 * kInchesToMeters;
28 const double tape_length = 5.5 * kInchesToMeters;
29
30 const double s = sin(theta);
31 const double c = cos(theta);
32 out.right.top = Vector<2>(tape_offset, 0.0);
33 out.right.inside = Vector<2>(tape_offset + tape_width * c, tape_width * s);
34 out.right.bottom = Vector<2>(tape_offset + tape_width * c + tape_length * s,
35 tape_width * s - tape_length * c);
36 out.right.outside =
37 Vector<2>(tape_offset + tape_length * s, -tape_length * c);
38
39 out.right.is_right = true;
40 out.left.top = Vector<2>(-out.right.top.x(), out.right.top.y());
41 out.left.inside = Vector<2>(-out.right.inside.x(), out.right.inside.y());
42 out.left.bottom = Vector<2>(-out.right.bottom.x(), out.right.bottom.y());
43 out.left.outside = Vector<2>(-out.right.outside.x(), out.right.outside.y());
44 return out;
45}
46
Austin Schuh2894e902019-03-03 21:12:46 -080047std::array<Vector<2>, 8> Target::ToPointList() const {
Austin Schuhe6cfbe32019-03-10 18:05:57 -070048 // Note, the even points are fit with the line solver in the 4 point solution
49 // while the odds are fit with the point matcher.
Alex Perrybac3d3f2019-03-10 14:26:51 -070050 return std::array<Vector<2>, 8>{{right.top, right.outside, right.inside,
51 right.bottom, left.top, left.outside,
52 left.inside, left.bottom}};
Parker Schuh2a1447c2019-02-17 00:25:29 -080053}
54
Parker Schuh2a1447c2019-02-17 00:25:29 -080055Target Project(const Target &target, const IntrinsicParams &intrinsics,
56 const ExtrinsicParams &extrinsics) {
Parker Schuh2a1447c2019-02-17 00:25:29 -080057 Target new_targ;
58 new_targ.right.is_right = true;
Austin Schuh4d6e9bd2019-03-08 19:54:17 -080059 new_targ.right.top = Project(target.right.top, intrinsics, extrinsics);
60 new_targ.right.inside = Project(target.right.inside, intrinsics, extrinsics);
61 new_targ.right.bottom = Project(target.right.bottom, intrinsics, extrinsics);
62 new_targ.right.outside =
63 Project(target.right.outside, intrinsics, extrinsics);
Parker Schuh2a1447c2019-02-17 00:25:29 -080064
Austin Schuh4d6e9bd2019-03-08 19:54:17 -080065 new_targ.left.top = Project(target.left.top, intrinsics, extrinsics);
66 new_targ.left.inside = Project(target.left.inside, intrinsics, extrinsics);
67 new_targ.left.bottom = Project(target.left.bottom, intrinsics, extrinsics);
68 new_targ.left.outside = Project(target.left.outside, intrinsics, extrinsics);
Parker Schuh2a1447c2019-02-17 00:25:29 -080069
70 return new_targ;
71}
72
73// Used at runtime on a single image given camera parameters.
Alex Perrybac3d3f2019-03-10 14:26:51 -070074struct PointCostFunctor {
75 PointCostFunctor(Vector<2> result, Vector<2> template_pt,
Tyler Chatowbf0609c2021-07-31 16:13:27 -070076 IntrinsicParams intrinsics)
Parker Schuh2a1447c2019-02-17 00:25:29 -080077 : result(result), template_pt(template_pt), intrinsics(intrinsics) {}
78
Alex Perry3d0abf22019-04-06 19:52:24 -070079 template <typename T>
80 bool operator()(const T *const x, T *residual) const {
81 const auto extrinsics = TemplatedExtrinsicParams<T>::get(x);
82 ::Eigen::Matrix<T, 2, 1> pt =
83 Project<T>(ToEigenMatrix<T>(template_pt), intrinsics, extrinsics);
84 residual[0] = result.x() - pt(0, 0);
Alex Perry670d5ac2019-04-07 14:20:31 -070085 residual[1] = result.y() - pt(1, 0);
Parker Schuh2a1447c2019-02-17 00:25:29 -080086 return true;
87 }
88
89 Vector<2> result;
90 Vector<2> template_pt;
91 IntrinsicParams intrinsics;
92};
93
Alex Perrybac3d3f2019-03-10 14:26:51 -070094// Find the distance from a lower target point to the 'vertical' line it should
95// be on.
96struct LineCostFunctor {
97 LineCostFunctor(Vector<2> result, Segment<2> template_seg,
98 IntrinsicParams intrinsics)
99 : result(result), template_seg(template_seg), intrinsics(intrinsics) {}
100
Alex Perry3d0abf22019-04-06 19:52:24 -0700101 template <typename T>
102 bool operator()(const T *const x, T *residual) const {
103 const auto extrinsics = TemplatedExtrinsicParams<T>::get(x);
104 const ::Eigen::Matrix<T, 2, 1> p1 =
105 Project<T>(ToEigenMatrix<T>(template_seg.A()), intrinsics, extrinsics);
106 const ::Eigen::Matrix<T, 2, 1> p2 =
107 Project<T>(ToEigenMatrix<T>(template_seg.B()), intrinsics, extrinsics);
108 // Distance from line(P1, P2) to point result
109 T dx = p2.x() - p1.x();
110 T dy = p2.y() - p1.y();
Tyler Chatowbf0609c2021-07-31 16:13:27 -0700111 T denom = (p2 - p1).norm();
Alex Perry3d0abf22019-04-06 19:52:24 -0700112 residual[0] = ceres::abs(dy * result.x() - dx * result.y() +
Alex Perrybac3d3f2019-03-10 14:26:51 -0700113 p2.x() * p1.y() - p2.y() * p1.x()) /
114 denom;
115 return true;
116 }
117
118 Vector<2> result;
119 Segment<2> template_seg;
120 IntrinsicParams intrinsics;
121};
122
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700123// Find the distance that the bottom point is outside the target and penalize
124// that linearly.
125class BottomPointCostFunctor {
126 public:
127 BottomPointCostFunctor(::Eigen::Vector2f bottom_point,
128 Segment<2> template_seg, IntrinsicParams intrinsics)
129 : bottom_point_(bottom_point.x(), bottom_point.y()),
130 template_seg_(template_seg),
131 intrinsics_(intrinsics) {}
132
Alex Perry3d0abf22019-04-06 19:52:24 -0700133 template <typename T>
134 bool operator()(const T *const x, T *residual) const {
135 const auto extrinsics = TemplatedExtrinsicParams<T>::get(x);
136 const ::Eigen::Matrix<T, 2, 1> p1 = Project<T>(
137 ToEigenMatrix<T>(template_seg_.A()), intrinsics_, extrinsics);
138 const ::Eigen::Matrix<T, 2, 1> p2 = Project<T>(
139 ToEigenMatrix<T>(template_seg_.B()), intrinsics_, extrinsics);
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700140
141 // Construct a vector pointed perpendicular to the line. This vector is
142 // pointed down out the bottom of the target.
Alex Perry3d0abf22019-04-06 19:52:24 -0700143 ::Eigen::Matrix<T, 2, 1> down_axis;
144 down_axis << -(p1.y() - p2.y()), p1.x() - p2.x();
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700145 down_axis.normalize();
146
147 // Positive means out.
Tyler Chatowbf0609c2021-07-31 16:13:27 -0700148 const T component = down_axis.transpose() * (bottom_point_ - p1);
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700149
Alex Perry3d0abf22019-04-06 19:52:24 -0700150 if (component > T(0)) {
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700151 residual[0] = component * 1.0;
152 } else {
Alex Perry3d0abf22019-04-06 19:52:24 -0700153 residual[0] = T(0);
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700154 }
155 return true;
156 }
157
158 private:
159 ::Eigen::Vector2d bottom_point_;
160 Segment<2> template_seg_;
161
162 IntrinsicParams intrinsics_;
163};
164
Parker Schuh2a1447c2019-02-17 00:25:29 -0800165IntermediateResult TargetFinder::ProcessTargetToResult(const Target &target,
166 bool verbose) {
167 // Memory for the ceres solver.
Alex Perrybac3d3f2019-03-10 14:26:51 -0700168 double params_8point[ExtrinsicParams::kNumParams];
169 default_extrinsics_.set(&params_8point[0]);
170 double params_4point[ExtrinsicParams::kNumParams];
171 default_extrinsics_.set(&params_4point[0]);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800172
Brian Silverman63236772019-03-23 22:02:44 -0700173 Problem::Options problem_options;
174 problem_options.context = ceres_context_.get();
175 Problem problem_8point(problem_options);
176 Problem problem_4point(problem_options);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800177
Austin Schuh2894e902019-03-03 21:12:46 -0800178 ::std::array<aos::vision::Vector<2>, 8> target_value = target.ToPointList();
179 ::std::array<aos::vision::Vector<2>, 8> template_value =
180 target_template_.ToPointList();
Parker Schuh2a1447c2019-02-17 00:25:29 -0800181
182 for (size_t i = 0; i < 8; ++i) {
Austin Schuh2894e902019-03-03 21:12:46 -0800183 aos::vision::Vector<2> a = template_value[i];
184 aos::vision::Vector<2> b = target_value[i];
Parker Schuh2a1447c2019-02-17 00:25:29 -0800185
Alex Perrybac3d3f2019-03-10 14:26:51 -0700186 if (i % 2 == 1) {
Tyler Chatowbf0609c2021-07-31 16:13:27 -0700187 aos::vision::Vector<2> a2 = template_value[i - 1];
Alex Perrybac3d3f2019-03-10 14:26:51 -0700188 aos::vision::Segment<2> line = Segment<2>(a, a2);
189
190 problem_4point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700191 new ceres::AutoDiffCostFunction<LineCostFunctor, 1, 4>(
Alex Perrybac3d3f2019-03-10 14:26:51 -0700192 new LineCostFunctor(b, line, intrinsics_)),
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700193 NULL, &params_4point[0]);
Alex Perrybac3d3f2019-03-10 14:26:51 -0700194 } else {
195 problem_4point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700196 new ceres::AutoDiffCostFunction<PointCostFunctor, 2, 4>(
Alex Perrybac3d3f2019-03-10 14:26:51 -0700197 new PointCostFunctor(b, a, intrinsics_)),
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700198 NULL, &params_4point[0]);
Alex Perrybac3d3f2019-03-10 14:26:51 -0700199 }
200
201 problem_8point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700202 new ceres::AutoDiffCostFunction<PointCostFunctor, 2, 4>(
Alex Perrybac3d3f2019-03-10 14:26:51 -0700203 new PointCostFunctor(b, a, intrinsics_)),
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700204 NULL, &params_8point[0]);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800205 }
206
Austin Schuhbb2ac922019-03-11 01:09:57 -0700207 Solver::Options options;
208 options.minimizer_progress_to_stdout = false;
209 Solver::Summary summary_8point;
210 Solve(options, &problem_8point, &summary_8point);
211
Tyler Chatowbf0609c2021-07-31 16:13:27 -0700212 // So, let's sneak up on it. Start by warm-starting it with where we got on
213 // the 8 point solution.
Austin Schuhbb2ac922019-03-11 01:09:57 -0700214 ExtrinsicParams::get(&params_8point[0]).set(&params_4point[0]);
215 // Then solve without the bottom constraint.
216 Solver::Summary summary_4point1;
217 Solve(options, &problem_4point, &summary_4point1);
218
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700219 // Now, add a large cost for the bottom point being below the bottom line.
220 problem_4point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700221 new ceres::AutoDiffCostFunction<BottomPointCostFunctor, 1, 4>(
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700222 new BottomPointCostFunctor(target.left.bottom_point,
223 Segment<2>(target_template_.left.outside,
224 target_template_.left.bottom),
225 intrinsics_)),
226 NULL, &params_4point[0]);
227 // Make sure to point the segment the other way so when we do a -pi/2 rotation
228 // on the line, it points down in target space.
229 problem_4point.AddResidualBlock(
Alex Perry3d0abf22019-04-06 19:52:24 -0700230 new ceres::AutoDiffCostFunction<BottomPointCostFunctor, 1, 4>(
Austin Schuhe6cfbe32019-03-10 18:05:57 -0700231 new BottomPointCostFunctor(target.right.bottom_point,
232 Segment<2>(target_template_.right.bottom,
233 target_template_.right.outside),
234 intrinsics_)),
235 NULL, &params_4point[0]);
236
Austin Schuhbb2ac922019-03-11 01:09:57 -0700237 // And then re-solve.
238 Solver::Summary summary_4point2;
239 Solve(options, &problem_4point, &summary_4point2);
Parker Schuh2a1447c2019-02-17 00:25:29 -0800240
241 IntermediateResult IR;
Alex Perrybac3d3f2019-03-10 14:26:51 -0700242 IR.extrinsics = ExtrinsicParams::get(&params_8point[0]);
243 IR.solver_error = summary_8point.final_cost;
244 IR.backup_extrinsics = ExtrinsicParams::get(&params_4point[0]);
Austin Schuhbb2ac922019-03-11 01:09:57 -0700245 IR.backup_solver_error = summary_4point2.final_cost;
Parker Schuh2a1447c2019-02-17 00:25:29 -0800246
Alex Perryb6f334d2019-03-23 13:10:45 -0700247 // Normalize all angles to (-M_PI, M_PI]
248 IR.extrinsics.r1 = ::aos::math::NormalizeAngle(IR.extrinsics.r1);
249 IR.extrinsics.r2 = ::aos::math::NormalizeAngle(IR.extrinsics.r2);
Austin Schuh45639882019-03-24 19:20:42 -0700250 IR.backup_extrinsics.r1 =
251 ::aos::math::NormalizeAngle(IR.backup_extrinsics.r1);
252 IR.backup_extrinsics.r2 =
253 ::aos::math::NormalizeAngle(IR.backup_extrinsics.r2);
Alex Perry5b1e8e32019-04-07 13:25:31 -0700254 IR.target_width = target.width();
Austin Schuh45639882019-03-24 19:20:42 -0700255
256 // Ok, let's look at how perpendicular the corners are.
257 // Vector from the outside to inside along the top on the left.
258 const ::Eigen::Vector2d top_left_vector =
259 (target.left.top.GetData() - target.left.inside.GetData())
260 .transpose()
261 .normalized();
262 // Vector up the outside of the left target.
263 const ::Eigen::Vector2d outer_left_vector =
264 (target.left.top.GetData() - target.left.outside.GetData())
265 .transpose()
266 .normalized();
267 // Vector up the inside of the left target.
268 const ::Eigen::Vector2d inner_left_vector =
269 (target.left.inside.GetData() - target.left.bottom.GetData())
270 .transpose()
271 .normalized();
272
273 // Vector from the outside to inside along the top on the right.
274 const ::Eigen::Vector2d top_right_vector =
275 (target.right.top.GetData() - target.right.inside.GetData())
276 .transpose()
277 .normalized();
278 // Vector up the outside of the right target.
279 const ::Eigen::Vector2d outer_right_vector =
280 (target.right.top.GetData() - target.right.outside.GetData())
281 .transpose()
282 .normalized();
283 // Vector up the inside of the right target.
284 const ::Eigen::Vector2d inner_right_vector =
285 (target.right.inside.GetData() - target.right.bottom.GetData())
286 .transpose()
287 .normalized();
288
289 // Now dot the vectors and use that to compute angles.
290 // Left side, outside corner.
291 const double left_outer_corner_dot =
292 (outer_left_vector.transpose() * top_left_vector)(0);
293 // Left side, inside corner.
294 const double left_inner_corner_dot =
295 (inner_left_vector.transpose() * top_left_vector)(0);
296 // Right side, outside corner.
297 const double right_outer_corner_dot =
298 (outer_right_vector.transpose() * top_right_vector)(0);
299 // Right side, inside corner.
300 const double right_inner_corner_dot =
301 (inner_right_vector.transpose() * top_right_vector)(0);
302
303 constexpr double kCornerThreshold = 0.35;
304 if (::std::abs(left_outer_corner_dot) < kCornerThreshold &&
305 ::std::abs(left_inner_corner_dot) < kCornerThreshold &&
306 ::std::abs(right_outer_corner_dot) < kCornerThreshold &&
307 ::std::abs(right_inner_corner_dot) < kCornerThreshold) {
308 IR.good_corners = true;
309 } else {
310 IR.good_corners = false;
311 }
Alex Perryb6f334d2019-03-23 13:10:45 -0700312
Parker Schuh2a1447c2019-02-17 00:25:29 -0800313 if (verbose) {
Alex Perrybac3d3f2019-03-10 14:26:51 -0700314 std::cout << "rup = " << intrinsics_.mount_angle * 180 / M_PI << ";\n";
315 std::cout << "fl = " << intrinsics_.focal_length << ";\n";
316 std::cout << "8 points:\n";
317 std::cout << summary_8point.BriefReport() << "\n";
318 std::cout << "error = " << summary_8point.final_cost << ";\n";
Parker Schuh2a1447c2019-02-17 00:25:29 -0800319 std::cout << "y = " << IR.extrinsics.y / kInchesToMeters << ";\n";
320 std::cout << "z = " << IR.extrinsics.z / kInchesToMeters << ";\n";
321 std::cout << "r1 = " << IR.extrinsics.r1 * 180 / M_PI << ";\n";
322 std::cout << "r2 = " << IR.extrinsics.r2 * 180 / M_PI << ";\n";
Alex Perrybac3d3f2019-03-10 14:26:51 -0700323 std::cout << "4 points:\n";
Austin Schuhbb2ac922019-03-11 01:09:57 -0700324 std::cout << summary_4point1.BriefReport() << "\n";
325 std::cout << "error = " << summary_4point1.final_cost << ";\n\n";
326 std::cout << "4 points:\n";
327 std::cout << summary_4point2.BriefReport() << "\n";
328 std::cout << "error = " << summary_4point2.final_cost << ";\n\n";
Alex Perrybac3d3f2019-03-10 14:26:51 -0700329 std::cout << "y = " << IR.backup_extrinsics.y / kInchesToMeters << ";\n";
330 std::cout << "z = " << IR.backup_extrinsics.z / kInchesToMeters << ";\n";
331 std::cout << "r1 = " << IR.backup_extrinsics.r1 * 180 / M_PI << ";\n";
332 std::cout << "r2 = " << IR.backup_extrinsics.r2 * 180 / M_PI << ";\n";
Austin Schuh45639882019-03-24 19:20:42 -0700333
Austin Schuh45639882019-03-24 19:20:42 -0700334 printf("left upper outer corner angle: %f, top (%f, %f), outer (%f, %f)\n",
335 (outer_left_vector.transpose() * top_left_vector)(0),
336 top_left_vector(0, 0), top_left_vector(1, 0),
337 outer_left_vector(0, 0), outer_left_vector(1, 0));
338 printf("left upper inner corner angle: %f\n",
339 (inner_left_vector.transpose() * top_left_vector)(0));
340
341 printf("right upper outer corner angle: %f, top (%f, %f), outer (%f, %f)\n",
342 (outer_right_vector.transpose() * top_right_vector)(0),
343 top_right_vector(0, 0), top_right_vector(1, 0),
344 outer_right_vector(0, 0), outer_right_vector(1, 0));
345 printf("right upper inner corner angle: %f\n",
346 (inner_right_vector.transpose() * top_right_vector)(0));
Parker Schuh2a1447c2019-02-17 00:25:29 -0800347 }
348 return IR;
349}
350
351} // namespace vision
352} // namespace y2019