Robot Core Documentation
Loading...
Searching...
No Matches
edu.wpi.first.math.kinematics.SwerveDriveOdometry Class Reference

Public Member Functions

 SwerveDriveOdometry (SwerveDriveKinematics kinematics, Rotation2d gyroAngle, SwerveModulePosition[] modulePositions, Pose2d initialPose)
 
 SwerveDriveOdometry (SwerveDriveKinematics kinematics, Rotation2d gyroAngle, SwerveModulePosition[] modulePositions)
 
void resetPosition (Rotation2d gyroAngle, SwerveModulePosition[] modulePositions, Pose2d pose)
 
Pose2d update (Rotation2d gyroAngle, SwerveModulePosition[] modulePositions)
 

Detailed Description

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() [1/2]

edu.wpi.first.math.kinematics.SwerveDriveOdometry.SwerveDriveOdometry ( SwerveDriveKinematics kinematics,
Rotation2d gyroAngle,
SwerveModulePosition[] modulePositions,
Pose2d initialPose )

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.

◆ SwerveDriveOdometry() [2/2]

edu.wpi.first.math.kinematics.SwerveDriveOdometry.SwerveDriveOdometry ( SwerveDriveKinematics kinematics,
Rotation2d gyroAngle,
SwerveModulePosition[] modulePositions )

Constructs a SwerveDriveOdometry object with the default pose at the origin.

Parameters
kinematicsThe swerve drive kinematics for your drivetrain.
gyroAngleThe angle reported by the gyroscope.
modulePositionsThe wheel positions reported by each module.

Member Function Documentation

◆ resetPosition()

void edu.wpi.first.math.kinematics.SwerveDriveOdometry.resetPosition ( Rotation2d gyroAngle,
SwerveModulePosition[] modulePositions,
Pose2d pose )

Resets the robot's position on the field.

The gyroscope angle does not need to be reset here on the user's robot code. The library automatically takes care of offsetting the gyro angle.

Similarly, module positions do not need to be reset in user code.

Parameters
gyroAngleThe angle reported by the gyroscope.
modulePositionsThe wheel positions reported by each module.,
poseThe position on the field that your robot is at.

◆ update()

Pose2d edu.wpi.first.math.kinematics.SwerveDriveOdometry.update ( Rotation2d gyroAngle,
SwerveModulePosition[] modulePositions )

Updates the robot's position on the field using forward kinematics and integration of the pose over time. This method automatically calculates the current time to calculate period (difference between two timestamps). The period is used to calculate the change in distance from a velocity. This also takes in an angle parameter which is used instead of the angular rate that is calculated from forward kinematics.

Parameters
gyroAngleThe angle reported by the gyroscope.
modulePositionsThe current position of all swerve modules. Please provide the positions in the same order in which you instantiated your SwerveDriveKinematics.
Returns
The new pose of the robot.

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