WPILibC++ 2024.3.2
PoseEstimator.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <Eigen/Core>
8#include <wpi/SymbolExports.h>
9#include <wpi/array.h>
10
11#include "frc/geometry/Pose2d.h"
17#include "units/time.h"
18#include "wpimath/MathShared.h"
19
20namespace frc {
21/**
22 * This class wraps odometry to fuse latency-compensated
23 * vision measurements with encoder measurements. Robot code should not use this
24 * directly- Instead, use the particular type for your drivetrain (e.g.,
25 * DifferentialDrivePoseEstimator). It will correct for noisy vision
26 * measurements and encoder drift. It is intended to be an easy drop-in for
27 * Odometry.
28 *
29 * Update() should be called every robot loop.
30 *
31 * AddVisionMeasurement() can be called as infrequently as you want; if you
32 * never call it, then this class will behave like regular encoder odometry.
33 *
34 * @tparam WheelSpeeds Wheel speeds type.
35 * @tparam WheelPositions Wheel positions type.
36 */
37template <typename WheelSpeeds, WheelPositions WheelPositions>
39 public:
40 /**
41 * Constructs a PoseEstimator.
42 *
43 * @param kinematics A correctly-configured kinematics object for your
44 * drivetrain.
45 * @param odometry A correctly-configured odometry object for your drivetrain.
46 * @param stateStdDevs Standard deviations of the pose estimate (x position in
47 * meters, y position in meters, and heading in radians). Increase these
48 * numbers to trust your state estimate less.
49 * @param visionMeasurementStdDevs Standard deviations of the vision pose
50 * measurement (x position in meters, y position in meters, and heading in
51 * radians). Increase these numbers to trust the vision pose measurement
52 * less.
53 */
56 const wpi::array<double, 3>& stateStdDevs,
57 const wpi::array<double, 3>& visionMeasurementStdDevs);
58
59 /**
60 * Sets the pose estimator's trust in vision measurements. This might be used
61 * to change trust in vision measurements after the autonomous period, or to
62 * change trust as distance to a vision target increases.
63 *
64 * @param visionMeasurementStdDevs Standard deviations of the vision pose
65 * measurement (x position in meters, y position in meters, and heading in
66 * radians). Increase these numbers to trust the vision pose measurement
67 * less.
68 */
69 void SetVisionMeasurementStdDevs(
70 const wpi::array<double, 3>& visionMeasurementStdDevs);
71
72 /**
73 * Resets the robot's position on the field.
74 *
75 * The gyroscope angle does not need to be reset in the user's robot code.
76 * The library automatically takes care of offsetting the gyro angle.
77 *
78 * @param gyroAngle The current gyro angle.
79 * @param wheelPositions The distances traveled by the encoders.
80 * @param pose The estimated pose of the robot on the field.
81 */
82 void ResetPosition(const Rotation2d& gyroAngle,
83 const WheelPositions& wheelPositions, const Pose2d& pose);
84
85 /**
86 * Gets the estimated robot pose.
87 *
88 * @return The estimated robot pose in meters.
89 */
90 Pose2d GetEstimatedPosition() const;
91
92 /**
93 * Adds a vision measurement to the Kalman Filter. This will correct
94 * the odometry pose estimate while still accounting for measurement noise.
95 *
96 * This method can be called as infrequently as you want, as long as you are
97 * calling Update() every loop.
98 *
99 * To promote stability of the pose estimate and make it robust to bad vision
100 * data, we recommend only adding vision measurements that are already within
101 * one meter or so of the current pose estimate.
102 *
103 * @param visionRobotPose The pose of the robot as measured by the vision
104 * camera.
105 * @param timestamp The timestamp of the vision measurement in seconds. Note
106 * that if you don't use your own time source by calling UpdateWithTime(),
107 * then you must use a timestamp with an epoch since FPGA startup (i.e.,
108 * the epoch of this timestamp is the same epoch as
109 * frc::Timer::GetFPGATimestamp(). This means that you should use
110 * frc::Timer::GetFPGATimestamp() as your time source in this case.
111 */
112 void AddVisionMeasurement(const Pose2d& visionRobotPose,
113 units::second_t timestamp);
114
115 /**
116 * Adds a vision measurement to the Kalman Filter. This will correct
117 * the odometry pose estimate while still accounting for measurement noise.
118 *
119 * This method can be called as infrequently as you want, as long as you are
120 * calling Update() every loop.
121 *
122 * To promote stability of the pose estimate and make it robust to bad vision
123 * data, we recommend only adding vision measurements that are already within
124 * one meter or so of the current pose estimate.
125 *
126 * Note that the vision measurement standard deviations passed into this
127 * method will continue to apply to future measurements until a subsequent
128 * call to SetVisionMeasurementStdDevs() or this method.
129 *
130 * @param visionRobotPose The pose of the robot as measured by the vision
131 * camera.
132 * @param timestamp The timestamp of the vision measurement in seconds. Note
133 * that if you don't use your own time source by calling UpdateWithTime(),
134 * then you must use a timestamp with an epoch since FPGA startup (i.e.,
135 * the epoch of this timestamp is the same epoch as
136 * frc::Timer::GetFPGATimestamp(). This means that you should use
137 * frc::Timer::GetFPGATimestamp() as your time source in this case.
138 * @param visionMeasurementStdDevs Standard deviations of the vision pose
139 * measurement (x position in meters, y position in meters, and heading in
140 * radians). Increase these numbers to trust the vision pose measurement
141 * less.
142 */
144 const Pose2d& visionRobotPose, units::second_t timestamp,
145 const wpi::array<double, 3>& visionMeasurementStdDevs) {
146 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
147 AddVisionMeasurement(visionRobotPose, timestamp);
148 }
149
150 /**
151 * Updates the pose estimator with wheel encoder and gyro information. This
152 * should be called every loop.
153 *
154 * @param gyroAngle The current gyro angle.
155 * @param wheelPositions The distances traveled by the encoders.
156 *
157 * @return The estimated pose of the robot in meters.
158 */
159 Pose2d Update(const Rotation2d& gyroAngle,
160 const WheelPositions& wheelPositions);
161
162 /**
163 * Updates the pose estimator with wheel encoder and gyro information. This
164 * should be called every loop.
165 *
166 * @param currentTime The time at which this method was called.
167 * @param gyroAngle The current gyro angle.
168 * @param wheelPositions The distances traveled by the encoders.
169 *
170 * @return The estimated pose of the robot in meters.
171 */
172 Pose2d UpdateWithTime(units::second_t currentTime,
173 const Rotation2d& gyroAngle,
174 const WheelPositions& wheelPositions);
175
176 private:
177 struct InterpolationRecord {
178 // The pose observed given the current sensor inputs and the previous pose.
179 Pose2d pose;
180
181 // The current gyroscope angle.
182 Rotation2d gyroAngle;
183
184 // The distances traveled by the wheels.
185 WheelPositions wheelPositions;
186
187 /**
188 * Checks equality between this InterpolationRecord and another object.
189 *
190 * @param other The other object.
191 * @return Whether the two objects are equal.
192 */
193 bool operator==(const InterpolationRecord& other) const = default;
194
195 /**
196 * Checks inequality between this InterpolationRecord and another object.
197 *
198 * @param other The other object.
199 * @return Whether the two objects are not equal.
200 */
201 bool operator!=(const InterpolationRecord& other) const = default;
202
203 /**
204 * Interpolates between two InterpolationRecords.
205 *
206 * @param endValue The end value for the interpolation.
207 * @param i The interpolant (fraction).
208 *
209 * @return The interpolated state.
210 */
211 InterpolationRecord Interpolate(
213 InterpolationRecord endValue, double i) const;
214 };
215
216 static constexpr units::second_t kBufferDuration = 1.5_s;
217
218 Kinematics<WheelSpeeds, WheelPositions>& m_kinematics;
219 Odometry<WheelSpeeds, WheelPositions>& m_odometry;
221 Eigen::Matrix3d m_visionK = Eigen::Matrix3d::Zero();
222
223 TimeInterpolatableBuffer<InterpolationRecord> m_poseBuffer{
224 kBufferDuration, [this](const InterpolationRecord& start,
225 const InterpolationRecord& end, double t) {
226 return start.Interpolate(this->m_kinematics, end, t);
227 }};
228};
229} // namespace frc
230
#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:23
Class for odometry.
Definition: Odometry.h:28
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
This class wraps odometry to fuse latency-compensated vision measurements with encoder measurements.
Definition: PoseEstimator.h:38
void AddVisionMeasurement(const Pose2d &visionRobotPose, units::second_t timestamp, const wpi::array< double, 3 > &visionMeasurementStdDevs)
Adds a vision measurement to the Kalman Filter.
Definition: PoseEstimator.h:143
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Definition: WheelPositions.h:11
Definition: AprilTagPoseEstimator.h:15
bool operator==(const Value &lhs, const Value &rhs)
constexpr bool operator!=(const UNIT_LIB_DEFAULT_TYPE lhs, const Units &rhs) noexcept
Definition: base.h:2716
constexpr empty_array_t empty_array
Definition: array.h:16