blob: aa340061541bc04b60e7244c9b9ba652ac459c4c [file] [log] [blame]
Milind Upadhyay7c205222022-11-16 18:20:58 -08001#ifndef FRC971_VISION_TARGET_MAPPER_H_
2#define FRC971_VISION_TARGET_MAPPER_H_
3
4#include <unordered_map>
5
Austin Schuh99f7c6a2024-06-25 22:07:44 -07006#include "absl/strings/str_format.h"
Milind Upadhyayc5beba12022-12-17 17:41:20 -08007#include "ceres/ceres.h"
Philipp Schrader790cb542023-07-05 21:06:52 -07008
9#include "aos/events/simulated_event_loop.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -080010#include "frc971/vision/ceres/types.h"
Milind Upadhyaycd677a32022-12-04 13:06:43 -080011#include "frc971/vision/target_map_generated.h"
Jim Ostrowski6d242d52024-04-03 20:39:03 -070012#include "frc971/vision/vision_util_lib.h"
milind-u8f4e43e2023-04-09 17:11:19 -070013#include "frc971/vision/visualize_robot.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -080014
Jim Ostrowski6d242d52024-04-03 20:39:03 -070015ABSL_DECLARE_FLAG(double, outlier_std_devs);
16
Milind Upadhyay7c205222022-11-16 18:20:58 -080017namespace frc971::vision {
18
19// Estimates positions of vision targets (ex. April Tags) using
20// target detections relative to a robot (which were computed using robot
21// positions at the time of those detections). Solves SLAM problem to estimate
22// target locations using deltas between consecutive target detections.
23class TargetMapper {
24 public:
25 using TargetId = int;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080026 using ConfidenceMatrix = Eigen::Matrix<double, 6, 6>;
Milind Upadhyay7c205222022-11-16 18:20:58 -080027
28 struct TargetPose {
29 TargetId id;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080030 ceres::examples::Pose3d pose;
Milind Upadhyay7c205222022-11-16 18:20:58 -080031 };
32
Milind Upadhyaycd677a32022-12-04 13:06:43 -080033 // target_poses_path is the path to a TargetMap json with initial guesses for
34 // the actual locations of the targets on the field.
Milind Upadhyay7c205222022-11-16 18:20:58 -080035 // target_constraints are the deltas between consecutive target detections,
36 // and are usually prepared by the DataAdapter class below.
Milind Upadhyaycd677a32022-12-04 13:06:43 -080037 TargetMapper(std::string_view target_poses_path,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080038 const ceres::examples::VectorOfConstraints &target_constraints);
Milind Upadhyaycd677a32022-12-04 13:06:43 -080039 // Alternate constructor for tests.
40 // Takes in the actual intial guesses instead of a file containing them
Milind Upadhyayc5beba12022-12-17 17:41:20 -080041 TargetMapper(const ceres::examples::MapOfPoses &target_poses,
42 const ceres::examples::VectorOfConstraints &target_constraints);
Milind Upadhyay7c205222022-11-16 18:20:58 -080043
Milind Upadhyay05652cb2022-12-07 20:51:51 -080044 // Solves for the target map. If output_dir is set, the map will be saved to
45 // output_dir/field_name.json
46 void Solve(std::string_view field_name,
47 std::optional<std::string_view> output_dir = std::nullopt);
Milind Upadhyaycd677a32022-12-04 13:06:43 -080048
49 // Prints target poses into a TargetMap flatbuffer json
Milind Upadhyay05652cb2022-12-07 20:51:51 -080050 std::string MapToJson(std::string_view field_name) const;
Milind Upadhyay7c205222022-11-16 18:20:58 -080051
Jim Ostrowski6d242d52024-04-03 20:39:03 -070052 // Builds a TargetPoseFbs from a TargetPose
53 static flatbuffers::Offset<TargetPoseFbs> TargetPoseToFbs(
54 const TargetMapper::TargetPose &target_pose,
55 flatbuffers::FlatBufferBuilder *fbb);
56
57 // Converts a TargetPoseFbs to a TargetPose
58 static TargetMapper::TargetPose TargetPoseFromFbs(
59 const TargetPoseFbs &target_pose_fbs);
60
Milind Upadhyay7c205222022-11-16 18:20:58 -080061 static std::optional<TargetPose> GetTargetPoseById(
62 std::vector<TargetPose> target_poses, TargetId target_id);
63
Jim Ostrowski49be8232023-03-23 01:00:14 -070064 // Version that gets based on internal target_poses
milind-u2ab4db12023-03-25 21:59:23 -070065 std::optional<TargetPose> GetTargetPoseById(TargetId target_id) const;
Jim Ostrowski49be8232023-03-23 01:00:14 -070066
Milind Upadhyayc5beba12022-12-17 17:41:20 -080067 ceres::examples::MapOfPoses target_poses() { return target_poses_; }
Milind Upadhyay7c205222022-11-16 18:20:58 -080068
milind-u8f4e43e2023-04-09 17:11:19 -070069 // Cost function for the secondary solver finding out where the whole map fits
70 // in the world
71 template <typename S>
72 bool operator()(const S *const translation, const S *const rotation,
73 S *residual) const;
74
milind-u401de982023-04-14 17:32:03 -070075 void DumpConstraints(std::string_view path) const;
76 void DumpStats(std::string_view path) const;
Jim Ostrowskif41b0942024-03-24 18:05:02 -070077 void PrintDiffs() const;
milind-u401de982023-04-14 17:32:03 -070078
Milind Upadhyay7c205222022-11-16 18:20:58 -080079 private:
milind-u401de982023-04-14 17:32:03 -070080 // Error in an estimated pose
81 struct PoseError {
82 double angle;
83 double distance;
84 };
85
86 // Stores info on how much all the constraints differ from our solved target
87 // map
88 struct Stats {
89 // Average error for translation and rotation
90 PoseError avg_err;
91 // Standard deviation for translation and rotation error
92 PoseError std_dev;
93 // Maximum error for translation and rotation
94 PoseError max_err;
95 };
96
97 // Compute the error of a single constraint
98 PoseError ComputeError(const ceres::examples::Constraint3d &constraint) const;
99 // Compute cumulative stats for all constraints
100 Stats ComputeStats() const;
101 // Removes constraints with very large errors
102 void RemoveOutlierConstraints();
103
milind-u526d5672023-04-17 20:09:10 -0700104 void CountConstraints();
105
Milind Upadhyay7c205222022-11-16 18:20:58 -0800106 // Constructs the nonlinear least squares optimization problem from the
107 // pose graph constraints.
milind-u8f4e43e2023-04-09 17:11:19 -0700108 void BuildTargetPoseOptimizationProblem(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800109 const ceres::examples::VectorOfConstraints &constraints,
110 ceres::examples::MapOfPoses *poses, ceres::Problem *problem);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800111
milind-u8f4e43e2023-04-09 17:11:19 -0700112 // Constructs the nonlinear least squares optimization problem for the solved
113 // -> actual pose solver.
milind-u401de982023-04-14 17:32:03 -0700114 std::unique_ptr<ceres::CostFunction> BuildMapFittingOptimizationProblem(
115 ceres::Problem *problem);
milind-u8f4e43e2023-04-09 17:11:19 -0700116
Jim Ostrowski4527dd72024-03-07 00:20:15 -0800117 // Create and display a visualization of the graph connectivity of the
118 // constraints
119 void DisplayConstraintGraph();
120
Jim Ostrowskiefc3bde2024-03-23 16:34:06 -0700121 // Create and display a visualization of the map solution (vs. the input map)
122 void DisplaySolvedVsInitial();
123
Milind Upadhyay7c205222022-11-16 18:20:58 -0800124 // Returns true if the solve was successful.
125 bool SolveOptimizationProblem(ceres::Problem *problem);
126
milind-u8f4e43e2023-04-09 17:11:19 -0700127 ceres::examples::MapOfPoses ideal_target_poses_;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800128 ceres::examples::MapOfPoses target_poses_;
129 ceres::examples::VectorOfConstraints target_constraints_;
milind-u8f4e43e2023-04-09 17:11:19 -0700130
milind-u526d5672023-04-17 20:09:10 -0700131 // Counts of each pair of target ids we observe, so we can scale cost based on
132 // the inverse of this and remove bias towards certain pairs
133 std::map<std::pair<TargetId, TargetId>, size_t> constraint_counts_;
134
milind-u8f4e43e2023-04-09 17:11:19 -0700135 // Transformation moving the target map we solved for to where it actually
136 // should be in the world
137 Eigen::Translation3d T_frozen_actual_;
138 Eigen::Quaterniond R_frozen_actual_;
139
Jim Ostrowski68e56172023-09-17 23:44:15 -0700140 const double kFieldWidth_ = 20.0; // 20 meters across
141 const int kImageWidth_ = 1000;
142 const int kImageHeight_ =
143 kImageWidth_ * 3.0 / 4.0; // Roughly matches field aspect ratio
milind-u8f4e43e2023-04-09 17:11:19 -0700144 mutable VisualizeRobot vis_robot_;
milind-u401de982023-04-14 17:32:03 -0700145
146 Stats stats_with_outliers_;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800147};
148
Milind Upadhyay7c205222022-11-16 18:20:58 -0800149// Transforms robot position and target detection data into target constraints
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800150// to be used for mapping.
Milind Upadhyay7c205222022-11-16 18:20:58 -0800151class DataAdapter {
152 public:
Milind Upadhyay7c205222022-11-16 18:20:58 -0800153 // Pairs target detection with a time point
154 struct TimestampedDetection {
155 aos::distributed_clock::time_point time;
156 // Pose of target relative to robot
157 Eigen::Affine3d H_robot_target;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800158 // Horizontal distance from camera to target, used for confidence
159 // calculation
160 double distance_from_camera;
milind-ud62f80a2023-03-04 16:37:09 -0800161 // A measure of how much distortion affected this detection from 0-1.
162 double distortion_factor;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800163 TargetMapper::TargetId id;
164 };
165
Milind Upadhyayec493912022-12-18 21:33:15 -0800166 // Pairs consecutive target detections that are not too far apart in time into
167 // constraints. Meant to be used on a system without a position measurement.
168 // Assumes timestamped_target_detections is in chronological order.
169 // max_dt is the maximum time between two target detections to match them up.
170 // If too much time passes, the recoding device (box of pis) could have moved
171 // too much
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800172 static ceres::examples::VectorOfConstraints MatchTargetDetections(
Milind Upadhyayec493912022-12-18 21:33:15 -0800173 const std::vector<TimestampedDetection> &timestamped_target_detections,
milind-u8791bed2023-03-04 14:45:52 -0800174 aos::distributed_clock::duration max_dt = std::chrono::milliseconds(10));
Milind Upadhyayec493912022-12-18 21:33:15 -0800175
Milind Upadhyay7c205222022-11-16 18:20:58 -0800176 // Computes inverse of covariance matrix, assuming there was a target
177 // detection between robot movement over the given time period. Ceres calls
178 // this matrix the "information"
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800179 static TargetMapper::ConfidenceMatrix ComputeConfidence(
milind-ud62f80a2023-03-04 16:37:09 -0800180 const TimestampedDetection &detection_start,
181 const TimestampedDetection &detection_end);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800182
Milind Upadhyay7c205222022-11-16 18:20:58 -0800183 // Computes the constraint between the start and end pose of the targets: the
184 // relative pose between the start and end target locations in the frame of
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800185 // the start target.
186 static ceres::examples::Constraint3d ComputeTargetConstraint(
Milind Upadhyayec493912022-12-18 21:33:15 -0800187 const TimestampedDetection &target_detection_start,
188 const TimestampedDetection &target_detection_end,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800189 const TargetMapper::ConfidenceMatrix &confidence);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800190};
191
milind-ufbc5c812023-04-06 21:24:29 -0700192} // namespace frc971::vision
193
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700194namespace ceres::examples {
195template <typename Sink>
196void AbslStringify(Sink &sink, ceres::examples::Pose3d pose) {
197 auto rpy = frc971::vision::PoseUtils::QuaternionToEulerAngles(pose.q);
198 absl::Format(&sink,
199 "{x: %.3f, y: %.3f, z: %.3f, roll: %.3f, pitch: "
200 "%.3f, yaw: %.3f}",
201 pose.p(0), pose.p(1), pose.p(2), rpy(0), rpy(1), rpy(2));
202}
203
204template <typename Sink>
205void AbslStringify(Sink &sink, ceres::examples::Constraint3d constraint) {
206 absl::Format(&sink, "{id_begin: %d, id_end: %d, pose: ", constraint.id_begin,
207 constraint.id_end);
208 AbslStringify(sink, constraint.t_be);
209 sink.Append("}");
210}
211} // namespace ceres::examples
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800212
Milind Upadhyay7c205222022-11-16 18:20:58 -0800213#endif // FRC971_VISION_TARGET_MAPPER_H_