Package edu.wpi.first.math.kinematics
Class MecanumDriveOdometry
java.lang.Object
edu.wpi.first.math.kinematics.MecanumDriveOdometry
public class MecanumDriveOdometry extends Object
Class for mecanum drive odometry. Odometry allows you to track the robot's position on the field
over a course of a match using readings from your mecanum wheel 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 Summary
Constructors Constructor Description MecanumDriveOdometry(MecanumDriveKinematics kinematics, Rotation2d gyroAngle)
Constructs a MecanumDriveOdometry object with the default pose at the origin.MecanumDriveOdometry(MecanumDriveKinematics kinematics, Rotation2d gyroAngle, Pose2d initialPoseMeters)
Constructs a MecanumDriveOdometry object. -
Method Summary
Modifier and Type Method Description Pose2d
getPoseMeters()
Returns the position of the robot on the field.void
resetPosition(Pose2d poseMeters, Rotation2d gyroAngle)
Resets the robot's position on the field.Pose2d
update(Rotation2d gyroAngle, MecanumDriveWheelSpeeds wheelSpeeds)
Updates the robot's position on the field using forward kinematics and integration of the pose over time.Pose2d
updateWithTime(double currentTimeSeconds, Rotation2d gyroAngle, MecanumDriveWheelSpeeds wheelSpeeds)
Updates the robot's position on the field using forward kinematics and integration of the pose over time.
-
Constructor Details
-
MecanumDriveOdometry
public MecanumDriveOdometry(MecanumDriveKinematics kinematics, Rotation2d gyroAngle, Pose2d initialPoseMeters)Constructs a MecanumDriveOdometry object.- Parameters:
kinematics
- The mecanum drive kinematics for your drivetrain.gyroAngle
- The angle reported by the gyroscope.initialPoseMeters
- The starting position of the robot on the field.
-
MecanumDriveOdometry
Constructs a MecanumDriveOdometry object with the default pose at the origin.- Parameters:
kinematics
- The mecanum drive kinematics for your drivetrain.gyroAngle
- The angle reported by the gyroscope.
-
-
Method Details
-
resetPosition
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:
poseMeters
- 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, MecanumDriveWheelSpeeds wheelSpeeds)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.wheelSpeeds
- The current wheel speeds.- Returns:
- The new pose of the robot.
-
update
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.wheelSpeeds
- The current wheel speeds.- Returns:
- The new pose of the robot.
-