35 DifferentialDriveWheelPositions> {
55 units::meter_t leftDistance,
56 units::meter_t rightDistance,
57 const Pose2d& initialPose);
78 units::meter_t leftDistance, units::meter_t rightDistance,
91 units::meter_t rightDistance,
const Pose2d& pose) {
94 ResetPosition(gyroAngle, {leftDistance, rightDistance}, pose);
108 units::meter_t rightDistance) {
112 {leftDistance, rightDistance});
128 units::meter_t leftDistance,
129 units::meter_t rightDistance) {
#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:29
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:126
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:107
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:25
This class wraps odometry to fuse latency-compensated vision measurements with encoder measurements.
Definition: PoseEstimator.h:35
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:26
Definition: AprilTagPoseEstimator.h:15
Represents the wheel positions for a differential drive drivetrain.
Definition: DifferentialDriveWheelPositions.h:16
Represents the wheel speeds for a differential drive drivetrain.
Definition: DifferentialDriveWheelSpeeds.h:15