blob: df9f5b485568289a85da25dad0709103f5071d8d [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 Upadhyaycd677a32022-12-04 13:06:43 -080038 // If output_path is set, the map will be saved to that file as a json
39 void Solve(std::optional<std::string_view> output_path = std::nullopt);
40
41 // Prints target poses into a TargetMap flatbuffer json
42 std::string MapToJson() const;
Milind Upadhyay7c205222022-11-16 18:20:58 -080043
44 static std::optional<TargetPose> GetTargetPoseById(
45 std::vector<TargetPose> target_poses, TargetId target_id);
46
47 std::map<TargetId, ceres::examples::Pose2d> target_poses() {
48 return target_poses_;
49 }
50
51 private:
Milind Upadhyay7c205222022-11-16 18:20:58 -080052 // Constructs the nonlinear least squares optimization problem from the
53 // pose graph constraints.
54 void BuildOptimizationProblem(
55 std::map<TargetId, ceres::examples::Pose2d> *target_poses,
56 const std::vector<ceres::examples::Constraint2d> &constraints,
57 ceres::Problem *problem);
58
59 // Returns true if the solve was successful.
60 bool SolveOptimizationProblem(ceres::Problem *problem);
61
62 std::map<TargetId, ceres::examples::Pose2d> target_poses_;
63 std::vector<ceres::examples::Constraint2d> target_constraints_;
64};
65
66// Utility functions for dealing with ceres::examples::Pose2d structs
67class PoseUtils {
68 public:
69 // Embeds a 2d pose into a 3d affine transformation to be used in 3d
70 // computation
71 static Eigen::Affine3d Pose2dToAffine3d(ceres::examples::Pose2d pose2d);
72 // Assumes only x and y translation, and only z rotation (yaw)
73 static ceres::examples::Pose2d Affine3dToPose2d(Eigen::Affine3d H);
74
75 // Computes pose_2 relative to pose_1. This is equivalent to (pose_1^-1 *
76 // pose_2)
77 static ceres::examples::Pose2d ComputeRelativePose(
78 ceres::examples::Pose2d pose_1, ceres::examples::Pose2d pose_2);
79
80 // Computes pose_2 given a pose_1 and pose_2 relative to pose_1. This is
81 // equivalent to (pose_1 * pose_2_relative)
82 static ceres::examples::Pose2d ComputeOffsetPose(
83 ceres::examples::Pose2d pose_1, ceres::examples::Pose2d pose_2_relative);
84};
85
86// Transforms robot position and target detection data into target constraints
87// to be used for mapping. Interpolates continous-time data, converting it to
88// discrete detection time steps.
89class DataAdapter {
90 public:
91 // Pairs pose with a time point
92 struct TimestampedPose {
93 aos::distributed_clock::time_point time;
94 ceres::examples::Pose2d pose;
95 };
96
97 // Pairs target detection with a time point
98 struct TimestampedDetection {
99 aos::distributed_clock::time_point time;
100 // Pose of target relative to robot
101 Eigen::Affine3d H_robot_target;
102 TargetMapper::TargetId id;
103 };
104
105 // Pairs consecutive target detections into constraints, and interpolates
106 // robot poses based on time points to compute motion between detections. This
107 // prepares data to be used by TargetMapper. Also returns vector of delta
108 // robot poses corresponding to each constraint, to be used for testing.
109 //
110 // Assumes both inputs are in chronological order.
111 static std::pair<std::vector<ceres::examples::Constraint2d>,
112 std::vector<ceres::examples::Pose2d>>
113 MatchTargetDetections(
114 const std::vector<TimestampedPose> &timestamped_robot_poses,
115 const std::vector<TimestampedDetection> &timestamped_target_detections);
116
117 // Computes inverse of covariance matrix, assuming there was a target
118 // detection between robot movement over the given time period. Ceres calls
119 // this matrix the "information"
120 static Eigen::Matrix3d ComputeConfidence(
121 aos::distributed_clock::time_point start,
122 aos::distributed_clock::time_point end);
123
124 private:
125 static ceres::examples::Pose2d InterpolatePose(
126 const TimestampedPose &pose_start, const TimestampedPose &pose_end,
127 aos::distributed_clock::time_point time);
128
129 // Computes the constraint between the start and end pose of the targets: the
130 // relative pose between the start and end target locations in the frame of
131 // the start target. Takes into account the robot motion in the time between
132 // the two detections.
133 static ceres::examples::Constraint2d ComputeTargetConstraint(
134 const TimestampedDetection &target_detection_start,
135 const Eigen::Affine3d &H_robotstart_robotend,
136 const TimestampedDetection &target_detection_end,
137 const Eigen::Matrix3d &confidence);
138};
139
140} // namespace frc971::vision
141
142#endif // FRC971_VISION_TARGET_MAPPER_H_