48template <
typename WheelSpeeds,
typename WheelPositions>
72 : m_odometry(odometry) {
73 for (
size_t i = 0; i < 4; ++i) {
74 m_q[i] = stateStdDevs[i] * stateStdDevs[i];
77 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
93 for (
size_t i = 0; i < 4; ++i) {
94 r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i];
99 for (
size_t row = 0; row < 4; ++row) {
100 if (m_q[row] == 0.0) {
101 m_visionK(row, row) = 0.0;
103 m_visionK(row, row) =
104 m_q[row] / (m_q[row] + std::sqrt(m_q[row] * r[row]));
107 double angle_gain = m_visionK(3, 3);
108 m_visionK(4, 4) = angle_gain;
109 m_visionK(5, 5) = angle_gain;
123 const WheelPositions& wheelPositions,
const Pose3d& pose) {
125 m_odometry.ResetPosition(gyroAngle, wheelPositions, pose);
126 m_odometryPoseBuffer.Clear();
127 m_visionUpdates.clear();
128 m_poseEstimate = m_odometry.GetPose();
137 m_odometry.ResetPose(pose);
138 m_odometryPoseBuffer.Clear();
139 m_visionUpdates.clear();
140 m_poseEstimate = m_odometry.GetPose();
149 m_odometry.ResetTranslation(translation);
150 m_odometryPoseBuffer.Clear();
151 m_visionUpdates.clear();
152 m_poseEstimate = m_odometry.GetPose();
161 m_odometry.ResetRotation(rotation);
162 m_odometryPoseBuffer.Clear();
163 m_visionUpdates.clear();
164 m_poseEstimate = m_odometry.GetPose();
181 std::optional<Pose3d>
SampleAt(units::second_t timestamp)
const {
183 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
190 units::second_t oldestOdometryTimestamp =
191 m_odometryPoseBuffer.GetInternalBuffer().front().first;
192 units::second_t newestOdometryTimestamp =
193 m_odometryPoseBuffer.GetInternalBuffer().back().first;
195 std::clamp(timestamp, oldestOdometryTimestamp, newestOdometryTimestamp);
199 if (m_visionUpdates.empty() || timestamp < m_visionUpdates.begin()->first) {
200 return m_odometryPoseBuffer.Sample(timestamp);
208 auto floorIter = m_visionUpdates.upper_bound(timestamp);
210 auto visionUpdate = floorIter->second;
213 auto odometryEstimate = m_odometryPoseBuffer.Sample(timestamp);
217 if (odometryEstimate) {
218 return visionUpdate.Compensate(*odometryEstimate);
244 units::second_t timestamp) {
247 if (m_odometryPoseBuffer.GetInternalBuffer().empty() ||
248 m_odometryPoseBuffer.GetInternalBuffer().front().first -
255 CleanUpVisionUpdates();
259 auto odometrySample = m_odometryPoseBuffer.Sample(timestamp);
261 if (!odometrySample) {
267 auto visionSample = SampleAt(timestamp);
275 auto twist = visionSample.value().Log(visionRobotPose);
282 twist.dz.value(), twist.rx.value(),
283 twist.ry.value(), twist.rz.value()};
287 units::meter_t{k_times_twist(0)}, units::meter_t{k_times_twist(1)},
288 units::meter_t{k_times_twist(2)}, units::radian_t{k_times_twist(3)},
289 units::radian_t{k_times_twist(4)}, units::radian_t{k_times_twist(5)}};
292 VisionUpdate visionUpdate{visionSample->Exp(scaledTwist), *odometrySample};
293 m_visionUpdates[timestamp] = visionUpdate;
296 auto firstAfter = m_visionUpdates.upper_bound(timestamp);
297 m_visionUpdates.erase(firstAfter, m_visionUpdates.end());
301 m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose());
333 const Pose3d& visionRobotPose, units::second_t timestamp,
335 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
336 AddVisionMeasurement(visionRobotPose, timestamp);
349 const WheelPositions& wheelPositions) {
366 const WheelPositions& wheelPositions) {
367 auto odometryEstimate = m_odometry.Update(gyroAngle, wheelPositions);
369 m_odometryPoseBuffer.AddSample(currentTime, odometryEstimate);
371 if (m_visionUpdates.empty()) {
372 m_poseEstimate = odometryEstimate;
374 auto visionUpdate = m_visionUpdates.rbegin()->second;
375 m_poseEstimate = visionUpdate.Compensate(odometryEstimate);
378 return GetEstimatedPosition();
385 void CleanUpVisionUpdates() {
387 if (m_odometryPoseBuffer.GetInternalBuffer().empty()) {
392 units::second_t oldestOdometryTimestamp =
393 m_odometryPoseBuffer.GetInternalBuffer().front().first;
396 if (m_visionUpdates.empty() ||
397 oldestOdometryTimestamp < m_visionUpdates.begin()->first) {
406 auto newestNeededVisionUpdate =
407 m_visionUpdates.upper_bound(oldestOdometryTimestamp);
408 --newestNeededVisionUpdate;
411 m_visionUpdates.erase(m_visionUpdates.begin(), newestNeededVisionUpdate);
414 struct VisionUpdate {
429 Pose3d Compensate(
const Pose3d& pose)
const {
430 auto delta = pose - odometryPose;
431 return visionPose + delta;
435 static constexpr units::second_t kBufferDuration = 1.5_s;
437 Odometry3d<WheelSpeeds, WheelPositions>& m_odometry;
442 TimeInterpolatableBuffer<Pose3d> m_odometryPoseBuffer{kBufferDuration};
446 std::map<units::second_t, VisionUpdate> m_visionUpdates;
448 Pose3d m_poseEstimate;
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition Kinematics.h:25
Class for odometry.
Definition Odometry3d.h:33
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.h:28
This class wraps odometry to fuse latency-compensated vision measurements with encoder measurements.
Definition PoseEstimator3d.h:49
void ResetRotation(const Rotation3d &rotation)
Resets the robot's rotation.
Definition PoseEstimator3d.h:160
PoseEstimator3d(Kinematics< WheelSpeeds, WheelPositions > &kinematics, Odometry3d< WheelSpeeds, WheelPositions > &odometry, const wpi::array< double, 4 > &stateStdDevs, const wpi::array< double, 4 > &visionMeasurementStdDevs)
Constructs a PoseEstimator3d.
Definition PoseEstimator3d.h:68
Pose3d UpdateWithTime(units::second_t currentTime, const Rotation3d &gyroAngle, const WheelPositions &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition PoseEstimator3d.h:364
void ResetTranslation(const Translation3d &translation)
Resets the robot's translation.
Definition PoseEstimator3d.h:148
std::optional< Pose3d > SampleAt(units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
Definition PoseEstimator3d.h:181
void SetVisionMeasurementStdDevs(const wpi::array< double, 4 > &visionMeasurementStdDevs)
Sets the pose estimator's trust in vision measurements.
Definition PoseEstimator3d.h:90
void AddVisionMeasurement(const Pose3d &visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition PoseEstimator3d.h:243
void ResetPosition(const Rotation3d &gyroAngle, const WheelPositions &wheelPositions, const Pose3d &pose)
Resets the robot's position on the field.
Definition PoseEstimator3d.h:122
Pose3d Update(const Rotation3d &gyroAngle, const WheelPositions &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition PoseEstimator3d.h:348
void ResetPose(const Pose3d &pose)
Resets the robot's pose.
Definition PoseEstimator3d.h:136
void AddVisionMeasurement(const Pose3d &visionRobotPose, units::second_t timestamp, const wpi::array< double, 4 > &visionMeasurementStdDevs)
Adds a vision measurement to the Kalman Filter.
Definition PoseEstimator3d.h:332
Pose3d GetEstimatedPosition() const
Gets the estimated robot pose.
Definition PoseEstimator3d.h:172
A rotation in a 3D coordinate frame represented by a quaternion.
Definition Rotation3d.h:29
Represents a translation in 3D space.
Definition Translation3d.h:26
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
static units::second_t GetTimestamp()
Definition MathShared.h:79
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.h:21
Eigen::Vector< double, Size > Vectord
Definition EigenCore.h:12
constexpr empty_array_t empty_array
Definition array.h:16
A change in distance along a 3D arc since the last pose update.
Definition Twist3d.h:22