blob: 7701fd1e1331669732585e1542e00cf1641d0410 [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"
Milind Upadhyayc5beba12022-12-17 17:41:20 -08007#include "ceres/ceres.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -08008#include "frc971/vision/ceres/types.h"
Milind Upadhyaycd677a32022-12-04 13:06:43 -08009#include "frc971/vision/target_map_generated.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -080010
11namespace frc971::vision {
12
13// Estimates positions of vision targets (ex. April Tags) using
14// target detections relative to a robot (which were computed using robot
15// positions at the time of those detections). Solves SLAM problem to estimate
16// target locations using deltas between consecutive target detections.
17class TargetMapper {
18 public:
19 using TargetId = int;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080020 using ConfidenceMatrix = Eigen::Matrix<double, 6, 6>;
Milind Upadhyay7c205222022-11-16 18:20:58 -080021
22 struct TargetPose {
23 TargetId id;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080024 ceres::examples::Pose3d pose;
Milind Upadhyay7c205222022-11-16 18:20:58 -080025 };
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,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080032 const ceres::examples::VectorOfConstraints &target_constraints);
Milind Upadhyaycd677a32022-12-04 13:06:43 -080033 // Alternate constructor for tests.
34 // Takes in the actual intial guesses instead of a file containing them
Milind Upadhyayc5beba12022-12-17 17:41:20 -080035 TargetMapper(const ceres::examples::MapOfPoses &target_poses,
36 const ceres::examples::VectorOfConstraints &target_constraints);
Milind Upadhyay7c205222022-11-16 18:20:58 -080037
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
Milind Upadhyayc5beba12022-12-17 17:41:20 -080049 ceres::examples::MapOfPoses target_poses() { return target_poses_; }
Milind Upadhyay7c205222022-11-16 18:20:58 -080050
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(
Milind Upadhyayc5beba12022-12-17 17:41:20 -080055 const ceres::examples::VectorOfConstraints &constraints,
56 ceres::examples::MapOfPoses *poses, ceres::Problem *problem);
Milind Upadhyay7c205222022-11-16 18:20:58 -080057
58 // Returns true if the solve was successful.
59 bool SolveOptimizationProblem(ceres::Problem *problem);
60
Milind Upadhyayc5beba12022-12-17 17:41:20 -080061 ceres::examples::MapOfPoses target_poses_;
62 ceres::examples::VectorOfConstraints target_constraints_;
Milind Upadhyay7c205222022-11-16 18:20:58 -080063};
64
Milind Upadhyayc5beba12022-12-17 17:41:20 -080065// Utility functions for dealing with ceres::examples::Pose3d structs
Milind Upadhyay7c205222022-11-16 18:20:58 -080066class PoseUtils {
67 public:
Milind Upadhyayc5beba12022-12-17 17:41:20 -080068 // Embeds a 3d pose into an affine transformation
69 static Eigen::Affine3d Pose3dToAffine3d(
70 const ceres::examples::Pose3d &pose3d);
71 // Inverse of above function
72 static ceres::examples::Pose3d Affine3dToPose3d(const Eigen::Affine3d &H);
Milind Upadhyay7c205222022-11-16 18:20:58 -080073
74 // Computes pose_2 relative to pose_1. This is equivalent to (pose_1^-1 *
75 // pose_2)
Milind Upadhyayc5beba12022-12-17 17:41:20 -080076 static ceres::examples::Pose3d ComputeRelativePose(
77 const ceres::examples::Pose3d &pose_1,
78 const ceres::examples::Pose3d &pose_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080079
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)
Milind Upadhyayc5beba12022-12-17 17:41:20 -080082 static ceres::examples::Pose3d ComputeOffsetPose(
83 const ceres::examples::Pose3d &pose_1,
84 const ceres::examples::Pose3d &pose_2_relative);
85
86 // Converts a rotation with roll, pitch, and yaw into a quaternion
87 static Eigen::Quaterniond EulerAnglesToQuaternion(const Eigen::Vector3d &rpy);
88 // Inverse of above function
89 static Eigen::Vector3d QuaternionToEulerAngles(const Eigen::Quaterniond &q);
90 // Converts a 3d rotation matrix into a rotation with roll, pitch, and yaw
91 static Eigen::Vector3d RotationMatrixToEulerAngles(const Eigen::Matrix3d &R);
milind-u3f5f83c2023-01-29 15:23:51 -080092
93 // Builds a TargetPoseFbs from a TargetPose
94 static flatbuffers::Offset<TargetPoseFbs> TargetPoseToFbs(
95 const TargetMapper::TargetPose &target_pose,
96 flatbuffers::FlatBufferBuilder *fbb);
97 // Converts a TargetPoseFbs to a TargetPose
98 static TargetMapper::TargetPose TargetPoseFromFbs(
99 const TargetPoseFbs &target_pose_fbs);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800100};
101
102// Transforms robot position and target detection data into target constraints
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800103// to be used for mapping.
Milind Upadhyay7c205222022-11-16 18:20:58 -0800104class DataAdapter {
105 public:
Milind Upadhyay7c205222022-11-16 18:20:58 -0800106 // Pairs target detection with a time point
107 struct TimestampedDetection {
108 aos::distributed_clock::time_point time;
109 // Pose of target relative to robot
110 Eigen::Affine3d H_robot_target;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800111 // Horizontal distance from camera to target, used for confidence
112 // calculation
113 double distance_from_camera;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800114 TargetMapper::TargetId id;
115 };
116
Milind Upadhyayec493912022-12-18 21:33:15 -0800117 // Pairs consecutive target detections that are not too far apart in time into
118 // constraints. Meant to be used on a system without a position measurement.
119 // Assumes timestamped_target_detections is in chronological order.
120 // max_dt is the maximum time between two target detections to match them up.
121 // If too much time passes, the recoding device (box of pis) could have moved
122 // too much
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800123 static ceres::examples::VectorOfConstraints MatchTargetDetections(
Milind Upadhyayec493912022-12-18 21:33:15 -0800124 const std::vector<TimestampedDetection> &timestamped_target_detections,
Milind Upadhyay915d6002022-12-26 20:37:43 -0800125 aos::distributed_clock::duration max_dt = std::chrono::milliseconds(1));
Milind Upadhyayec493912022-12-18 21:33:15 -0800126
Milind Upadhyay7c205222022-11-16 18:20:58 -0800127 // Computes inverse of covariance matrix, assuming there was a target
128 // detection between robot movement over the given time period. Ceres calls
129 // this matrix the "information"
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800130 static TargetMapper::ConfidenceMatrix ComputeConfidence(
Milind Upadhyay7c205222022-11-16 18:20:58 -0800131 aos::distributed_clock::time_point start,
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800132 aos::distributed_clock::time_point end, double distance_from_camera_start,
133 double distance_from_camera_end);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800134
135 private:
Milind Upadhyay7c205222022-11-16 18:20:58 -0800136 // Computes the constraint between the start and end pose of the targets: the
137 // relative pose between the start and end target locations in the frame of
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800138 // the start target.
139 static ceres::examples::Constraint3d ComputeTargetConstraint(
Milind Upadhyayec493912022-12-18 21:33:15 -0800140 const TimestampedDetection &target_detection_start,
141 const TimestampedDetection &target_detection_end,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800142 const TargetMapper::ConfidenceMatrix &confidence);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800143};
144
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800145std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose);
146std::ostream &operator<<(std::ostream &os,
147 ceres::examples::Constraint3d constraint);
148
Milind Upadhyay7c205222022-11-16 18:20:58 -0800149} // namespace frc971::vision
150
151#endif // FRC971_VISION_TARGET_MAPPER_H_