Class Odometry<T extends WheelPositions<T>>

java.lang.Object
edu.wpi.first.math.kinematics.Odometry<T>
Direct Known Subclasses:
DifferentialDriveOdometry, MecanumDriveOdometry, SwerveDriveOdometry

public class Odometry<T extends WheelPositions<T>>
extends Object
Class for odometry. Robot code should not use this directly- Instead, use the particular type for your drivetrain (e.g., DifferentialDriveOdometry). Odometry allows you to track the robot's position on the field over the course of a match using readings from encoders and a gyroscope.

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

    • Odometry

      public Odometry​(Kinematics<?,​T> kinematics, Rotation2d gyroAngle, T wheelPositions, Pose2d initialPoseMeters)
      Constructs an Odometry object.
      Parameters:
      kinematics - The kinematics of the drivebase.
      gyroAngle - The angle reported by the gyroscope.
      wheelPositions - The current encoder readings.
      initialPoseMeters - The starting position of the robot on the field.
  • Method Details

    • resetPosition

      public void resetPosition​(Rotation2d gyroAngle, T wheelPositions, Pose2d poseMeters)
      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:
      gyroAngle - The angle reported by the gyroscope.
      wheelPositions - The current encoder readings.
      poseMeters - The position on the field that your robot is at.
    • getPoseMeters

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

      public Pose2d update​(Rotation2d gyroAngle, T wheelPositions)
      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.
      Parameters:
      gyroAngle - The angle reported by the gyroscope.
      wheelPositions - The current encoder readings.
      Returns:
      The new pose of the robot.