blob: ca36866f6db8c4a2426baa354de0cde751a14538 [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-u8f4e43e2023-04-09 17:11:19 -070010#include "frc971/vision/visualize_robot.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -080011
12namespace frc971::vision {
13
14// Estimates positions of vision targets (ex. April Tags) using
15// target detections relative to a robot (which were computed using robot
16// positions at the time of those detections). Solves SLAM problem to estimate
17// target locations using deltas between consecutive target detections.
18class TargetMapper {
19 public:
20 using TargetId = int;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080021 using ConfidenceMatrix = Eigen::Matrix<double, 6, 6>;
Milind Upadhyay7c205222022-11-16 18:20:58 -080022
23 struct TargetPose {
24 TargetId id;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080025 ceres::examples::Pose3d pose;
Milind Upadhyay7c205222022-11-16 18:20:58 -080026 };
27
Milind Upadhyaycd677a32022-12-04 13:06:43 -080028 // target_poses_path is the path to a TargetMap json with initial guesses for
29 // the actual locations of the targets on the field.
Milind Upadhyay7c205222022-11-16 18:20:58 -080030 // target_constraints are the deltas between consecutive target detections,
31 // and are usually prepared by the DataAdapter class below.
Milind Upadhyaycd677a32022-12-04 13:06:43 -080032 TargetMapper(std::string_view target_poses_path,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080033 const ceres::examples::VectorOfConstraints &target_constraints);
Milind Upadhyaycd677a32022-12-04 13:06:43 -080034 // Alternate constructor for tests.
35 // Takes in the actual intial guesses instead of a file containing them
Milind Upadhyayc5beba12022-12-17 17:41:20 -080036 TargetMapper(const ceres::examples::MapOfPoses &target_poses,
37 const ceres::examples::VectorOfConstraints &target_constraints);
Milind Upadhyay7c205222022-11-16 18:20:58 -080038
Milind Upadhyay05652cb2022-12-07 20:51:51 -080039 // Solves for the target map. If output_dir is set, the map will be saved to
40 // output_dir/field_name.json
41 void Solve(std::string_view field_name,
42 std::optional<std::string_view> output_dir = std::nullopt);
Milind Upadhyaycd677a32022-12-04 13:06:43 -080043
44 // Prints target poses into a TargetMap flatbuffer json
Milind Upadhyay05652cb2022-12-07 20:51:51 -080045 std::string MapToJson(std::string_view field_name) const;
Milind Upadhyay7c205222022-11-16 18:20:58 -080046
47 static std::optional<TargetPose> GetTargetPoseById(
48 std::vector<TargetPose> target_poses, TargetId target_id);
49
Jim Ostrowski49be8232023-03-23 01:00:14 -070050 // Version that gets based on internal target_poses
milind-u2ab4db12023-03-25 21:59:23 -070051 std::optional<TargetPose> GetTargetPoseById(TargetId target_id) const;
Jim Ostrowski49be8232023-03-23 01:00:14 -070052
Milind Upadhyayc5beba12022-12-17 17:41:20 -080053 ceres::examples::MapOfPoses target_poses() { return target_poses_; }
Milind Upadhyay7c205222022-11-16 18:20:58 -080054
milind-u8f4e43e2023-04-09 17:11:19 -070055 // Cost function for the secondary solver finding out where the whole map fits
56 // in the world
57 template <typename S>
58 bool operator()(const S *const translation, const S *const rotation,
59 S *residual) const;
60
Milind Upadhyay7c205222022-11-16 18:20:58 -080061 private:
Milind Upadhyay7c205222022-11-16 18:20:58 -080062 // Constructs the nonlinear least squares optimization problem from the
63 // pose graph constraints.
milind-u8f4e43e2023-04-09 17:11:19 -070064 void BuildTargetPoseOptimizationProblem(
Milind Upadhyayc5beba12022-12-17 17:41:20 -080065 const ceres::examples::VectorOfConstraints &constraints,
66 ceres::examples::MapOfPoses *poses, ceres::Problem *problem);
Milind Upadhyay7c205222022-11-16 18:20:58 -080067
milind-u8f4e43e2023-04-09 17:11:19 -070068 // Constructs the nonlinear least squares optimization problem for the solved
69 // -> actual pose solver.
70 void BuildMapFittingOptimizationProblem(ceres::Problem *problem);
71
Milind Upadhyay7c205222022-11-16 18:20:58 -080072 // Returns true if the solve was successful.
73 bool SolveOptimizationProblem(ceres::Problem *problem);
74
milind-u8f4e43e2023-04-09 17:11:19 -070075 ceres::examples::MapOfPoses ideal_target_poses_;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080076 ceres::examples::MapOfPoses target_poses_;
77 ceres::examples::VectorOfConstraints target_constraints_;
milind-u8f4e43e2023-04-09 17:11:19 -070078
79 // Transformation moving the target map we solved for to where it actually
80 // should be in the world
81 Eigen::Translation3d T_frozen_actual_;
82 Eigen::Quaterniond R_frozen_actual_;
83
84 mutable VisualizeRobot vis_robot_;
Milind Upadhyay7c205222022-11-16 18:20:58 -080085};
86
Milind Upadhyayc5beba12022-12-17 17:41:20 -080087// Utility functions for dealing with ceres::examples::Pose3d structs
Milind Upadhyay7c205222022-11-16 18:20:58 -080088class PoseUtils {
89 public:
Milind Upadhyayc5beba12022-12-17 17:41:20 -080090 // Embeds a 3d pose into an affine transformation
91 static Eigen::Affine3d Pose3dToAffine3d(
92 const ceres::examples::Pose3d &pose3d);
93 // Inverse of above function
94 static ceres::examples::Pose3d Affine3dToPose3d(const Eigen::Affine3d &H);
Milind Upadhyay7c205222022-11-16 18:20:58 -080095
96 // Computes pose_2 relative to pose_1. This is equivalent to (pose_1^-1 *
97 // pose_2)
Milind Upadhyayc5beba12022-12-17 17:41:20 -080098 static ceres::examples::Pose3d ComputeRelativePose(
99 const ceres::examples::Pose3d &pose_1,
100 const ceres::examples::Pose3d &pose_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800101
102 // Computes pose_2 given a pose_1 and pose_2 relative to pose_1. This is
103 // equivalent to (pose_1 * pose_2_relative)
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800104 static ceres::examples::Pose3d ComputeOffsetPose(
105 const ceres::examples::Pose3d &pose_1,
106 const ceres::examples::Pose3d &pose_2_relative);
107
108 // Converts a rotation with roll, pitch, and yaw into a quaternion
109 static Eigen::Quaterniond EulerAnglesToQuaternion(const Eigen::Vector3d &rpy);
110 // Inverse of above function
111 static Eigen::Vector3d QuaternionToEulerAngles(const Eigen::Quaterniond &q);
112 // Converts a 3d rotation matrix into a rotation with roll, pitch, and yaw
113 static Eigen::Vector3d RotationMatrixToEulerAngles(const Eigen::Matrix3d &R);
milind-u3f5f83c2023-01-29 15:23:51 -0800114
115 // Builds a TargetPoseFbs from a TargetPose
116 static flatbuffers::Offset<TargetPoseFbs> TargetPoseToFbs(
117 const TargetMapper::TargetPose &target_pose,
118 flatbuffers::FlatBufferBuilder *fbb);
119 // Converts a TargetPoseFbs to a TargetPose
120 static TargetMapper::TargetPose TargetPoseFromFbs(
121 const TargetPoseFbs &target_pose_fbs);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800122};
123
124// Transforms robot position and target detection data into target constraints
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800125// to be used for mapping.
Milind Upadhyay7c205222022-11-16 18:20:58 -0800126class DataAdapter {
127 public:
Milind Upadhyay7c205222022-11-16 18:20:58 -0800128 // Pairs target detection with a time point
129 struct TimestampedDetection {
130 aos::distributed_clock::time_point time;
131 // Pose of target relative to robot
132 Eigen::Affine3d H_robot_target;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800133 // Horizontal distance from camera to target, used for confidence
134 // calculation
135 double distance_from_camera;
milind-ud62f80a2023-03-04 16:37:09 -0800136 // A measure of how much distortion affected this detection from 0-1.
137 double distortion_factor;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800138 TargetMapper::TargetId id;
139 };
140
Milind Upadhyayec493912022-12-18 21:33:15 -0800141 // Pairs consecutive target detections that are not too far apart in time into
142 // constraints. Meant to be used on a system without a position measurement.
143 // Assumes timestamped_target_detections is in chronological order.
144 // max_dt is the maximum time between two target detections to match them up.
145 // If too much time passes, the recoding device (box of pis) could have moved
146 // too much
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800147 static ceres::examples::VectorOfConstraints MatchTargetDetections(
Milind Upadhyayec493912022-12-18 21:33:15 -0800148 const std::vector<TimestampedDetection> &timestamped_target_detections,
milind-u8791bed2023-03-04 14:45:52 -0800149 aos::distributed_clock::duration max_dt = std::chrono::milliseconds(10));
Milind Upadhyayec493912022-12-18 21:33:15 -0800150
Milind Upadhyay7c205222022-11-16 18:20:58 -0800151 // Computes inverse of covariance matrix, assuming there was a target
152 // detection between robot movement over the given time period. Ceres calls
153 // this matrix the "information"
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800154 static TargetMapper::ConfidenceMatrix ComputeConfidence(
milind-ud62f80a2023-03-04 16:37:09 -0800155 const TimestampedDetection &detection_start,
156 const TimestampedDetection &detection_end);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800157
Milind Upadhyay7c205222022-11-16 18:20:58 -0800158 // Computes the constraint between the start and end pose of the targets: the
159 // relative pose between the start and end target locations in the frame of
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800160 // the start target.
161 static ceres::examples::Constraint3d ComputeTargetConstraint(
Milind Upadhyayec493912022-12-18 21:33:15 -0800162 const TimestampedDetection &target_detection_start,
163 const TimestampedDetection &target_detection_end,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800164 const TargetMapper::ConfidenceMatrix &confidence);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800165};
166
milind-ufbc5c812023-04-06 21:24:29 -0700167} // namespace frc971::vision
168
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800169std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose);
170std::ostream &operator<<(std::ostream &os,
171 ceres::examples::Constraint3d constraint);
172
Milind Upadhyay7c205222022-11-16 18:20:58 -0800173#endif // FRC971_VISION_TARGET_MAPPER_H_