30 :
public Odometry<DifferentialDriveWheelSpeeds,
31 DifferentialDriveWheelPositions> {
45 units::meter_t leftDistance,
46 units::meter_t rightDistance,
64 units::meter_t rightDistance,
const Pose2d& pose) {
84 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
const Pose2d & Update(const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance)
Updates the robot position on the field using distance measurements from encoders.
Definition: DifferentialDriveOdometry.h:83
DifferentialDriveOdometry(const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose2d &initialPose=Pose2d{})
Constructs a DifferentialDriveOdometry object.
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: DifferentialDriveOdometry.h:63
Class for odometry.
Definition: Odometry.h:28
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
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