blob: edf22601c86b5b839fb58140572937e74604146f [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
6#include "aos/events/simulated_event_loop.h"
7#include "frc971/vision/ceres/types.h"
Milind Upadhyaycd677a32022-12-04 13:06:43 -08008#include "frc971/vision/target_map_generated.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -08009
10namespace frc971::vision {
11
12// Estimates positions of vision targets (ex. April Tags) using
13// target detections relative to a robot (which were computed using robot
14// positions at the time of those detections). Solves SLAM problem to estimate
15// target locations using deltas between consecutive target detections.
16class TargetMapper {
17 public:
18 using TargetId = int;
19
20 struct TargetPose {
21 TargetId id;
Milind Upadhyaycd677a32022-12-04 13:06:43 -080022 // TOOD(milind): switch everything to 3d once we're more confident in 2d
23 // solving
Milind Upadhyay7c205222022-11-16 18:20:58 -080024 ceres::examples::Pose2d pose;
25 };
26
Milind Upadhyaycd677a32022-12-04 13:06:43 -080027 // target_poses_path is the path to a TargetMap json with initial guesses for
28 // the actual locations of the targets on the field.
Milind Upadhyay7c205222022-11-16 18:20:58 -080029 // target_constraints are the deltas between consecutive target detections,
30 // and are usually prepared by the DataAdapter class below.
Milind Upadhyaycd677a32022-12-04 13:06:43 -080031 TargetMapper(std::string_view target_poses_path,
32 std::vector<ceres::examples::Constraint2d> target_constraints);
33 // Alternate constructor for tests.
34 // Takes in the actual intial guesses instead of a file containing them
Milind Upadhyay7c205222022-11-16 18:20:58 -080035 TargetMapper(std::map<TargetId, ceres::examples::Pose2d> target_poses,
36 std::vector<ceres::examples::Constraint2d> target_constraints);
37
Milind Upadhyay05652cb2022-12-07 20:51:51 -080038 // Solves for the target map. If output_dir is set, the map will be saved to
39 // output_dir/field_name.json
40 void Solve(std::string_view field_name,
41 std::optional<std::string_view> output_dir = std::nullopt);
Milind Upadhyaycd677a32022-12-04 13:06:43 -080042
43 // Prints target poses into a TargetMap flatbuffer json
Milind Upadhyay05652cb2022-12-07 20:51:51 -080044 std::string MapToJson(std::string_view field_name) const;
Milind Upadhyay7c205222022-11-16 18:20:58 -080045
46 static std::optional<TargetPose> GetTargetPoseById(
47 std::vector<TargetPose> target_poses, TargetId target_id);
48
49 std::map<TargetId, ceres::examples::Pose2d> target_poses() {
50 return target_poses_;
51 }
52
53 private:
Milind Upadhyay7c205222022-11-16 18:20:58 -080054 // Constructs the nonlinear least squares optimization problem from the
55 // pose graph constraints.
56 void BuildOptimizationProblem(
57 std::map<TargetId, ceres::examples::Pose2d> *target_poses,
58 const std::vector<ceres::examples::Constraint2d> &constraints,
59 ceres::Problem *problem);
60
61 // Returns true if the solve was successful.
62 bool SolveOptimizationProblem(ceres::Problem *problem);
63
64 std::map<TargetId, ceres::examples::Pose2d> target_poses_;
65 std::vector<ceres::examples::Constraint2d> target_constraints_;
66};
67
68// Utility functions for dealing with ceres::examples::Pose2d structs
69class PoseUtils {
70 public:
71 // Embeds a 2d pose into a 3d affine transformation to be used in 3d
72 // computation
73 static Eigen::Affine3d Pose2dToAffine3d(ceres::examples::Pose2d pose2d);
74 // Assumes only x and y translation, and only z rotation (yaw)
75 static ceres::examples::Pose2d Affine3dToPose2d(Eigen::Affine3d H);
76
77 // Computes pose_2 relative to pose_1. This is equivalent to (pose_1^-1 *
78 // pose_2)
79 static ceres::examples::Pose2d ComputeRelativePose(
80 ceres::examples::Pose2d pose_1, ceres::examples::Pose2d pose_2);
81
82 // Computes pose_2 given a pose_1 and pose_2 relative to pose_1. This is
83 // equivalent to (pose_1 * pose_2_relative)
84 static ceres::examples::Pose2d ComputeOffsetPose(
85 ceres::examples::Pose2d pose_1, ceres::examples::Pose2d pose_2_relative);
86};
87
88// Transforms robot position and target detection data into target constraints
89// to be used for mapping. Interpolates continous-time data, converting it to
90// discrete detection time steps.
91class DataAdapter {
92 public:
93 // Pairs pose with a time point
94 struct TimestampedPose {
95 aos::distributed_clock::time_point time;
96 ceres::examples::Pose2d pose;
97 };
98
99 // Pairs target detection with a time point
100 struct TimestampedDetection {
101 aos::distributed_clock::time_point time;
102 // Pose of target relative to robot
103 Eigen::Affine3d H_robot_target;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800104 // Horizontal distance from camera to target, used for confidence
105 // calculation
106 double distance_from_camera;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800107 TargetMapper::TargetId id;
108 };
109
110 // Pairs consecutive target detections into constraints, and interpolates
111 // robot poses based on time points to compute motion between detections. This
112 // prepares data to be used by TargetMapper. Also returns vector of delta
113 // robot poses corresponding to each constraint, to be used for testing.
114 //
115 // Assumes both inputs are in chronological order.
116 static std::pair<std::vector<ceres::examples::Constraint2d>,
117 std::vector<ceres::examples::Pose2d>>
118 MatchTargetDetections(
119 const std::vector<TimestampedPose> &timestamped_robot_poses,
120 const std::vector<TimestampedDetection> &timestamped_target_detections);
121
Milind Upadhyayec493912022-12-18 21:33:15 -0800122 // Pairs consecutive target detections that are not too far apart in time into
123 // constraints. Meant to be used on a system without a position measurement.
124 // Assumes timestamped_target_detections is in chronological order.
125 // max_dt is the maximum time between two target detections to match them up.
126 // If too much time passes, the recoding device (box of pis) could have moved
127 // too much
128 static std::vector<ceres::examples::Constraint2d> MatchTargetDetections(
129 const std::vector<TimestampedDetection> &timestamped_target_detections,
Milind Upadhyay915d6002022-12-26 20:37:43 -0800130 aos::distributed_clock::duration max_dt = std::chrono::milliseconds(1));
Milind Upadhyayec493912022-12-18 21:33:15 -0800131
Milind Upadhyay7c205222022-11-16 18:20:58 -0800132 // Computes inverse of covariance matrix, assuming there was a target
133 // detection between robot movement over the given time period. Ceres calls
134 // this matrix the "information"
135 static Eigen::Matrix3d ComputeConfidence(
136 aos::distributed_clock::time_point start,
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800137 aos::distributed_clock::time_point end, double distance_from_camera_start,
138 double distance_from_camera_end);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800139
140 private:
141 static ceres::examples::Pose2d InterpolatePose(
142 const TimestampedPose &pose_start, const TimestampedPose &pose_end,
143 aos::distributed_clock::time_point time);
144
145 // Computes the constraint between the start and end pose of the targets: the
146 // relative pose between the start and end target locations in the frame of
147 // the start target. Takes into account the robot motion in the time between
148 // the two detections.
149 static ceres::examples::Constraint2d ComputeTargetConstraint(
150 const TimestampedDetection &target_detection_start,
151 const Eigen::Affine3d &H_robotstart_robotend,
152 const TimestampedDetection &target_detection_end,
153 const Eigen::Matrix3d &confidence);
Milind Upadhyayec493912022-12-18 21:33:15 -0800154 // Same as above function, but assumes no robot motion between the two
155 // detections
156 static ceres::examples::Constraint2d ComputeTargetConstraint(
157 const TimestampedDetection &target_detection_start,
158 const TimestampedDetection &target_detection_end,
159 const Eigen::Matrix3d &confidence);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800160};
161
162} // namespace frc971::vision
163
164#endif // FRC971_VISION_TARGET_MAPPER_H_