Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 1 | #include "y2019/vision/target_finder.h" |
| 2 | |
| 3 | #include "ceres/ceres.h" |
| 4 | |
| 5 | #include <math.h> |
| 6 | |
| 7 | using ceres::NumericDiffCostFunction; |
| 8 | using ceres::CENTRAL; |
| 9 | using ceres::CostFunction; |
| 10 | using ceres::Problem; |
| 11 | using ceres::Solver; |
| 12 | using ceres::Solve; |
| 13 | |
| 14 | namespace y2019 { |
| 15 | namespace vision { |
| 16 | |
| 17 | static constexpr double kInchesToMeters = 0.0254; |
| 18 | |
| 19 | using namespace aos::vision; |
| 20 | using aos::vision::Vector; |
| 21 | |
| 22 | Target 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 Schuh | 2894e90 | 2019-03-03 21:12:46 -0800 | [diff] [blame] | 48 | std::array<Vector<2>, 8> Target::ToPointList() const { |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 49 | // 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 Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 51 | 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 Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 54 | } |
| 55 | |
| 56 | Vector<2> Project(Vector<2> pt, const IntrinsicParams &intrinsics, |
| 57 | const ExtrinsicParams &extrinsics) { |
James Kuszmaul | 289756f | 2019-03-05 21:52:10 -0800 | [diff] [blame] | 58 | const double y = extrinsics.y; // height |
| 59 | const double z = extrinsics.z; // distance |
| 60 | const double r1 = extrinsics.r1; // skew |
| 61 | const double r2 = extrinsics.r2; // heading |
Austin Schuh | cacc692 | 2019-03-06 20:44:30 -0800 | [diff] [blame] | 62 | const double rup = intrinsics.mount_angle; |
| 63 | const double rbarrel = intrinsics.barrel_mount; |
| 64 | const double fl = intrinsics.focal_length; |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 65 | |
James Kuszmaul | 289756f | 2019-03-05 21:52:10 -0800 | [diff] [blame] | 66 | // Start by translating point in target-space to be at correct height. |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 67 | ::Eigen::Matrix<double, 1, 3> pts{pt.x(), pt.y() + y, 0.0}; |
| 68 | |
| 69 | { |
James Kuszmaul | 289756f | 2019-03-05 21:52:10 -0800 | [diff] [blame] | 70 | // Rotate to compensate for skew angle, to get into a frame still at the |
| 71 | // same (x, y) position as the target but rotated to be facing straight |
| 72 | // towards the camera. |
Austin Schuh | cacc692 | 2019-03-06 20:44:30 -0800 | [diff] [blame] | 73 | const double theta = r1; |
| 74 | const double s = sin(theta); |
| 75 | const double c = cos(theta); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 76 | pts = (::Eigen::Matrix<double, 3, 3>() << c, 0, -s, 0, 1, 0, s, 0, |
| 77 | c).finished() * |
| 78 | pts.transpose(); |
| 79 | } |
| 80 | |
James Kuszmaul | 289756f | 2019-03-05 21:52:10 -0800 | [diff] [blame] | 81 | // Translate the coordinate frame to have (x, y) centered at the camera, but |
| 82 | // still oriented to be facing along the line from the camera to the target. |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 83 | pts(2) += z; |
| 84 | |
| 85 | { |
James Kuszmaul | 289756f | 2019-03-05 21:52:10 -0800 | [diff] [blame] | 86 | // Rotate out the heading so that the frame is oriented to line up with the |
| 87 | // camera's viewpoint in the yaw-axis. |
Austin Schuh | cacc692 | 2019-03-06 20:44:30 -0800 | [diff] [blame] | 88 | const double theta = r2; |
| 89 | const double s = sin(theta); |
| 90 | const double c = cos(theta); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 91 | pts = (::Eigen::Matrix<double, 3, 3>() << c, 0, -s, 0, 1, 0, s, 0, |
| 92 | c).finished() * |
| 93 | pts.transpose(); |
| 94 | } |
| 95 | |
| 96 | // TODO: Apply 15 degree downward rotation. |
| 97 | { |
James Kuszmaul | 289756f | 2019-03-05 21:52:10 -0800 | [diff] [blame] | 98 | // Compensate for rotation in the pitch of the camera up/down to get into |
| 99 | // the coordinate frame lined up with the plane of the camera sensor. |
Austin Schuh | cacc692 | 2019-03-06 20:44:30 -0800 | [diff] [blame] | 100 | const double theta = rup; |
| 101 | const double s = sin(theta); |
| 102 | const double c = cos(theta); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 103 | |
| 104 | pts = (::Eigen::Matrix<double, 3, 3>() << 1, 0, 0, 0, c, -s, 0, s, |
| 105 | c).finished() * |
| 106 | pts.transpose(); |
| 107 | } |
| 108 | |
James Kuszmaul | 289756f | 2019-03-05 21:52:10 -0800 | [diff] [blame] | 109 | // Compensate for rotation of the barrel of the camera, i.e. about the axis |
| 110 | // that points straight out from the camera lense, using an AngleAxis instead |
| 111 | // of manually constructing the rotation matrices because once you get into |
| 112 | // this frame you no longer need to be masochistic. |
Parker Schuh | 9e1d169 | 2019-02-24 14:34:04 -0800 | [diff] [blame] | 113 | // TODO: Maybe barrel should be extrinsics to allow rocking? |
| 114 | // Also, in this case, barrel should go above the rotation above? |
| 115 | pts = ::Eigen::AngleAxis<double>(rbarrel, ::Eigen::Vector3d(0.0, 0.0, 1.0)) * |
| 116 | pts.transpose(); |
| 117 | |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 118 | // TODO: Final image projection. |
Austin Schuh | cacc692 | 2019-03-06 20:44:30 -0800 | [diff] [blame] | 119 | const ::Eigen::Matrix<double, 1, 3> res = pts; |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 120 | |
James Kuszmaul | 289756f | 2019-03-05 21:52:10 -0800 | [diff] [blame] | 121 | // Finally, scale to account for focal length and translate to get into |
| 122 | // pixel-space. |
Austin Schuh | cacc692 | 2019-03-06 20:44:30 -0800 | [diff] [blame] | 123 | const float scale = fl / res.z(); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 124 | return Vector<2>(res.x() * scale + 320.0, 240.0 - res.y() * scale); |
| 125 | } |
| 126 | |
| 127 | Target Project(const Target &target, const IntrinsicParams &intrinsics, |
| 128 | const ExtrinsicParams &extrinsics) { |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 129 | Target new_targ; |
| 130 | new_targ.right.is_right = true; |
Austin Schuh | 4d6e9bd | 2019-03-08 19:54:17 -0800 | [diff] [blame] | 131 | new_targ.right.top = Project(target.right.top, intrinsics, extrinsics); |
| 132 | new_targ.right.inside = Project(target.right.inside, intrinsics, extrinsics); |
| 133 | new_targ.right.bottom = Project(target.right.bottom, intrinsics, extrinsics); |
| 134 | new_targ.right.outside = |
| 135 | Project(target.right.outside, intrinsics, extrinsics); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 136 | |
Austin Schuh | 4d6e9bd | 2019-03-08 19:54:17 -0800 | [diff] [blame] | 137 | new_targ.left.top = Project(target.left.top, intrinsics, extrinsics); |
| 138 | new_targ.left.inside = Project(target.left.inside, intrinsics, extrinsics); |
| 139 | new_targ.left.bottom = Project(target.left.bottom, intrinsics, extrinsics); |
| 140 | new_targ.left.outside = Project(target.left.outside, intrinsics, extrinsics); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 141 | |
| 142 | return new_targ; |
| 143 | } |
| 144 | |
| 145 | // Used at runtime on a single image given camera parameters. |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 146 | struct PointCostFunctor { |
| 147 | PointCostFunctor(Vector<2> result, Vector<2> template_pt, |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 148 | IntrinsicParams intrinsics) |
| 149 | : result(result), template_pt(template_pt), intrinsics(intrinsics) {} |
| 150 | |
| 151 | bool operator()(const double *const x, double *residual) const { |
| 152 | auto extrinsics = ExtrinsicParams::get(x); |
| 153 | auto pt = result - Project(template_pt, intrinsics, extrinsics); |
| 154 | residual[0] = pt.x(); |
| 155 | residual[1] = pt.y(); |
| 156 | return true; |
| 157 | } |
| 158 | |
| 159 | Vector<2> result; |
| 160 | Vector<2> template_pt; |
| 161 | IntrinsicParams intrinsics; |
| 162 | }; |
| 163 | |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 164 | // Find the distance from a lower target point to the 'vertical' line it should |
| 165 | // be on. |
| 166 | struct LineCostFunctor { |
| 167 | LineCostFunctor(Vector<2> result, Segment<2> template_seg, |
| 168 | IntrinsicParams intrinsics) |
| 169 | : result(result), template_seg(template_seg), intrinsics(intrinsics) {} |
| 170 | |
| 171 | bool operator()(const double *const x, double *residual) const { |
| 172 | const auto extrinsics = ExtrinsicParams::get(x); |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 173 | const Vector<2> p1 = Project(template_seg.A(), intrinsics, extrinsics); |
| 174 | const Vector<2> p2 = Project(template_seg.B(), intrinsics, extrinsics); |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 175 | // distance from line (P1, P2) to point result |
| 176 | double dx = p2.x() - p1.x(); |
| 177 | double dy = p2.y() - p1.y(); |
| 178 | double denom = p2.DistanceTo(p1); |
| 179 | residual[0] = ::std::abs(dy * result.x() - dx * result.y() + |
| 180 | p2.x() * p1.y() - p2.y() * p1.x()) / |
| 181 | denom; |
| 182 | return true; |
| 183 | } |
| 184 | |
| 185 | Vector<2> result; |
| 186 | Segment<2> template_seg; |
| 187 | IntrinsicParams intrinsics; |
| 188 | }; |
| 189 | |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 190 | // Find the distance that the bottom point is outside the target and penalize |
| 191 | // that linearly. |
| 192 | class BottomPointCostFunctor { |
| 193 | public: |
| 194 | BottomPointCostFunctor(::Eigen::Vector2f bottom_point, |
| 195 | Segment<2> template_seg, IntrinsicParams intrinsics) |
| 196 | : bottom_point_(bottom_point.x(), bottom_point.y()), |
| 197 | template_seg_(template_seg), |
| 198 | intrinsics_(intrinsics) {} |
| 199 | |
| 200 | bool operator()(const double *const x, double *residual) const { |
| 201 | const ExtrinsicParams extrinsics = ExtrinsicParams::get(x); |
| 202 | const Vector<2> p1 = Project(template_seg_.A(), intrinsics_, extrinsics); |
| 203 | const Vector<2> p2 = Project(template_seg_.B(), intrinsics_, extrinsics); |
| 204 | |
| 205 | // Construct a vector pointed perpendicular to the line. This vector is |
| 206 | // pointed down out the bottom of the target. |
| 207 | ::Eigen::Vector2d down_axis(-(p1.y() - p2.y()), p1.x() - p2.x()); |
| 208 | down_axis.normalize(); |
| 209 | |
| 210 | // Positive means out. |
| 211 | const double component = |
| 212 | down_axis.transpose() * (bottom_point_ - p1.GetData().transpose()); |
| 213 | |
| 214 | if (component > 0) { |
| 215 | residual[0] = component * 1.0; |
| 216 | } else { |
| 217 | residual[0] = 0.0; |
| 218 | } |
| 219 | return true; |
| 220 | } |
| 221 | |
| 222 | private: |
| 223 | ::Eigen::Vector2d bottom_point_; |
| 224 | Segment<2> template_seg_; |
| 225 | |
| 226 | IntrinsicParams intrinsics_; |
| 227 | }; |
| 228 | |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 229 | IntermediateResult TargetFinder::ProcessTargetToResult(const Target &target, |
| 230 | bool verbose) { |
| 231 | // Memory for the ceres solver. |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 232 | double params_8point[ExtrinsicParams::kNumParams]; |
| 233 | default_extrinsics_.set(¶ms_8point[0]); |
| 234 | double params_4point[ExtrinsicParams::kNumParams]; |
| 235 | default_extrinsics_.set(¶ms_4point[0]); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 236 | |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 237 | Problem problem_8point; |
| 238 | Problem problem_4point; |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 239 | |
Austin Schuh | 2894e90 | 2019-03-03 21:12:46 -0800 | [diff] [blame] | 240 | ::std::array<aos::vision::Vector<2>, 8> target_value = target.ToPointList(); |
| 241 | ::std::array<aos::vision::Vector<2>, 8> template_value = |
| 242 | target_template_.ToPointList(); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 243 | |
| 244 | for (size_t i = 0; i < 8; ++i) { |
Austin Schuh | 2894e90 | 2019-03-03 21:12:46 -0800 | [diff] [blame] | 245 | aos::vision::Vector<2> a = template_value[i]; |
| 246 | aos::vision::Vector<2> b = target_value[i]; |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 247 | |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 248 | if (i % 2 == 1) { |
| 249 | aos::vision::Vector<2> a2 = template_value[i-1]; |
| 250 | aos::vision::Segment<2> line = Segment<2>(a, a2); |
| 251 | |
| 252 | problem_4point.AddResidualBlock( |
| 253 | new NumericDiffCostFunction<LineCostFunctor, CENTRAL, 1, 4>( |
| 254 | new LineCostFunctor(b, line, intrinsics_)), |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 255 | NULL, ¶ms_4point[0]); |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 256 | } else { |
| 257 | problem_4point.AddResidualBlock( |
| 258 | new NumericDiffCostFunction<PointCostFunctor, CENTRAL, 2, 4>( |
| 259 | new PointCostFunctor(b, a, intrinsics_)), |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 260 | NULL, ¶ms_4point[0]); |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 261 | } |
| 262 | |
| 263 | problem_8point.AddResidualBlock( |
| 264 | new NumericDiffCostFunction<PointCostFunctor, CENTRAL, 2, 4>( |
| 265 | new PointCostFunctor(b, a, intrinsics_)), |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 266 | NULL, ¶ms_8point[0]); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 267 | } |
| 268 | |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 269 | // Now, add a large cost for the bottom point being below the bottom line. |
| 270 | problem_4point.AddResidualBlock( |
| 271 | new NumericDiffCostFunction<BottomPointCostFunctor, CENTRAL, 1, 4>( |
| 272 | new BottomPointCostFunctor(target.left.bottom_point, |
| 273 | Segment<2>(target_template_.left.outside, |
| 274 | target_template_.left.bottom), |
| 275 | intrinsics_)), |
| 276 | NULL, ¶ms_4point[0]); |
| 277 | // Make sure to point the segment the other way so when we do a -pi/2 rotation |
| 278 | // on the line, it points down in target space. |
| 279 | problem_4point.AddResidualBlock( |
| 280 | new NumericDiffCostFunction<BottomPointCostFunctor, CENTRAL, 1, 4>( |
| 281 | new BottomPointCostFunctor(target.right.bottom_point, |
| 282 | Segment<2>(target_template_.right.bottom, |
| 283 | target_template_.right.outside), |
| 284 | intrinsics_)), |
| 285 | NULL, ¶ms_4point[0]); |
| 286 | |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 287 | Solver::Options options; |
| 288 | options.minimizer_progress_to_stdout = false; |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 289 | Solver::Summary summary_8point; |
| 290 | Solve(options, &problem_8point, &summary_8point); |
| 291 | Solver::Summary summary_4point; |
| 292 | Solve(options, &problem_4point, &summary_4point); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 293 | |
| 294 | IntermediateResult IR; |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 295 | IR.extrinsics = ExtrinsicParams::get(¶ms_8point[0]); |
| 296 | IR.solver_error = summary_8point.final_cost; |
| 297 | IR.backup_extrinsics = ExtrinsicParams::get(¶ms_4point[0]); |
| 298 | IR.backup_solver_error = summary_4point.final_cost; |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 299 | |
| 300 | if (verbose) { |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 301 | std::cout << "rup = " << intrinsics_.mount_angle * 180 / M_PI << ";\n"; |
| 302 | std::cout << "fl = " << intrinsics_.focal_length << ";\n"; |
| 303 | std::cout << "8 points:\n"; |
| 304 | std::cout << summary_8point.BriefReport() << "\n"; |
| 305 | std::cout << "error = " << summary_8point.final_cost << ";\n"; |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 306 | std::cout << "y = " << IR.extrinsics.y / kInchesToMeters << ";\n"; |
| 307 | std::cout << "z = " << IR.extrinsics.z / kInchesToMeters << ";\n"; |
| 308 | std::cout << "r1 = " << IR.extrinsics.r1 * 180 / M_PI << ";\n"; |
| 309 | std::cout << "r2 = " << IR.extrinsics.r2 * 180 / M_PI << ";\n"; |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 310 | std::cout << "4 points:\n"; |
| 311 | std::cout << summary_4point.BriefReport() << "\n"; |
| 312 | std::cout << "error = " << summary_4point.final_cost << ";\n\n"; |
| 313 | std::cout << "y = " << IR.backup_extrinsics.y / kInchesToMeters << ";\n"; |
| 314 | std::cout << "z = " << IR.backup_extrinsics.z / kInchesToMeters << ";\n"; |
| 315 | std::cout << "r1 = " << IR.backup_extrinsics.r1 * 180 / M_PI << ";\n"; |
| 316 | std::cout << "r2 = " << IR.backup_extrinsics.r2 * 180 / M_PI << ";\n"; |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 317 | } |
| 318 | return IR; |
| 319 | } |
| 320 | |
| 321 | } // namespace vision |
| 322 | } // namespace y2019 |