56 m_gyroOffset = m_pose.Rotation() - gyroAngle;
57 m_previousWheelPositions = wheelPositions;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition: MecanumDriveKinematics.h:42
Class for mecanum drive odometry.
Definition: MecanumDriveOdometry.h:26
const Pose2d & GetPose() const
Returns the position of the robot on the field.
Definition: MecanumDriveOdometry.h:64
MecanumDriveOdometry(MecanumDriveKinematics kinematics, const Rotation2d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose2d &initialPose=Pose2d{})
Constructs a MecanumDriveOdometry object.
const Pose2d & Update(const Rotation2d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions)
Updates the robot's position on the field using forward kinematics and integration of the pose over t...
void ResetPosition(const Rotation2d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose2d &pose)
Resets the robot's position on the field.
Definition: MecanumDriveOdometry.h:51
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
Represents the wheel speeds for a mecanum drive drivetrain.
Definition: MecanumDriveWheelPositions.h:15