WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
frc::SwerveDriveOdometry< NumModules > Class Template Reference

Class for swerve drive odometry. More...

#include <frc/kinematics/SwerveDriveOdometry.h>

Inheritance diagram for frc::SwerveDriveOdometry< NumModules >:
frc::Odometry< wpi::array< SwerveModuleState, NumModules >, wpi::array< SwerveModulePosition, NumModules > >

Public Member Functions

 SwerveDriveOdometry (SwerveDriveKinematics< NumModules > kinematics, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose=Pose2d{})
 Constructs a SwerveDriveOdometry object.
 
- Public Member Functions inherited from frc::Odometry< wpi::array< SwerveModuleState, NumModules >, wpi::array< SwerveModulePosition, NumModules > >
 Odometry (const Kinematics< wpi::array< SwerveModuleState, NumModules >, wpi::array< SwerveModulePosition, NumModules > > &kinematics, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &wheelPositions, const Pose2d &initialPose=Pose2d{})
 Constructs an Odometry object.
 
void ResetPosition (const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &wheelPositions, const Pose2d &pose)
 Resets the robot's position on the field.
 
void ResetPose (const Pose2d &pose)
 Resets the pose.
 
void ResetTranslation (const Translation2d &translation)
 Resets the translation of the pose.
 
void ResetRotation (const Rotation2d &rotation)
 Resets the rotation of the pose.
 
const Pose2dGetPose () const
 Returns the position of the robot on the field.
 
const Pose2dUpdate (const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &wheelPositions)
 Updates the robot's position on the field using forward kinematics and integration of the pose over time.
 

Detailed Description

template<size_t NumModules>
class frc::SwerveDriveOdometry< NumModules >

Class for swerve drive odometry.

Odometry allows you to track the robot's position on the field over a course of a match using readings from your swerve drive encoders and swerve azimuth encoders.

Teams can use odometry during the autonomous period for complex tasks like path following. Furthermore, odometry can be used for latency compensation when using computer-vision systems.

Constructor & Destructor Documentation

◆ SwerveDriveOdometry()

template<size_t NumModules>
frc::SwerveDriveOdometry< NumModules >::SwerveDriveOdometry ( SwerveDriveKinematics< NumModules > kinematics,
const Rotation2d & gyroAngle,
const wpi::array< SwerveModulePosition, NumModules > & modulePositions,
const Pose2d & initialPose = Pose2d{} )
inline

Constructs a SwerveDriveOdometry object.

Parameters
kinematicsThe swerve drive kinematics for your drivetrain.
gyroAngleThe angle reported by the gyroscope.
modulePositionsThe wheel positions reported by each module.
initialPoseThe starting position of the robot on the field.

The documentation for this class was generated from the following file: