24template <
typename WheelSpeeds, WheelPositions WheelPositions>
54 m_gyroOffset = m_pose.Rotation() - gyroAngle;
55 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: Kinematics.h:23
Class for odometry.
Definition: Odometry.h:25
void ResetPosition(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions, const Pose2d &pose)
Resets the robot's position on the field.
Definition: Odometry.h:50
const Pose2d & GetPose() const
Returns the position of the robot on the field.
Definition: Odometry.h:62
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: WheelPositions.h:11
Definition: AprilTagPoseEstimator.h:15