milind-u | 9219598 | 2022-01-22 20:29:31 -0800 | [diff] [blame] | 1 | #include "y2022/vision/target_estimator.h" |
| 2 | |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 3 | #include "absl/strings/str_format.h" |
| 4 | #include "aos/time/time.h" |
| 5 | #include "ceres/ceres.h" |
| 6 | #include "frc971/control_loops/quaternion_utils.h" |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 7 | #include "geometry.h" |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 8 | #include "opencv2/core/core.hpp" |
| 9 | #include "opencv2/core/eigen.hpp" |
| 10 | #include "opencv2/features2d.hpp" |
| 11 | #include "opencv2/highgui/highgui.hpp" |
| 12 | #include "opencv2/imgproc.hpp" |
milind-u | cafdd5d | 2022-03-01 19:58:57 -0800 | [diff] [blame] | 13 | #include "y2022/constants.h" |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 14 | |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 15 | DEFINE_bool(freeze_roll, false, "If true, don't solve for roll"); |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 16 | DEFINE_bool(freeze_pitch, false, "If true, don't solve for pitch"); |
| 17 | DEFINE_bool(freeze_yaw, false, "If true, don't solve for yaw"); |
| 18 | DEFINE_bool(freeze_camera_height, true, |
| 19 | "If true, don't solve for camera height"); |
| 20 | DEFINE_bool(freeze_angle_to_camera, true, |
| 21 | "If true, don't solve for polar angle to camera"); |
| 22 | |
| 23 | DEFINE_uint64(max_num_iterations, 200, |
| 24 | "Maximum number of iterations for the ceres solver"); |
| 25 | DEFINE_bool(solver_output, false, |
| 26 | "If true, log the solver progress and results"); |
| 27 | |
milind-u | 9219598 | 2022-01-22 20:29:31 -0800 | [diff] [blame] | 28 | namespace y2022::vision { |
| 29 | |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 30 | namespace { |
| 31 | |
| 32 | constexpr size_t kNumPiecesOfTape = 16; |
| 33 | // Width and height of a piece of reflective tape |
| 34 | constexpr double kTapePieceWidth = 0.13; |
| 35 | constexpr double kTapePieceHeight = 0.05; |
| 36 | // Height of the center of the tape (m) |
| 37 | constexpr double kTapeCenterHeight = 2.58 + (kTapePieceHeight / 2); |
| 38 | // Horizontal distance from tape to center of hub (m) |
| 39 | constexpr double kUpperHubRadius = 1.22 / 2; |
| 40 | |
| 41 | std::vector<cv::Point3d> ComputeTapePoints() { |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 42 | std::vector<cv::Point3d> tape_points; |
milind-u | 9219598 | 2022-01-22 20:29:31 -0800 | [diff] [blame] | 43 | |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 44 | constexpr size_t kNumVisiblePiecesOfTape = 5; |
| 45 | for (size_t i = 0; i < kNumVisiblePiecesOfTape; i++) { |
| 46 | // The center piece of tape is at 0 rad, so the angle indices are offset |
| 47 | // by the number of pieces of tape on each side of it |
| 48 | const double theta_index = |
| 49 | static_cast<double>(i) - ((kNumVisiblePiecesOfTape - 1) / 2); |
| 50 | // The polar angle is a multiple of the angle between tape centers |
| 51 | double theta = theta_index * ((2.0 * M_PI) / kNumPiecesOfTape); |
| 52 | tape_points.emplace_back(kUpperHubRadius * std::cos(theta), |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 53 | kUpperHubRadius * std::sin(theta), |
| 54 | kTapeCenterHeight); |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 55 | } |
milind-u | 9219598 | 2022-01-22 20:29:31 -0800 | [diff] [blame] | 56 | |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 57 | return tape_points; |
| 58 | } |
milind-u | 9219598 | 2022-01-22 20:29:31 -0800 | [diff] [blame] | 59 | |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 60 | std::array<cv::Point3d, 4> ComputeMiddleTapePiecePoints() { |
| 61 | std::array<cv::Point3d, 4> tape_piece_points; |
| 62 | |
| 63 | // Angle that each piece of tape occupies on the hub |
| 64 | constexpr double kTapePieceAngle = |
| 65 | (kTapePieceWidth / (2.0 * M_PI * kUpperHubRadius)) * (2.0 * M_PI); |
| 66 | |
| 67 | constexpr double kThetaTapeLeft = -kTapePieceAngle / 2.0; |
| 68 | constexpr double kThetaTapeRight = kTapePieceAngle / 2.0; |
| 69 | |
| 70 | constexpr double kTapeTopHeight = |
| 71 | kTapeCenterHeight + (kTapePieceHeight / 2.0); |
| 72 | constexpr double kTapeBottomHeight = |
| 73 | kTapeCenterHeight - (kTapePieceHeight / 2.0); |
| 74 | |
| 75 | tape_piece_points[0] = {kUpperHubRadius * std::cos(kThetaTapeLeft), |
| 76 | kUpperHubRadius * std::sin(kThetaTapeLeft), |
| 77 | kTapeTopHeight}; |
| 78 | tape_piece_points[1] = {kUpperHubRadius * std::cos(kThetaTapeRight), |
| 79 | kUpperHubRadius * std::sin(kThetaTapeRight), |
| 80 | kTapeTopHeight}; |
| 81 | |
| 82 | tape_piece_points[2] = {kUpperHubRadius * std::cos(kThetaTapeRight), |
| 83 | kUpperHubRadius * std::sin(kThetaTapeRight), |
| 84 | kTapeBottomHeight}; |
| 85 | tape_piece_points[3] = {kUpperHubRadius * std::cos(kThetaTapeLeft), |
| 86 | kUpperHubRadius * std::sin(kThetaTapeLeft), |
| 87 | kTapeBottomHeight}; |
| 88 | |
| 89 | return tape_piece_points; |
| 90 | } |
| 91 | |
| 92 | } // namespace |
| 93 | |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 94 | const std::vector<cv::Point3d> TargetEstimator::kTapePoints = |
| 95 | ComputeTapePoints(); |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 96 | const std::array<cv::Point3d, 4> TargetEstimator::kMiddleTapePiecePoints = |
| 97 | ComputeMiddleTapePiecePoints(); |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 98 | |
| 99 | TargetEstimator::TargetEstimator(cv::Mat intrinsics, cv::Mat extrinsics) |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 100 | : blob_stats_(), |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 101 | image_(std::nullopt), |
| 102 | roll_(0.0), |
| 103 | pitch_(0.0), |
| 104 | yaw_(M_PI), |
| 105 | distance_(3.0), |
| 106 | angle_to_camera_(0.0), |
milind-u | cafdd5d | 2022-03-01 19:58:57 -0800 | [diff] [blame] | 107 | // Seed camera height |
| 108 | camera_height_(extrinsics.at<double>(2, 3) + |
| 109 | constants::Values::kImuHeight()) { |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 110 | cv::cv2eigen(intrinsics, intrinsics_); |
| 111 | cv::cv2eigen(extrinsics, extrinsics_); |
| 112 | } |
| 113 | |
| 114 | namespace { |
| 115 | void SetBoundsOrFreeze(double *param, bool freeze, double min, double max, |
| 116 | ceres::Problem *problem) { |
| 117 | if (freeze) { |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 118 | problem->SetParameterBlockConstant(param); |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 119 | } else { |
| 120 | problem->SetParameterLowerBound(param, 0, min); |
| 121 | problem->SetParameterUpperBound(param, 0, max); |
| 122 | } |
| 123 | } |
milind-u | cafdd5d | 2022-03-01 19:58:57 -0800 | [diff] [blame] | 124 | |
| 125 | // With X, Y, Z being hub axes and x, y, z being camera axes, |
| 126 | // x = -Y, y = -Z, z = X |
| 127 | const Eigen::Matrix3d kHubToCameraAxes = |
| 128 | (Eigen::Matrix3d() << 0.0, -1.0, 0.0, 0.0, 0.0, -1.0, 1.0, 0.0, 0.0) |
| 129 | .finished(); |
| 130 | |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 131 | } // namespace |
| 132 | |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 133 | void TargetEstimator::Solve( |
| 134 | const std::vector<BlobDetector::BlobStats> &blob_stats, |
| 135 | std::optional<cv::Mat> image) { |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 136 | auto start = aos::monotonic_clock::now(); |
| 137 | |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 138 | blob_stats_ = blob_stats; |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 139 | image_ = image; |
| 140 | |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 141 | // Do nothing if no blobs were detected |
| 142 | if (blob_stats_.size() == 0) { |
| 143 | confidence_ = 0.0; |
| 144 | return; |
| 145 | } |
| 146 | |
| 147 | CHECK_GE(blob_stats_.size(), 3) << "Expected at least 3 blobs"; |
| 148 | |
| 149 | const auto circle = |
| 150 | Circle::Fit({blob_stats_[0].centroid, blob_stats_[1].centroid, |
| 151 | blob_stats_[2].centroid}); |
| 152 | CHECK(circle.has_value()); |
| 153 | |
| 154 | // Find the middle blob, which is the one with the angle closest to the |
| 155 | // average |
| 156 | double theta_avg = 0.0; |
| 157 | for (const auto &stats : blob_stats_) { |
| 158 | theta_avg += circle->AngleOf(stats.centroid); |
| 159 | } |
| 160 | theta_avg /= blob_stats_.size(); |
| 161 | |
| 162 | double min_diff = std::numeric_limits<double>::infinity(); |
| 163 | for (auto it = blob_stats_.begin(); it < blob_stats_.end(); it++) { |
| 164 | const double diff = std::abs(circle->AngleOf(it->centroid) - theta_avg); |
| 165 | if (diff < min_diff) { |
| 166 | min_diff = diff; |
| 167 | middle_blob_index_ = it - blob_stats_.begin(); |
| 168 | } |
| 169 | } |
| 170 | |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 171 | ceres::Problem problem; |
| 172 | |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 173 | // x and y differences between projected centroids and blob centroids, as well |
| 174 | // as width and height differences between middle projected piece and the |
| 175 | // detected blob |
| 176 | const size_t num_residuals = (blob_stats_.size() * 2) + 2; |
| 177 | |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 178 | // Set up the only cost function (also known as residual). This uses |
| 179 | // auto-differentiation to obtain the derivative (jacobian). |
| 180 | ceres::CostFunction *cost_function = |
| 181 | new ceres::AutoDiffCostFunction<TargetEstimator, ceres::DYNAMIC, 1, 1, 1, |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 182 | 1, 1, 1>(this, num_residuals, |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 183 | ceres::DO_NOT_TAKE_OWNERSHIP); |
| 184 | |
| 185 | // TODO(milind): add loss function when we get more noisy data |
| 186 | problem.AddResidualBlock(cost_function, nullptr, &roll_, &pitch_, &yaw_, |
| 187 | &distance_, &angle_to_camera_, &camera_height_); |
| 188 | |
milind-u | cafdd5d | 2022-03-01 19:58:57 -0800 | [diff] [blame] | 189 | // Compute the estimated rotation of the camera using the robot rotation. |
| 190 | const Eigen::Vector3d ypr_extrinsics = |
| 191 | (Eigen::Affine3d(extrinsics_).rotation() * kHubToCameraAxes) |
| 192 | .eulerAngles(2, 1, 0); |
| 193 | // TODO(milind): seed with localizer output as well |
| 194 | const double roll_seed = ypr_extrinsics.z(); |
| 195 | const double pitch_seed = ypr_extrinsics.y(); |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 196 | |
milind-u | cafdd5d | 2022-03-01 19:58:57 -0800 | [diff] [blame] | 197 | // Constrain the rotation to be around the localizer's, otherwise there can be |
| 198 | // multiple solutions. There shouldn't be too much roll or pitch |
| 199 | constexpr double kMaxRollDelta = 0.1; |
| 200 | SetBoundsOrFreeze(&roll_, FLAGS_freeze_roll, roll_seed - kMaxRollDelta, |
| 201 | roll_seed + kMaxRollDelta, &problem); |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 202 | |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 203 | constexpr double kMaxPitchDelta = 0.15; |
milind-u | cafdd5d | 2022-03-01 19:58:57 -0800 | [diff] [blame] | 204 | SetBoundsOrFreeze(&pitch_, FLAGS_freeze_pitch, pitch_seed - kMaxPitchDelta, |
| 205 | pitch_seed + kMaxPitchDelta, &problem); |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 206 | // Constrain the yaw to where the target would be visible |
| 207 | constexpr double kMaxYawDelta = M_PI / 4.0; |
| 208 | SetBoundsOrFreeze(&yaw_, FLAGS_freeze_yaw, M_PI - kMaxYawDelta, |
| 209 | M_PI + kMaxYawDelta, &problem); |
| 210 | |
| 211 | constexpr double kMaxHeightDelta = 0.1; |
| 212 | SetBoundsOrFreeze(&camera_height_, FLAGS_freeze_camera_height, |
| 213 | camera_height_ - kMaxHeightDelta, |
| 214 | camera_height_ + kMaxHeightDelta, &problem); |
| 215 | |
| 216 | // Distances shouldn't be too close to the target or too far |
| 217 | constexpr double kMinDistance = 1.0; |
| 218 | constexpr double kMaxDistance = 10.0; |
| 219 | SetBoundsOrFreeze(&distance_, false, kMinDistance, kMaxDistance, &problem); |
| 220 | |
| 221 | // Keep the angle between +/- half of the angle between piece of tape |
| 222 | constexpr double kMaxAngle = ((2.0 * M_PI) / kNumPiecesOfTape) / 2.0; |
| 223 | SetBoundsOrFreeze(&angle_to_camera_, FLAGS_freeze_angle_to_camera, -kMaxAngle, |
| 224 | kMaxAngle, &problem); |
| 225 | |
| 226 | ceres::Solver::Options options; |
| 227 | options.minimizer_progress_to_stdout = FLAGS_solver_output; |
| 228 | options.gradient_tolerance = 1e-12; |
| 229 | options.function_tolerance = 1e-16; |
| 230 | options.parameter_tolerance = 1e-12; |
| 231 | options.max_num_iterations = FLAGS_max_num_iterations; |
| 232 | ceres::Solver::Summary summary; |
| 233 | ceres::Solve(options, &problem, &summary); |
| 234 | |
| 235 | auto end = aos::monotonic_clock::now(); |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 236 | VLOG(1) << "Target estimation elapsed time: " |
| 237 | << std::chrono::duration<double, std::milli>(end - start).count() |
| 238 | << " ms"; |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 239 | |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 240 | // For computing the confidence, find the standard deviation in pixels |
| 241 | std::vector<double> residual(num_residuals); |
| 242 | (*this)(&roll_, &pitch_, &yaw_, &distance_, &angle_to_camera_, |
| 243 | &camera_height_, residual.data()); |
| 244 | double std_dev = 0.0; |
| 245 | for (auto it = residual.begin(); it < residual.end() - 2; it++) { |
| 246 | std_dev += std::pow(*it, 2); |
Milind Upadhyay | 14279de | 2022-02-26 16:07:53 -0800 | [diff] [blame] | 247 | } |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 248 | std_dev /= num_residuals - 2; |
| 249 | std_dev = std::sqrt(std_dev); |
| 250 | |
| 251 | // Use a sigmoid to convert the deviation into a confidence for the |
| 252 | // localizer. Fit a sigmoid to the points of (0, 1) and two other |
| 253 | // reasonable deviation-confidence combinations using |
| 254 | // https://www.desmos.com/calculator/try0pgx1qw |
| 255 | constexpr double kSigmoidCapacity = 1.045; |
| 256 | // Stretch the sigmoid out correctly. |
| 257 | // Currently, good estimates have deviations of around 2 pixels. |
| 258 | constexpr double kSigmoidScalar = 0.04452; |
| 259 | constexpr double kSigmoidGrowthRate = -0.4021; |
| 260 | confidence_ = |
| 261 | kSigmoidCapacity / |
| 262 | (1.0 + kSigmoidScalar * std::exp(-kSigmoidGrowthRate * std_dev)); |
Milind Upadhyay | 14279de | 2022-02-26 16:07:53 -0800 | [diff] [blame] | 263 | |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 264 | if (FLAGS_solver_output) { |
| 265 | LOG(INFO) << summary.FullReport(); |
| 266 | |
| 267 | LOG(INFO) << "roll: " << roll_; |
| 268 | LOG(INFO) << "pitch: " << pitch_; |
| 269 | LOG(INFO) << "yaw: " << yaw_; |
| 270 | LOG(INFO) << "angle to target (based on yaw): " << angle_to_target(); |
| 271 | LOG(INFO) << "angle to camera (polar): " << angle_to_camera_; |
| 272 | LOG(INFO) << "distance (polar): " << distance_; |
| 273 | LOG(INFO) << "camera height: " << camera_height_; |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 274 | LOG(INFO) << "standard deviation (px): " << std_dev; |
Milind Upadhyay | 14279de | 2022-02-26 16:07:53 -0800 | [diff] [blame] | 275 | LOG(INFO) << "confidence: " << confidence_; |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 276 | } |
| 277 | } |
| 278 | |
| 279 | namespace { |
| 280 | // Hacks to extract a double from a scalar, which is either a ceres jet or a |
| 281 | // double. Only used for debugging and displaying. |
| 282 | template <typename S> |
| 283 | double ScalarToDouble(S s) { |
| 284 | const double *ptr = reinterpret_cast<double *>(&s); |
| 285 | return *ptr; |
| 286 | } |
| 287 | |
| 288 | template <typename S> |
| 289 | cv::Point2d ScalarPointToDouble(cv::Point_<S> p) { |
| 290 | return cv::Point2d(ScalarToDouble(p.x), ScalarToDouble(p.y)); |
| 291 | } |
| 292 | } // namespace |
| 293 | |
| 294 | template <typename S> |
| 295 | bool TargetEstimator::operator()(const S *const roll, const S *const pitch, |
| 296 | const S *const yaw, const S *const distance, |
| 297 | const S *const theta, |
| 298 | const S *const camera_height, |
| 299 | S *residual) const { |
| 300 | using Vector3s = Eigen::Matrix<S, 3, 1>; |
| 301 | using Affine3s = Eigen::Transform<S, 3, Eigen::Affine>; |
| 302 | |
| 303 | Eigen::AngleAxis<S> roll_angle(*roll, Vector3s::UnitX()); |
| 304 | Eigen::AngleAxis<S> pitch_angle(*pitch, Vector3s::UnitY()); |
| 305 | Eigen::AngleAxis<S> yaw_angle(*yaw, Vector3s::UnitZ()); |
| 306 | // Construct the rotation and translation of the camera in the hub's frame |
| 307 | Eigen::Quaternion<S> R_camera_hub = yaw_angle * pitch_angle * roll_angle; |
| 308 | Vector3s T_camera_hub(*distance * ceres::cos(*theta), |
| 309 | *distance * ceres::sin(*theta), *camera_height); |
| 310 | |
| 311 | Affine3s H_camera_hub = Eigen::Translation<S, 3>(T_camera_hub) * R_camera_hub; |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 312 | Affine3s H_hub_camera = H_camera_hub.inverse(); |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 313 | |
| 314 | std::vector<cv::Point_<S>> tape_points_proj; |
| 315 | for (cv::Point3d tape_point_hub : kTapePoints) { |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 316 | tape_points_proj.emplace_back(ProjectToImage(tape_point_hub, H_hub_camera)); |
| 317 | VLOG(2) << "Projected tape point: " |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 318 | << ScalarPointToDouble( |
| 319 | tape_points_proj[tape_points_proj.size() - 1]); |
| 320 | } |
| 321 | |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 322 | // Find the rectangle bounding the projected piece of tape |
| 323 | std::array<cv::Point_<S>, 4> middle_tape_piece_points_proj; |
| 324 | for (auto tape_piece_it = kMiddleTapePiecePoints.begin(); |
| 325 | tape_piece_it < kMiddleTapePiecePoints.end(); tape_piece_it++) { |
| 326 | middle_tape_piece_points_proj[tape_piece_it - |
| 327 | kMiddleTapePiecePoints.begin()] = |
| 328 | ProjectToImage(*tape_piece_it, H_hub_camera); |
| 329 | } |
| 330 | |
| 331 | for (size_t i = 0; i < blob_stats_.size(); i++) { |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 332 | const auto distance = DistanceFromTape(i, tape_points_proj); |
| 333 | // Set the residual to the (x, y) distance of the centroid from the |
| 334 | // nearest projected piece of tape |
| 335 | residual[i * 2] = distance.x; |
| 336 | residual[(i * 2) + 1] = distance.y; |
| 337 | } |
| 338 | |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 339 | // Penalize based on the difference between the size of the projected piece of |
| 340 | // tape and that of the detected blobs. Use the squared size to avoid taking a |
| 341 | // norm, which ceres can't handle well |
| 342 | const S middle_tape_piece_width_squared = |
| 343 | ceres::pow(middle_tape_piece_points_proj[2].x - |
| 344 | middle_tape_piece_points_proj[3].x, |
| 345 | 2) + |
| 346 | ceres::pow(middle_tape_piece_points_proj[2].y - |
| 347 | middle_tape_piece_points_proj[3].y, |
| 348 | 2); |
| 349 | const S middle_tape_piece_height_squared = |
| 350 | ceres::pow(middle_tape_piece_points_proj[1].x - |
| 351 | middle_tape_piece_points_proj[2].x, |
| 352 | 2) + |
| 353 | ceres::pow(middle_tape_piece_points_proj[1].y - |
| 354 | middle_tape_piece_points_proj[2].y, |
| 355 | 2); |
| 356 | |
| 357 | residual[blob_stats_.size() * 2] = |
| 358 | middle_tape_piece_width_squared - |
| 359 | std::pow(blob_stats_[middle_blob_index_].size.width, 2); |
| 360 | residual[(blob_stats_.size() * 2) + 1] = |
| 361 | middle_tape_piece_height_squared - |
| 362 | std::pow(blob_stats_[middle_blob_index_].size.height, 2); |
| 363 | |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 364 | if (image_.has_value()) { |
| 365 | // Draw the current stage of the solving |
| 366 | cv::Mat image = image_->clone(); |
| 367 | for (size_t i = 0; i < tape_points_proj.size() - 1; i++) { |
| 368 | cv::line(image, ScalarPointToDouble(tape_points_proj[i]), |
| 369 | ScalarPointToDouble(tape_points_proj[i + 1]), |
| 370 | cv::Scalar(255, 255, 255)); |
| 371 | cv::circle(image, ScalarPointToDouble(tape_points_proj[i]), 2, |
| 372 | cv::Scalar(255, 20, 147), cv::FILLED); |
| 373 | cv::circle(image, ScalarPointToDouble(tape_points_proj[i + 1]), 2, |
| 374 | cv::Scalar(255, 20, 147), cv::FILLED); |
| 375 | } |
| 376 | cv::imshow("image", image); |
| 377 | cv::waitKey(10); |
| 378 | } |
| 379 | |
| 380 | return true; |
| 381 | } |
| 382 | |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 383 | template <typename S> |
| 384 | cv::Point_<S> TargetEstimator::ProjectToImage( |
| 385 | cv::Point3d tape_point_hub, |
| 386 | Eigen::Transform<S, 3, Eigen::Affine> &H_hub_camera) const { |
| 387 | using Vector3s = Eigen::Matrix<S, 3, 1>; |
| 388 | |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 389 | const Vector3s tape_point_hub_eigen = |
| 390 | Vector3s(S(tape_point_hub.x), S(tape_point_hub.y), S(tape_point_hub.z)); |
| 391 | // Project the 3d tape point onto the image using the transformation and |
| 392 | // intrinsics |
| 393 | const Vector3s tape_point_proj = |
milind-u | cafdd5d | 2022-03-01 19:58:57 -0800 | [diff] [blame] | 394 | intrinsics_ * (kHubToCameraAxes * (H_hub_camera * tape_point_hub_eigen)); |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 395 | |
| 396 | // Normalize the projected point |
| 397 | return {tape_point_proj.x() / tape_point_proj.z(), |
| 398 | tape_point_proj.y() / tape_point_proj.z()}; |
| 399 | } |
| 400 | |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 401 | namespace { |
| 402 | template <typename S> |
| 403 | cv::Point_<S> Distance(cv::Point p, cv::Point_<S> q) { |
| 404 | return cv::Point_<S>(S(p.x) - q.x, S(p.y) - q.y); |
| 405 | } |
| 406 | |
| 407 | template <typename S> |
| 408 | bool Less(cv::Point_<S> distance_1, cv::Point_<S> distance_2) { |
| 409 | return (ceres::pow(distance_1.x, 2) + ceres::pow(distance_1.y, 2) < |
| 410 | ceres::pow(distance_2.x, 2) + ceres::pow(distance_2.y, 2)); |
| 411 | } |
| 412 | } // namespace |
| 413 | |
| 414 | template <typename S> |
| 415 | cv::Point_<S> TargetEstimator::DistanceFromTape( |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 416 | size_t blob_index, const std::vector<cv::Point_<S>> &tape_points) const { |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 417 | auto distance = cv::Point_<S>(std::numeric_limits<S>::infinity(), |
| 418 | std::numeric_limits<S>::infinity()); |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 419 | if (blob_index == middle_blob_index_) { |
| 420 | // Fix the middle blob so the solver can't go too far off |
| 421 | distance = Distance(blob_stats_[middle_blob_index_].centroid, |
| 422 | tape_points[tape_points.size() / 2]); |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 423 | } else { |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 424 | // Give the other blob_stats some freedom in case some are split into pieces |
| 425 | for (auto it = tape_points.begin(); it < tape_points.end(); it++) { |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 426 | const auto current_distance = |
Milind Upadhyay | 8f38ad8 | 2022-03-03 10:06:18 -0800 | [diff] [blame] | 427 | Distance(blob_stats_[blob_index].centroid, *it); |
| 428 | if ((it != tape_points.begin() + (tape_points.size() / 2)) && |
| 429 | Less(current_distance, distance)) { |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 430 | distance = current_distance; |
| 431 | } |
| 432 | } |
| 433 | } |
| 434 | |
| 435 | return distance; |
| 436 | } |
| 437 | |
| 438 | namespace { |
| 439 | void DrawEstimateValues(double distance, double angle_to_target, |
| 440 | double angle_to_camera, double roll, double pitch, |
Milind Upadhyay | 14279de | 2022-02-26 16:07:53 -0800 | [diff] [blame] | 441 | double yaw, double confidence, cv::Mat view_image) { |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 442 | constexpr int kTextX = 10; |
Milind Upadhyay | 2da80bb | 2022-03-12 22:54:35 -0800 | [diff] [blame^] | 443 | int text_y = 0; |
| 444 | constexpr int kTextSpacing = 25; |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 445 | |
| 446 | const auto kTextColor = cv::Scalar(0, 255, 255); |
Milind Upadhyay | 2da80bb | 2022-03-12 22:54:35 -0800 | [diff] [blame^] | 447 | constexpr double kFontScale = 0.6; |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 448 | |
| 449 | cv::putText(view_image, absl::StrFormat("Distance: %.3f", distance), |
| 450 | cv::Point(kTextX, text_y += kTextSpacing), |
| 451 | cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2); |
| 452 | cv::putText(view_image, |
| 453 | absl::StrFormat("Angle to target: %.3f", angle_to_target), |
| 454 | cv::Point(kTextX, text_y += kTextSpacing), |
| 455 | cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2); |
| 456 | cv::putText(view_image, |
| 457 | absl::StrFormat("Angle to camera: %.3f", angle_to_camera), |
| 458 | cv::Point(kTextX, text_y += kTextSpacing), |
| 459 | cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2); |
| 460 | |
| 461 | cv::putText( |
| 462 | view_image, |
| 463 | absl::StrFormat("Roll: %.3f, pitch: %.3f, yaw: %.3f", roll, pitch, yaw), |
| 464 | cv::Point(kTextX, text_y += kTextSpacing), cv::FONT_HERSHEY_DUPLEX, |
| 465 | kFontScale, kTextColor, 2); |
Milind Upadhyay | 14279de | 2022-02-26 16:07:53 -0800 | [diff] [blame] | 466 | |
| 467 | cv::putText(view_image, absl::StrFormat("Confidence: %.3f", confidence), |
| 468 | cv::Point(kTextX, text_y += kTextSpacing), |
| 469 | cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2); |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 470 | } |
| 471 | } // namespace |
| 472 | |
| 473 | void TargetEstimator::DrawEstimate(const TargetEstimate &target_estimate, |
| 474 | cv::Mat view_image) { |
| 475 | DrawEstimateValues(target_estimate.distance(), |
| 476 | target_estimate.angle_to_target(), |
| 477 | target_estimate.angle_to_camera(), |
| 478 | target_estimate.rotation_camera_hub()->roll(), |
| 479 | target_estimate.rotation_camera_hub()->pitch(), |
Milind Upadhyay | 14279de | 2022-02-26 16:07:53 -0800 | [diff] [blame] | 480 | target_estimate.rotation_camera_hub()->yaw(), |
| 481 | target_estimate.confidence(), view_image); |
Milind Upadhyay | f61e148 | 2022-02-11 20:42:55 -0800 | [diff] [blame] | 482 | } |
| 483 | |
| 484 | void TargetEstimator::DrawEstimate(cv::Mat view_image) const { |
| 485 | DrawEstimateValues(distance_, angle_to_target(), angle_to_camera_, roll_, |
Milind Upadhyay | 14279de | 2022-02-26 16:07:53 -0800 | [diff] [blame] | 486 | pitch_, yaw_, confidence_, view_image); |
milind-u | 9219598 | 2022-01-22 20:29:31 -0800 | [diff] [blame] | 487 | } |
| 488 | |
| 489 | } // namespace y2022::vision |