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.Pose3d; 009import edu.wpi.first.math.geometry.Rotation2d; 010import edu.wpi.first.math.geometry.Rotation3d; 011import edu.wpi.first.math.geometry.Translation2d; 012import edu.wpi.first.math.geometry.Translation3d; 013import edu.wpi.first.math.geometry.Twist3d; 014 015/** 016 * Class for odometry. Robot code should not use this directly- Instead, use the particular type for 017 * your drivetrain (e.g., {@link DifferentialDriveOdometry3d}). Odometry allows you to track the 018 * robot's position on the field over the course of a match using readings from encoders and a 019 * gyroscope. 020 * 021 * <p>This class is meant to be an easy replacement for {@link Odometry}, only requiring the 022 * addition of appropriate conversions between 2D and 3D versions of geometry classes. (See {@link 023 * Pose3d#Pose3d(Pose2d)}, {@link Rotation3d#Rotation3d(Rotation2d)}, {@link 024 * Translation3d#Translation3d(Translation2d)}, and {@link Pose3d#toPose2d()}.) 025 * 026 * <p>Teams can use odometry during the autonomous period for complex tasks like path following. 027 * Furthermore, odometry can be used for latency compensation when using computer-vision systems. 028 * 029 * @param <T> Wheel positions type. 030 */ 031public class Odometry3d<T> { 032 private final Kinematics<?, T> m_kinematics; 033 private Pose3d m_poseMeters; 034 035 // Applying a rotation intrinsically to the measured gyro angle should cause the corrected angle 036 // to be rotated intrinsically in the same way, so the measured gyro angle must be applied 037 // intrinsically. This is equivalent to applying the offset extrinsically to the measured gyro 038 // angle. 039 private Rotation3d m_gyroOffset; 040 041 // Always equal to m_poseMeters.getRotation() 042 private Rotation3d m_previousAngle; 043 044 private final T m_previousWheelPositions; 045 046 /** 047 * Constructs an Odometry3d object. 048 * 049 * @param kinematics The kinematics of the drivebase. 050 * @param gyroAngle The angle reported by the gyroscope. 051 * @param wheelPositions The current encoder readings. 052 * @param initialPoseMeters The starting position of the robot on the field. 053 */ 054 public Odometry3d( 055 Kinematics<?, T> kinematics, 056 Rotation3d gyroAngle, 057 T wheelPositions, 058 Pose3d initialPoseMeters) { 059 m_kinematics = kinematics; 060 m_poseMeters = initialPoseMeters; 061 // When applied extrinsically, m_gyroOffset cancels the current gyroAngle and 062 // then rotates to m_poseMeters.getRotation() 063 m_gyroOffset = gyroAngle.unaryMinus().rotateBy(m_poseMeters.getRotation()); 064 m_previousAngle = m_poseMeters.getRotation(); 065 m_previousWheelPositions = m_kinematics.copy(wheelPositions); 066 } 067 068 /** 069 * Resets the robot's position on the field. 070 * 071 * <p>The gyroscope angle does not need to be reset here on the user's robot code. The library 072 * automatically takes care of offsetting the gyro angle. 073 * 074 * @param gyroAngle The angle reported by the gyroscope. 075 * @param wheelPositions The current encoder readings. 076 * @param poseMeters The position on the field that your robot is at. 077 */ 078 public void resetPosition(Rotation3d gyroAngle, T wheelPositions, Pose3d poseMeters) { 079 m_poseMeters = poseMeters; 080 m_previousAngle = m_poseMeters.getRotation(); 081 // When applied extrinsically, m_gyroOffset cancels the current gyroAngle and 082 // then rotates to m_poseMeters.getRotation() 083 m_gyroOffset = gyroAngle.unaryMinus().rotateBy(m_poseMeters.getRotation()); 084 m_kinematics.copyInto(wheelPositions, m_previousWheelPositions); 085 } 086 087 /** 088 * Resets the pose. 089 * 090 * @param poseMeters The pose to reset to. 091 */ 092 public void resetPose(Pose3d poseMeters) { 093 // Cancel the previous m_pose.Rotation() and then rotate to the new angle 094 m_gyroOffset = 095 m_gyroOffset 096 .rotateBy(m_poseMeters.getRotation().unaryMinus()) 097 .rotateBy(poseMeters.getRotation()); 098 m_poseMeters = poseMeters; 099 m_previousAngle = m_poseMeters.getRotation(); 100 } 101 102 /** 103 * Resets the translation of the pose. 104 * 105 * @param translation The translation to reset to. 106 */ 107 public void resetTranslation(Translation3d translation) { 108 m_poseMeters = new Pose3d(translation, m_poseMeters.getRotation()); 109 } 110 111 /** 112 * Resets the rotation of the pose. 113 * 114 * @param rotation The rotation to reset to. 115 */ 116 public void resetRotation(Rotation3d rotation) { 117 // Cancel the previous m_pose.Rotation() and then rotate to the new angle 118 m_gyroOffset = 119 m_gyroOffset.rotateBy(m_poseMeters.getRotation().unaryMinus()).rotateBy(rotation); 120 m_poseMeters = new Pose3d(m_poseMeters.getTranslation(), rotation); 121 m_previousAngle = m_poseMeters.getRotation(); 122 } 123 124 /** 125 * Returns the position of the robot on the field. 126 * 127 * @return The pose of the robot (x, y, and z are in meters). 128 */ 129 public Pose3d getPoseMeters() { 130 return m_poseMeters; 131 } 132 133 /** 134 * Updates the robot's position on the field using forward kinematics and integration of the pose 135 * over time. This method takes in an angle parameter which is used instead of the angular rate 136 * that is calculated from forward kinematics, in addition to the current distance measurement at 137 * each wheel. 138 * 139 * @param gyroAngle The angle reported by the gyroscope. 140 * @param wheelPositions The current encoder readings. 141 * @return The new pose of the robot. 142 */ 143 public Pose3d update(Rotation3d gyroAngle, T wheelPositions) { 144 var angle = gyroAngle.rotateBy(m_gyroOffset); 145 var angle_difference = angle.minus(m_previousAngle).toVector(); 146 147 var twist2d = m_kinematics.toTwist2d(m_previousWheelPositions, wheelPositions); 148 var twist = 149 new Twist3d( 150 twist2d.dx, 151 twist2d.dy, 152 0, 153 angle_difference.get(0), 154 angle_difference.get(1), 155 angle_difference.get(2)); 156 157 var newPose = m_poseMeters.exp(twist); 158 159 m_kinematics.copyInto(wheelPositions, m_previousWheelPositions); 160 m_previousAngle = angle; 161 m_poseMeters = new Pose3d(newPose.getTranslation(), angle); 162 163 return m_poseMeters; 164 } 165}