Class SwerveDriveOdometry

java.lang.Object
edu.wpi.first.math.kinematics.Odometry<SwerveDriveWheelPositions>
edu.wpi.first.math.kinematics.SwerveDriveOdometry

public class SwerveDriveOdometry
extends Odometry<SwerveDriveWheelPositions>
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​(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:
      gyroAngle - The angle reported by the gyroscope.
      modulePositions - The wheel positions reported by each module.,
      pose - The position on the field that your robot is at.
    • resetPosition

      public void resetPosition​(Rotation2d gyroAngle, SwerveDriveWheelPositions modulePositions, Pose2d pose)
      Description copied from class: Odometry
      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.

      Overrides:
      resetPosition in class Odometry<SwerveDriveWheelPositions>
      Parameters:
      gyroAngle - The angle reported by the gyroscope.
      modulePositions - The current encoder readings.
      pose - The position on the field that your robot is at.
    • update

      public Pose2d 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:
      gyroAngle - The angle reported by the gyroscope.
      modulePositions - The 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.
    • update

      public Pose2d update​(Rotation2d gyroAngle, SwerveDriveWheelPositions modulePositions)
      Description copied from class: Odometry
      Updates the robot's position on the field using forward kinematics and integration of the pose over time. This method takes in an angle parameter which is used instead of the angular rate that is calculated from forward kinematics, in addition to the current distance measurement at each wheel.
      Overrides:
      update in class Odometry<SwerveDriveWheelPositions>
      Parameters:
      gyroAngle - The angle reported by the gyroscope.
      modulePositions - The current encoder readings.
      Returns:
      The new pose of the robot.