Class SwerveDriveOdometry

java.lang.Object
edu.wpi.first.math.kinematics.SwerveDriveOdometry

public class SwerveDriveOdometry
extends Object
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 Details

  • Method Details

    • resetPosition

      public void resetPosition​(Pose2d pose, Rotation2d gyroAngle)
      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.

      Parameters:
      pose - The position on the field that your robot is at.
      gyroAngle - The angle reported by the gyroscope.
    • getPoseMeters

      Returns the position of the robot on the field.
      Returns:
      The pose of the robot (x and y are in meters).
    • updateWithTime

      public Pose2d updateWithTime​(double currentTimeSeconds, Rotation2d gyroAngle, SwerveModuleState... moduleStates)
      Updates the robot's position on the field using forward kinematics and integration of the pose over time. This method takes in the current time as a parameter 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:
      currentTimeSeconds - The current time in seconds.
      gyroAngle - The angle reported by the gyroscope.
      moduleStates - The current state of all swerve modules. Please provide the states in the same order in which you instantiated your SwerveDriveKinematics.
      Returns:
      The new pose of the robot.
    • update

      public Pose2d update​(Rotation2d gyroAngle, SwerveModuleState... moduleStates)
      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:
      gyroAngle - The angle reported by the gyroscope.
      moduleStates - The current state of all swerve modules. Please provide the states in the same order in which you instantiated your SwerveDriveKinematics.
      Returns:
      The new pose of the robot.