39 units::meter_t leftDistance,
40 units::meter_t rightDistance,
58 units::meter_t rightDistance,
const Pose2d& pose) {
61 m_gyroOffset = m_pose.Rotation() - gyroAngle;
63 m_prevLeftDistance = leftDistance;
64 m_prevRightDistance = rightDistance;
85 units::meter_t rightDistance);
93 units::meter_t m_prevLeftDistance = 0_m;
94 units::meter_t m_prevRightDistance = 0_m;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Class for differential drive odometry.
Definition: DifferentialDriveOdometry.h:25
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.
const Pose2d & GetPose() const
Returns the position of the robot on the field.
Definition: DifferentialDriveOdometry.h:71
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:57
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:25
constexpr const Rotation2d & Rotation() const
Returns the underlying rotation.
Definition: Pose2d.h:105
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:26
Definition: AprilTagFieldLayout.h:22