Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 1 | #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 Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 7 | #include "ceres/ceres.h" |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 8 | #include "frc971/vision/ceres/types.h" |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 9 | #include "frc971/vision/target_map_generated.h" |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 10 | |
| 11 | namespace 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. |
| 17 | class TargetMapper { |
| 18 | public: |
| 19 | using TargetId = int; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 20 | using ConfidenceMatrix = Eigen::Matrix<double, 6, 6>; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 21 | |
| 22 | struct TargetPose { |
| 23 | TargetId id; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 24 | ceres::examples::Pose3d pose; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 25 | }; |
| 26 | |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 27 | // 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 Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 29 | // target_constraints are the deltas between consecutive target detections, |
| 30 | // and are usually prepared by the DataAdapter class below. |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 31 | TargetMapper(std::string_view target_poses_path, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 32 | const ceres::examples::VectorOfConstraints &target_constraints); |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 33 | // Alternate constructor for tests. |
| 34 | // Takes in the actual intial guesses instead of a file containing them |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 35 | TargetMapper(const ceres::examples::MapOfPoses &target_poses, |
| 36 | const ceres::examples::VectorOfConstraints &target_constraints); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 37 | |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 38 | // 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 Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 42 | |
| 43 | // Prints target poses into a TargetMap flatbuffer json |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 44 | std::string MapToJson(std::string_view field_name) const; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 45 | |
| 46 | static std::optional<TargetPose> GetTargetPoseById( |
| 47 | std::vector<TargetPose> target_poses, TargetId target_id); |
| 48 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 49 | ceres::examples::MapOfPoses target_poses() { return target_poses_; } |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 50 | |
| 51 | private: |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 52 | // Constructs the nonlinear least squares optimization problem from the |
| 53 | // pose graph constraints. |
| 54 | void BuildOptimizationProblem( |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 55 | const ceres::examples::VectorOfConstraints &constraints, |
| 56 | ceres::examples::MapOfPoses *poses, ceres::Problem *problem); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 57 | |
| 58 | // Returns true if the solve was successful. |
| 59 | bool SolveOptimizationProblem(ceres::Problem *problem); |
| 60 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 61 | ceres::examples::MapOfPoses target_poses_; |
| 62 | ceres::examples::VectorOfConstraints target_constraints_; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 63 | }; |
| 64 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 65 | // Utility functions for dealing with ceres::examples::Pose3d structs |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 66 | class PoseUtils { |
| 67 | public: |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 68 | // 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 Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 73 | |
| 74 | // Computes pose_2 relative to pose_1. This is equivalent to (pose_1^-1 * |
| 75 | // pose_2) |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 76 | static ceres::examples::Pose3d ComputeRelativePose( |
| 77 | const ceres::examples::Pose3d &pose_1, |
| 78 | const ceres::examples::Pose3d &pose_2); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 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) |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 82 | 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 Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 92 | }; |
| 93 | |
| 94 | // Transforms robot position and target detection data into target constraints |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 95 | // to be used for mapping. |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 96 | class DataAdapter { |
| 97 | public: |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 98 | // Pairs target detection with a time point |
| 99 | struct TimestampedDetection { |
| 100 | aos::distributed_clock::time_point time; |
| 101 | // Pose of target relative to robot |
| 102 | Eigen::Affine3d H_robot_target; |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 103 | // Horizontal distance from camera to target, used for confidence |
| 104 | // calculation |
| 105 | double distance_from_camera; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 106 | TargetMapper::TargetId id; |
| 107 | }; |
| 108 | |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 109 | // Pairs consecutive target detections that are not too far apart in time into |
| 110 | // constraints. Meant to be used on a system without a position measurement. |
| 111 | // Assumes timestamped_target_detections is in chronological order. |
| 112 | // max_dt is the maximum time between two target detections to match them up. |
| 113 | // If too much time passes, the recoding device (box of pis) could have moved |
| 114 | // too much |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 115 | static ceres::examples::VectorOfConstraints MatchTargetDetections( |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 116 | const std::vector<TimestampedDetection> ×tamped_target_detections, |
Milind Upadhyay | 915d600 | 2022-12-26 20:37:43 -0800 | [diff] [blame] | 117 | aos::distributed_clock::duration max_dt = std::chrono::milliseconds(1)); |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 118 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 119 | // Computes inverse of covariance matrix, assuming there was a target |
| 120 | // detection between robot movement over the given time period. Ceres calls |
| 121 | // this matrix the "information" |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 122 | static TargetMapper::ConfidenceMatrix ComputeConfidence( |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 123 | aos::distributed_clock::time_point start, |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 124 | aos::distributed_clock::time_point end, double distance_from_camera_start, |
| 125 | double distance_from_camera_end); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 126 | |
| 127 | private: |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 128 | // Computes the constraint between the start and end pose of the targets: the |
| 129 | // relative pose between the start and end target locations in the frame of |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 130 | // the start target. |
| 131 | static ceres::examples::Constraint3d ComputeTargetConstraint( |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 132 | const TimestampedDetection &target_detection_start, |
| 133 | const TimestampedDetection &target_detection_end, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 134 | const TargetMapper::ConfidenceMatrix &confidence); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 135 | }; |
| 136 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 137 | std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose); |
| 138 | std::ostream &operator<<(std::ostream &os, |
| 139 | ceres::examples::Constraint3d constraint); |
| 140 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 141 | } // namespace frc971::vision |
| 142 | |
| 143 | #endif // FRC971_VISION_TARGET_MAPPER_H_ |