001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package edu.wpi.first.math.kinematics;
006
007import edu.wpi.first.math.geometry.Pose2d;
008import edu.wpi.first.math.geometry.Rotation2d;
009
010/**
011 * Class for odometry. Robot code should not use this directly- Instead, use the particular type for
012 * your drivetrain (e.g., {@link DifferentialDriveOdometry}). Odometry allows you to track the
013 * robot's position on the field over the course of a match using readings from encoders and a
014 * gyroscope.
015 *
016 * <p>Teams can use odometry during the autonomous period for complex tasks like path following.
017 * Furthermore, odometry can be used for latency compensation when using computer-vision systems.
018 */
019public class Odometry<T extends WheelPositions<T>> {
020  private final Kinematics<?, T> m_kinematics;
021  private Pose2d m_poseMeters;
022
023  private Rotation2d m_gyroOffset;
024  private Rotation2d m_previousAngle;
025  private T m_previousWheelPositions;
026
027  /**
028   * Constructs an Odometry object.
029   *
030   * @param kinematics The kinematics of the drivebase.
031   * @param gyroAngle The angle reported by the gyroscope.
032   * @param wheelPositions The current encoder readings.
033   * @param initialPoseMeters The starting position of the robot on the field.
034   */
035  public Odometry(
036      Kinematics<?, T> kinematics,
037      Rotation2d gyroAngle,
038      T wheelPositions,
039      Pose2d initialPoseMeters) {
040    m_kinematics = kinematics;
041    m_poseMeters = initialPoseMeters;
042    m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle);
043    m_previousAngle = m_poseMeters.getRotation();
044    m_previousWheelPositions = wheelPositions.copy();
045  }
046
047  /**
048   * Resets the robot's position on the field.
049   *
050   * <p>The gyroscope angle does not need to be reset here on the user's robot code. The library
051   * automatically takes care of offsetting the gyro angle.
052   *
053   * @param gyroAngle The angle reported by the gyroscope.
054   * @param wheelPositions The current encoder readings.
055   * @param poseMeters The position on the field that your robot is at.
056   */
057  public void resetPosition(Rotation2d gyroAngle, T wheelPositions, Pose2d poseMeters) {
058    m_poseMeters = poseMeters;
059    m_previousAngle = m_poseMeters.getRotation();
060    m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle);
061    m_previousWheelPositions = wheelPositions.copy();
062  }
063
064  /**
065   * Returns the position of the robot on the field.
066   *
067   * @return The pose of the robot (x and y are in meters).
068   */
069  public Pose2d getPoseMeters() {
070    return m_poseMeters;
071  }
072
073  /**
074   * Updates the robot's position on the field using forward kinematics and integration of the pose
075   * over time. This method takes in an angle parameter which is used instead of the angular rate
076   * that is calculated from forward kinematics, in addition to the current distance measurement at
077   * each wheel.
078   *
079   * @param gyroAngle The angle reported by the gyroscope.
080   * @param wheelPositions The current encoder readings.
081   * @return The new pose of the robot.
082   */
083  public Pose2d update(Rotation2d gyroAngle, T wheelPositions) {
084    T wheelDeltas = wheelPositions.minus(m_previousWheelPositions);
085
086    var angle = gyroAngle.plus(m_gyroOffset);
087
088    var twist = m_kinematics.toTwist2d(wheelDeltas);
089    twist.dtheta = angle.minus(m_previousAngle).getRadians();
090
091    var newPose = m_poseMeters.exp(twist);
092
093    m_previousWheelPositions = wheelPositions.copy();
094    m_previousAngle = angle;
095    m_poseMeters = new Pose2d(newPose.getTranslation(), angle);
096
097    return m_poseMeters;
098  }
099}