blob: a4c12b2403aadcdba1dff3b230d47323d53e129e [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
Milind Upadhyayc5beba12022-12-17 17:41:20 -08006#include "ceres/ceres.h"
Philipp Schrader790cb542023-07-05 21:06:52 -07007
8#include "aos/events/simulated_event_loop.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -08009#include "frc971/vision/ceres/types.h"
Milind Upadhyaycd677a32022-12-04 13:06:43 -080010#include "frc971/vision/target_map_generated.h"
milind-u8f4e43e2023-04-09 17:11:19 -070011#include "frc971/vision/visualize_robot.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -080012
13namespace frc971::vision {
14
15// Estimates positions of vision targets (ex. April Tags) using
16// target detections relative to a robot (which were computed using robot
17// positions at the time of those detections). Solves SLAM problem to estimate
18// target locations using deltas between consecutive target detections.
19class TargetMapper {
20 public:
21 using TargetId = int;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080022 using ConfidenceMatrix = Eigen::Matrix<double, 6, 6>;
Milind Upadhyay7c205222022-11-16 18:20:58 -080023
24 struct TargetPose {
25 TargetId id;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080026 ceres::examples::Pose3d pose;
Milind Upadhyay7c205222022-11-16 18:20:58 -080027 };
28
Milind Upadhyaycd677a32022-12-04 13:06:43 -080029 // target_poses_path is the path to a TargetMap json with initial guesses for
30 // the actual locations of the targets on the field.
Milind Upadhyay7c205222022-11-16 18:20:58 -080031 // target_constraints are the deltas between consecutive target detections,
32 // and are usually prepared by the DataAdapter class below.
Milind Upadhyaycd677a32022-12-04 13:06:43 -080033 TargetMapper(std::string_view target_poses_path,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080034 const ceres::examples::VectorOfConstraints &target_constraints);
Milind Upadhyaycd677a32022-12-04 13:06:43 -080035 // Alternate constructor for tests.
36 // Takes in the actual intial guesses instead of a file containing them
Milind Upadhyayc5beba12022-12-17 17:41:20 -080037 TargetMapper(const ceres::examples::MapOfPoses &target_poses,
38 const ceres::examples::VectorOfConstraints &target_constraints);
Milind Upadhyay7c205222022-11-16 18:20:58 -080039
Milind Upadhyay05652cb2022-12-07 20:51:51 -080040 // Solves for the target map. If output_dir is set, the map will be saved to
41 // output_dir/field_name.json
42 void Solve(std::string_view field_name,
43 std::optional<std::string_view> output_dir = std::nullopt);
Milind Upadhyaycd677a32022-12-04 13:06:43 -080044
45 // Prints target poses into a TargetMap flatbuffer json
Milind Upadhyay05652cb2022-12-07 20:51:51 -080046 std::string MapToJson(std::string_view field_name) const;
Milind Upadhyay7c205222022-11-16 18:20:58 -080047
48 static std::optional<TargetPose> GetTargetPoseById(
49 std::vector<TargetPose> target_poses, TargetId target_id);
50
Jim Ostrowski49be8232023-03-23 01:00:14 -070051 // Version that gets based on internal target_poses
milind-u2ab4db12023-03-25 21:59:23 -070052 std::optional<TargetPose> GetTargetPoseById(TargetId target_id) const;
Jim Ostrowski49be8232023-03-23 01:00:14 -070053
Milind Upadhyayc5beba12022-12-17 17:41:20 -080054 ceres::examples::MapOfPoses target_poses() { return target_poses_; }
Milind Upadhyay7c205222022-11-16 18:20:58 -080055
milind-u8f4e43e2023-04-09 17:11:19 -070056 // Cost function for the secondary solver finding out where the whole map fits
57 // in the world
58 template <typename S>
59 bool operator()(const S *const translation, const S *const rotation,
60 S *residual) const;
61
milind-u401de982023-04-14 17:32:03 -070062 void DumpConstraints(std::string_view path) const;
63 void DumpStats(std::string_view path) const;
64
Milind Upadhyay7c205222022-11-16 18:20:58 -080065 private:
milind-u401de982023-04-14 17:32:03 -070066 // Error in an estimated pose
67 struct PoseError {
68 double angle;
69 double distance;
70 };
71
72 // Stores info on how much all the constraints differ from our solved target
73 // map
74 struct Stats {
75 // Average error for translation and rotation
76 PoseError avg_err;
77 // Standard deviation for translation and rotation error
78 PoseError std_dev;
79 // Maximum error for translation and rotation
80 PoseError max_err;
81 };
82
83 // Compute the error of a single constraint
84 PoseError ComputeError(const ceres::examples::Constraint3d &constraint) const;
85 // Compute cumulative stats for all constraints
86 Stats ComputeStats() const;
87 // Removes constraints with very large errors
88 void RemoveOutlierConstraints();
89
milind-u526d5672023-04-17 20:09:10 -070090 void CountConstraints();
91
Milind Upadhyay7c205222022-11-16 18:20:58 -080092 // Constructs the nonlinear least squares optimization problem from the
93 // pose graph constraints.
milind-u8f4e43e2023-04-09 17:11:19 -070094 void BuildTargetPoseOptimizationProblem(
Milind Upadhyayc5beba12022-12-17 17:41:20 -080095 const ceres::examples::VectorOfConstraints &constraints,
96 ceres::examples::MapOfPoses *poses, ceres::Problem *problem);
Milind Upadhyay7c205222022-11-16 18:20:58 -080097
milind-u8f4e43e2023-04-09 17:11:19 -070098 // Constructs the nonlinear least squares optimization problem for the solved
99 // -> actual pose solver.
milind-u401de982023-04-14 17:32:03 -0700100 std::unique_ptr<ceres::CostFunction> BuildMapFittingOptimizationProblem(
101 ceres::Problem *problem);
milind-u8f4e43e2023-04-09 17:11:19 -0700102
Jim Ostrowski4527dd72024-03-07 00:20:15 -0800103 // Create and display a visualization of the graph connectivity of the
104 // constraints
105 void DisplayConstraintGraph();
106
Jim Ostrowskiefc3bde2024-03-23 16:34:06 -0700107 // Create and display a visualization of the map solution (vs. the input map)
108 void DisplaySolvedVsInitial();
109
Milind Upadhyay7c205222022-11-16 18:20:58 -0800110 // Returns true if the solve was successful.
111 bool SolveOptimizationProblem(ceres::Problem *problem);
112
milind-u8f4e43e2023-04-09 17:11:19 -0700113 ceres::examples::MapOfPoses ideal_target_poses_;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800114 ceres::examples::MapOfPoses target_poses_;
115 ceres::examples::VectorOfConstraints target_constraints_;
milind-u8f4e43e2023-04-09 17:11:19 -0700116
milind-u526d5672023-04-17 20:09:10 -0700117 // Counts of each pair of target ids we observe, so we can scale cost based on
118 // the inverse of this and remove bias towards certain pairs
119 std::map<std::pair<TargetId, TargetId>, size_t> constraint_counts_;
120
milind-u8f4e43e2023-04-09 17:11:19 -0700121 // Transformation moving the target map we solved for to where it actually
122 // should be in the world
123 Eigen::Translation3d T_frozen_actual_;
124 Eigen::Quaterniond R_frozen_actual_;
125
Jim Ostrowski68e56172023-09-17 23:44:15 -0700126 const double kFieldWidth_ = 20.0; // 20 meters across
127 const int kImageWidth_ = 1000;
128 const int kImageHeight_ =
129 kImageWidth_ * 3.0 / 4.0; // Roughly matches field aspect ratio
milind-u8f4e43e2023-04-09 17:11:19 -0700130 mutable VisualizeRobot vis_robot_;
milind-u401de982023-04-14 17:32:03 -0700131
132 Stats stats_with_outliers_;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800133};
134
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800135// Utility functions for dealing with ceres::examples::Pose3d structs
Milind Upadhyay7c205222022-11-16 18:20:58 -0800136class PoseUtils {
137 public:
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800138 // Embeds a 3d pose into an affine transformation
139 static Eigen::Affine3d Pose3dToAffine3d(
140 const ceres::examples::Pose3d &pose3d);
141 // Inverse of above function
142 static ceres::examples::Pose3d Affine3dToPose3d(const Eigen::Affine3d &H);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800143
144 // Computes pose_2 relative to pose_1. This is equivalent to (pose_1^-1 *
145 // pose_2)
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800146 static ceres::examples::Pose3d ComputeRelativePose(
147 const ceres::examples::Pose3d &pose_1,
148 const ceres::examples::Pose3d &pose_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800149
150 // Computes pose_2 given a pose_1 and pose_2 relative to pose_1. This is
151 // equivalent to (pose_1 * pose_2_relative)
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800152 static ceres::examples::Pose3d ComputeOffsetPose(
153 const ceres::examples::Pose3d &pose_1,
154 const ceres::examples::Pose3d &pose_2_relative);
155
156 // Converts a rotation with roll, pitch, and yaw into a quaternion
157 static Eigen::Quaterniond EulerAnglesToQuaternion(const Eigen::Vector3d &rpy);
158 // Inverse of above function
159 static Eigen::Vector3d QuaternionToEulerAngles(const Eigen::Quaterniond &q);
160 // Converts a 3d rotation matrix into a rotation with roll, pitch, and yaw
161 static Eigen::Vector3d RotationMatrixToEulerAngles(const Eigen::Matrix3d &R);
milind-u3f5f83c2023-01-29 15:23:51 -0800162
163 // Builds a TargetPoseFbs from a TargetPose
164 static flatbuffers::Offset<TargetPoseFbs> TargetPoseToFbs(
165 const TargetMapper::TargetPose &target_pose,
166 flatbuffers::FlatBufferBuilder *fbb);
167 // Converts a TargetPoseFbs to a TargetPose
168 static TargetMapper::TargetPose TargetPoseFromFbs(
169 const TargetPoseFbs &target_pose_fbs);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800170};
171
172// Transforms robot position and target detection data into target constraints
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800173// to be used for mapping.
Milind Upadhyay7c205222022-11-16 18:20:58 -0800174class DataAdapter {
175 public:
Milind Upadhyay7c205222022-11-16 18:20:58 -0800176 // Pairs target detection with a time point
177 struct TimestampedDetection {
178 aos::distributed_clock::time_point time;
179 // Pose of target relative to robot
180 Eigen::Affine3d H_robot_target;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800181 // Horizontal distance from camera to target, used for confidence
182 // calculation
183 double distance_from_camera;
milind-ud62f80a2023-03-04 16:37:09 -0800184 // A measure of how much distortion affected this detection from 0-1.
185 double distortion_factor;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800186 TargetMapper::TargetId id;
187 };
188
Milind Upadhyayec493912022-12-18 21:33:15 -0800189 // Pairs consecutive target detections that are not too far apart in time into
190 // constraints. Meant to be used on a system without a position measurement.
191 // Assumes timestamped_target_detections is in chronological order.
192 // max_dt is the maximum time between two target detections to match them up.
193 // If too much time passes, the recoding device (box of pis) could have moved
194 // too much
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800195 static ceres::examples::VectorOfConstraints MatchTargetDetections(
Milind Upadhyayec493912022-12-18 21:33:15 -0800196 const std::vector<TimestampedDetection> &timestamped_target_detections,
milind-u8791bed2023-03-04 14:45:52 -0800197 aos::distributed_clock::duration max_dt = std::chrono::milliseconds(10));
Milind Upadhyayec493912022-12-18 21:33:15 -0800198
Milind Upadhyay7c205222022-11-16 18:20:58 -0800199 // Computes inverse of covariance matrix, assuming there was a target
200 // detection between robot movement over the given time period. Ceres calls
201 // this matrix the "information"
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800202 static TargetMapper::ConfidenceMatrix ComputeConfidence(
milind-ud62f80a2023-03-04 16:37:09 -0800203 const TimestampedDetection &detection_start,
204 const TimestampedDetection &detection_end);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800205
Milind Upadhyay7c205222022-11-16 18:20:58 -0800206 // Computes the constraint between the start and end pose of the targets: the
207 // relative pose between the start and end target locations in the frame of
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800208 // the start target.
209 static ceres::examples::Constraint3d ComputeTargetConstraint(
Milind Upadhyayec493912022-12-18 21:33:15 -0800210 const TimestampedDetection &target_detection_start,
211 const TimestampedDetection &target_detection_end,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800212 const TargetMapper::ConfidenceMatrix &confidence);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800213};
214
milind-ufbc5c812023-04-06 21:24:29 -0700215} // namespace frc971::vision
216
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800217std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose);
218std::ostream &operator<<(std::ostream &os,
219 ceres::examples::Constraint3d constraint);
220
Milind Upadhyay7c205222022-11-16 18:20:58 -0800221#endif // FRC971_VISION_TARGET_MAPPER_H_