WPILibC++ 2025.3.1
Loading...
Searching...
No Matches
DifferentialDrivePoseEstimator.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 <wpi/SymbolExports.h>
8#include <wpi/array.h>
9
11#include "frc/geometry/Pose2d.h"
15#include "units/time.h"
16
17namespace frc {
18/**
19 * This class wraps Differential Drive Odometry to fuse latency-compensated
20 * vision measurements with differential drive encoder measurements. It will
21 * correct for noisy vision measurements and encoder drift. It is intended to be
22 * an easy drop-in for DifferentialDriveOdometry. In fact, if you never call
23 * AddVisionMeasurement(), and only call Update(), this will behave exactly the
24 * same as DifferentialDriveOdometry.
25 *
26 * Update() should be called every robot loop (if your robot loops are faster or
27 * slower than the default of 20 ms, then you should change the nominal delta
28 * time via the constructor).
29 *
30 * AddVisionMeasurement() can be called as infrequently as you want; if you
31 * never call it, then this class will behave like regular encoder odometry.
32 */
34 : public PoseEstimator<DifferentialDriveWheelSpeeds,
35 DifferentialDriveWheelPositions> {
36 public:
37 /**
38 * Constructs a DifferentialDrivePoseEstimator with default standard
39 * deviations for the model and vision measurements.
40 *
41 * The default standard deviations of the model states are
42 * 0.02 meters for x, 0.02 meters for y, and 0.01 radians for heading.
43 * The default standard deviations of the vision measurements are
44 * 0.1 meters for x, 0.1 meters for y, and 0.1 radians for heading.
45 *
46 * @param kinematics A correctly-configured kinematics object for your
47 * drivetrain.
48 * @param gyroAngle The gyro angle of the robot.
49 * @param leftDistance The distance traveled by the left encoder.
50 * @param rightDistance The distance traveled by the right encoder.
51 * @param initialPose The estimated initial pose.
52 */
54 const Rotation2d& gyroAngle,
55 units::meter_t leftDistance,
56 units::meter_t rightDistance,
57 const Pose2d& initialPose);
58
59 /**
60 * Constructs a DifferentialDrivePoseEstimator.
61 *
62 * @param kinematics A correctly-configured kinematics object for your
63 * drivetrain.
64 * @param gyroAngle The gyro angle of the robot.
65 * @param leftDistance The distance traveled by the left encoder.
66 * @param rightDistance The distance traveled by the right encoder.
67 * @param initialPose The estimated initial pose.
68 * @param stateStdDevs Standard deviations of the pose estimate (x position in
69 * meters, y position in meters, and heading in radians). Increase these
70 * numbers to trust your state estimate less.
71 * @param visionMeasurementStdDevs Standard deviations of the vision pose
72 * measurement (x position in meters, y position in meters, and heading in
73 * radians). Increase these numbers to trust the vision pose measurement
74 * less.
75 */
77 DifferentialDriveKinematics& kinematics, const Rotation2d& gyroAngle,
78 units::meter_t leftDistance, units::meter_t rightDistance,
79 const Pose2d& initialPose, const wpi::array<double, 3>& stateStdDevs,
80 const wpi::array<double, 3>& visionMeasurementStdDevs);
81
82 /**
83 * Resets the robot's position on the field.
84 *
85 * @param gyroAngle The current gyro angle.
86 * @param leftDistance The distance traveled by the left encoder.
87 * @param rightDistance The distance traveled by the right encoder.
88 * @param pose The estimated pose of the robot on the field.
89 */
90 void ResetPosition(const Rotation2d& gyroAngle, units::meter_t leftDistance,
91 units::meter_t rightDistance, const Pose2d& pose) {
92 PoseEstimator::ResetPosition(gyroAngle, {leftDistance, rightDistance},
93 pose);
94 }
95
96 /**
97 * Updates the pose estimator with wheel encoder and gyro information. This
98 * should be called every loop.
99 *
100 * @param gyroAngle The current gyro angle.
101 * @param leftDistance The distance traveled by the left encoder.
102 * @param rightDistance The distance traveled by the right encoder.
103 *
104 * @return The estimated pose of the robot.
105 */
106 Pose2d Update(const Rotation2d& gyroAngle, units::meter_t leftDistance,
107 units::meter_t rightDistance) {
108 return PoseEstimator::Update(gyroAngle, {leftDistance, rightDistance});
109 }
110
111 /**
112 * Updates the pose estimator with wheel encoder and gyro information. This
113 * should be called every loop.
114 *
115 * @param currentTime The time at which this method was called.
116 * @param gyroAngle The current gyro angle.
117 * @param leftDistance The distance traveled by the left encoder.
118 * @param rightDistance The distance traveled by the right encoder.
119 *
120 * @return The estimated pose of the robot.
121 */
122 Pose2d UpdateWithTime(units::second_t currentTime,
123 const Rotation2d& gyroAngle,
124 units::meter_t leftDistance,
125 units::meter_t rightDistance) {
126 return PoseEstimator::UpdateWithTime(currentTime, gyroAngle,
127 {leftDistance, rightDistance});
128 }
129
130 private:
131 DifferentialDriveOdometry m_odometryImpl;
132};
133
134} // namespace frc
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition DifferentialDriveKinematics.h:31
Class for differential drive odometry.
Definition DifferentialDriveOdometry.h:31
This class wraps Differential Drive Odometry to fuse latency-compensated vision measurements with dif...
Definition DifferentialDrivePoseEstimator.h:35
Pose2d UpdateWithTime(units::second_t currentTime, const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance)
Updates the pose estimator with wheel encoder and gyro information.
Definition DifferentialDrivePoseEstimator.h:122
Pose2d Update(const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance)
Updates the pose estimator with wheel encoder and gyro information.
Definition DifferentialDrivePoseEstimator.h:106
void ResetPosition(const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose2d &pose)
Resets the robot's position on the field.
Definition DifferentialDrivePoseEstimator.h:90
DifferentialDrivePoseEstimator(DifferentialDriveKinematics &kinematics, const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose2d &initialPose, const wpi::array< double, 3 > &stateStdDevs, const wpi::array< double, 3 > &visionMeasurementStdDevs)
Constructs a DifferentialDrivePoseEstimator.
DifferentialDrivePoseEstimator(DifferentialDriveKinematics &kinematics, const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose2d &initialPose)
Constructs a DifferentialDrivePoseEstimator with default standard deviations for the model and vision...
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
This class wraps odometry to fuse latency-compensated vision measurements with encoder measurements.
Definition PoseEstimator.h:43
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
Definition CAN.h:11