30template <
size_t NumModules>
96 SwerveDriveOdometry<4>;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:25
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:26
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module ...
Definition: SwerveDriveKinematics.h:47
Class for swerve drive odometry.
Definition: SwerveDriveOdometry.h:31
const Pose2d & Update(const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions)
Updates the robot's position on the field using forward kinematics and integration of the pose over t...
Definition: SwerveDriveOdometry.inc:44
SwerveDriveOdometry(SwerveDriveKinematics< NumModules > kinematics, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose=Pose2d{})
Constructs a SwerveDriveOdometry object.
Definition: SwerveDriveOdometry.inc:12
void ResetPosition(const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &pose)
Resets the robot's position on the field.
Definition: SwerveDriveOdometry.inc:30
const Pose2d & GetPose() const
Returns the position of the robot on the field.
Definition: SwerveDriveOdometry.h:65
This class is a wrapper around std::array that does compile time size checking.
Definition: array.h:25
Definition: AprilTagFieldLayout.h:22
template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) LinearQuadraticRegulator< 1
constexpr empty_array_t empty_array
Definition: array.h:15