Tyler Chatow | bf0609c | 2021-07-31 16:13:27 -0700 | [diff] [blame] | 1 | #include <cmath> |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 2 | |
Tyler Chatow | bf0609c | 2021-07-31 16:13:27 -0700 | [diff] [blame] | 3 | #include "ceres/ceres.h" |
Philipp Schrader | 790cb54 | 2023-07-05 21:06:52 -0700 | [diff] [blame] | 4 | |
| 5 | #include "aos/util/math.h" |
Tyler Chatow | bf0609c | 2021-07-31 16:13:27 -0700 | [diff] [blame] | 6 | #include "y2019/vision/target_finder.h" |
Alex Perry | b6f334d | 2019-03-23 13:10:45 -0700 | [diff] [blame] | 7 | |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 8 | using ceres::CENTRAL; |
| 9 | using ceres::CostFunction; |
| 10 | using ceres::Problem; |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 11 | using ceres::Solve; |
Tyler Chatow | bf0609c | 2021-07-31 16:13:27 -0700 | [diff] [blame] | 12 | using ceres::Solver; |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 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 | |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 56 | Target Project(const Target &target, const IntrinsicParams &intrinsics, |
| 57 | const ExtrinsicParams &extrinsics) { |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 58 | Target new_targ; |
| 59 | new_targ.right.is_right = true; |
Austin Schuh | 4d6e9bd | 2019-03-08 19:54:17 -0800 | [diff] [blame] | 60 | 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 Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 65 | |
Austin Schuh | 4d6e9bd | 2019-03-08 19:54:17 -0800 | [diff] [blame] | 66 | 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 Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 70 | |
| 71 | return new_targ; |
| 72 | } |
| 73 | |
| 74 | // Used at runtime on a single image given camera parameters. |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 75 | struct PointCostFunctor { |
| 76 | PointCostFunctor(Vector<2> result, Vector<2> template_pt, |
Tyler Chatow | bf0609c | 2021-07-31 16:13:27 -0700 | [diff] [blame] | 77 | IntrinsicParams intrinsics) |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 78 | : result(result), template_pt(template_pt), intrinsics(intrinsics) {} |
| 79 | |
Alex Perry | 3d0abf2 | 2019-04-06 19:52:24 -0700 | [diff] [blame] | 80 | 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 Perry | 670d5ac | 2019-04-07 14:20:31 -0700 | [diff] [blame] | 86 | residual[1] = result.y() - pt(1, 0); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 87 | return true; |
| 88 | } |
| 89 | |
| 90 | Vector<2> result; |
| 91 | Vector<2> template_pt; |
| 92 | IntrinsicParams intrinsics; |
| 93 | }; |
| 94 | |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 95 | // Find the distance from a lower target point to the 'vertical' line it should |
| 96 | // be on. |
| 97 | struct LineCostFunctor { |
| 98 | LineCostFunctor(Vector<2> result, Segment<2> template_seg, |
| 99 | IntrinsicParams intrinsics) |
| 100 | : result(result), template_seg(template_seg), intrinsics(intrinsics) {} |
| 101 | |
Alex Perry | 3d0abf2 | 2019-04-06 19:52:24 -0700 | [diff] [blame] | 102 | 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 Chatow | bf0609c | 2021-07-31 16:13:27 -0700 | [diff] [blame] | 112 | T denom = (p2 - p1).norm(); |
Alex Perry | 3d0abf2 | 2019-04-06 19:52:24 -0700 | [diff] [blame] | 113 | residual[0] = ceres::abs(dy * result.x() - dx * result.y() + |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 114 | 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 Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 124 | // Find the distance that the bottom point is outside the target and penalize |
| 125 | // that linearly. |
| 126 | class 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 Perry | 3d0abf2 | 2019-04-06 19:52:24 -0700 | [diff] [blame] | 134 | 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 Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 141 | |
| 142 | // Construct a vector pointed perpendicular to the line. This vector is |
| 143 | // pointed down out the bottom of the target. |
Alex Perry | 3d0abf2 | 2019-04-06 19:52:24 -0700 | [diff] [blame] | 144 | ::Eigen::Matrix<T, 2, 1> down_axis; |
| 145 | down_axis << -(p1.y() - p2.y()), p1.x() - p2.x(); |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 146 | down_axis.normalize(); |
| 147 | |
| 148 | // Positive means out. |
Tyler Chatow | bf0609c | 2021-07-31 16:13:27 -0700 | [diff] [blame] | 149 | const T component = down_axis.transpose() * (bottom_point_ - p1); |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 150 | |
Alex Perry | 3d0abf2 | 2019-04-06 19:52:24 -0700 | [diff] [blame] | 151 | if (component > T(0)) { |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 152 | residual[0] = component * 1.0; |
| 153 | } else { |
Alex Perry | 3d0abf2 | 2019-04-06 19:52:24 -0700 | [diff] [blame] | 154 | residual[0] = T(0); |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 155 | } |
| 156 | return true; |
| 157 | } |
| 158 | |
| 159 | private: |
| 160 | ::Eigen::Vector2d bottom_point_; |
| 161 | Segment<2> template_seg_; |
| 162 | |
| 163 | IntrinsicParams intrinsics_; |
| 164 | }; |
| 165 | |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 166 | IntermediateResult TargetFinder::ProcessTargetToResult(const Target &target, |
| 167 | bool verbose) { |
| 168 | // Memory for the ceres solver. |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 169 | double params_8point[ExtrinsicParams::kNumParams]; |
| 170 | default_extrinsics_.set(¶ms_8point[0]); |
| 171 | double params_4point[ExtrinsicParams::kNumParams]; |
| 172 | default_extrinsics_.set(¶ms_4point[0]); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 173 | |
Brian Silverman | 6323677 | 2019-03-23 22:02:44 -0700 | [diff] [blame] | 174 | Problem::Options problem_options; |
| 175 | problem_options.context = ceres_context_.get(); |
| 176 | Problem problem_8point(problem_options); |
| 177 | Problem problem_4point(problem_options); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 178 | |
Austin Schuh | 2894e90 | 2019-03-03 21:12:46 -0800 | [diff] [blame] | 179 | ::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 Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 182 | |
| 183 | for (size_t i = 0; i < 8; ++i) { |
Austin Schuh | 2894e90 | 2019-03-03 21:12:46 -0800 | [diff] [blame] | 184 | aos::vision::Vector<2> a = template_value[i]; |
| 185 | aos::vision::Vector<2> b = target_value[i]; |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 186 | |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 187 | if (i % 2 == 1) { |
Tyler Chatow | bf0609c | 2021-07-31 16:13:27 -0700 | [diff] [blame] | 188 | aos::vision::Vector<2> a2 = template_value[i - 1]; |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 189 | aos::vision::Segment<2> line = Segment<2>(a, a2); |
| 190 | |
| 191 | problem_4point.AddResidualBlock( |
Alex Perry | 3d0abf2 | 2019-04-06 19:52:24 -0700 | [diff] [blame] | 192 | new ceres::AutoDiffCostFunction<LineCostFunctor, 1, 4>( |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 193 | new LineCostFunctor(b, line, intrinsics_)), |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 194 | NULL, ¶ms_4point[0]); |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 195 | } else { |
| 196 | problem_4point.AddResidualBlock( |
Alex Perry | 3d0abf2 | 2019-04-06 19:52:24 -0700 | [diff] [blame] | 197 | new ceres::AutoDiffCostFunction<PointCostFunctor, 2, 4>( |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 198 | new PointCostFunctor(b, a, intrinsics_)), |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 199 | NULL, ¶ms_4point[0]); |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 200 | } |
| 201 | |
| 202 | problem_8point.AddResidualBlock( |
Alex Perry | 3d0abf2 | 2019-04-06 19:52:24 -0700 | [diff] [blame] | 203 | new ceres::AutoDiffCostFunction<PointCostFunctor, 2, 4>( |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 204 | new PointCostFunctor(b, a, intrinsics_)), |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 205 | NULL, ¶ms_8point[0]); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 206 | } |
| 207 | |
Austin Schuh | bb2ac92 | 2019-03-11 01:09:57 -0700 | [diff] [blame] | 208 | Solver::Options options; |
| 209 | options.minimizer_progress_to_stdout = false; |
| 210 | Solver::Summary summary_8point; |
| 211 | Solve(options, &problem_8point, &summary_8point); |
| 212 | |
Tyler Chatow | bf0609c | 2021-07-31 16:13:27 -0700 | [diff] [blame] | 213 | // So, let's sneak up on it. Start by warm-starting it with where we got on |
| 214 | // the 8 point solution. |
Austin Schuh | bb2ac92 | 2019-03-11 01:09:57 -0700 | [diff] [blame] | 215 | ExtrinsicParams::get(¶ms_8point[0]).set(¶ms_4point[0]); |
| 216 | // Then solve without the bottom constraint. |
| 217 | Solver::Summary summary_4point1; |
| 218 | Solve(options, &problem_4point, &summary_4point1); |
| 219 | |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 220 | // Now, add a large cost for the bottom point being below the bottom line. |
| 221 | problem_4point.AddResidualBlock( |
Alex Perry | 3d0abf2 | 2019-04-06 19:52:24 -0700 | [diff] [blame] | 222 | new ceres::AutoDiffCostFunction<BottomPointCostFunctor, 1, 4>( |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 223 | new BottomPointCostFunctor(target.left.bottom_point, |
| 224 | Segment<2>(target_template_.left.outside, |
| 225 | target_template_.left.bottom), |
| 226 | intrinsics_)), |
| 227 | NULL, ¶ms_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 Perry | 3d0abf2 | 2019-04-06 19:52:24 -0700 | [diff] [blame] | 231 | new ceres::AutoDiffCostFunction<BottomPointCostFunctor, 1, 4>( |
Austin Schuh | e6cfbe3 | 2019-03-10 18:05:57 -0700 | [diff] [blame] | 232 | new BottomPointCostFunctor(target.right.bottom_point, |
| 233 | Segment<2>(target_template_.right.bottom, |
| 234 | target_template_.right.outside), |
| 235 | intrinsics_)), |
| 236 | NULL, ¶ms_4point[0]); |
| 237 | |
Austin Schuh | bb2ac92 | 2019-03-11 01:09:57 -0700 | [diff] [blame] | 238 | // And then re-solve. |
| 239 | Solver::Summary summary_4point2; |
| 240 | Solve(options, &problem_4point, &summary_4point2); |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 241 | |
| 242 | IntermediateResult IR; |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 243 | IR.extrinsics = ExtrinsicParams::get(¶ms_8point[0]); |
| 244 | IR.solver_error = summary_8point.final_cost; |
| 245 | IR.backup_extrinsics = ExtrinsicParams::get(¶ms_4point[0]); |
Austin Schuh | bb2ac92 | 2019-03-11 01:09:57 -0700 | [diff] [blame] | 246 | IR.backup_solver_error = summary_4point2.final_cost; |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 247 | |
Alex Perry | b6f334d | 2019-03-23 13:10:45 -0700 | [diff] [blame] | 248 | // 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 Schuh | 4563988 | 2019-03-24 19:20:42 -0700 | [diff] [blame] | 251 | 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 Perry | 5b1e8e3 | 2019-04-07 13:25:31 -0700 | [diff] [blame] | 255 | IR.target_width = target.width(); |
Austin Schuh | 4563988 | 2019-03-24 19:20:42 -0700 | [diff] [blame] | 256 | |
| 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 Perry | b6f334d | 2019-03-23 13:10:45 -0700 | [diff] [blame] | 313 | |
Parker Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 314 | if (verbose) { |
Alex Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 315 | 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 Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 320 | 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 Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 324 | std::cout << "4 points:\n"; |
Austin Schuh | bb2ac92 | 2019-03-11 01:09:57 -0700 | [diff] [blame] | 325 | 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 Perry | bac3d3f | 2019-03-10 14:26:51 -0700 | [diff] [blame] | 330 | 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 Schuh | 4563988 | 2019-03-24 19:20:42 -0700 | [diff] [blame] | 334 | |
Austin Schuh | 4563988 | 2019-03-24 19:20:42 -0700 | [diff] [blame] | 335 | 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 Schuh | 2a1447c | 2019-02-17 00:25:29 -0800 | [diff] [blame] | 348 | } |
| 349 | return IR; |
| 350 | } |
| 351 | |
| 352 | } // namespace vision |
| 353 | } // namespace y2019 |