37template <
typename WheelSpeeds, WheelPositions WheelPositions>
69 void SetVisionMeasurementStdDevs(
82 void ResetPosition(
const Rotation2d& gyroAngle,
90 Pose2d GetEstimatedPosition()
const;
112 void AddVisionMeasurement(
const Pose2d& visionRobotPose,
113 units::second_t timestamp);
144 const Pose2d& visionRobotPose, units::second_t timestamp,
146 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
147 AddVisionMeasurement(visionRobotPose, timestamp);
172 Pose2d UpdateWithTime(units::second_t currentTime,
177 struct InterpolationRecord {
193 bool operator==(
const InterpolationRecord& other)
const =
default;
201 bool operator!=(
const InterpolationRecord& other)
const =
default;
211 InterpolationRecord Interpolate(
213 InterpolationRecord endValue,
double i)
const;
216 static constexpr units::second_t kBufferDuration = 1.5_s;
218 Kinematics<WheelSpeeds, WheelPositions>& m_kinematics;
219 Odometry<WheelSpeeds, WheelPositions>& m_odometry;
221 Eigen::Matrix3d m_visionK = Eigen::Matrix3d::Zero();
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);
#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