30 :
public Odometry<DifferentialDriveWheelSpeeds,
31 DifferentialDriveWheelPositions> {
45 units::meter_t leftDistance,
46 units::meter_t rightDistance,
64 units::meter_t rightDistance,
const Pose2d& pose) {
65 Odometry::ResetPosition(gyroAngle, {leftDistance, rightDistance}, pose);
80 units::meter_t rightDistance) {
81 return Odometry::Update(gyroAngle, {leftDistance, 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:31
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:79
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:30
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31