From b4d30ca113accab5889565d3cd62a50bc7dd92e2 Mon Sep 17 00:00:00 2001 From: T Grinch <10247070+thenetworkgrinch@users.noreply.github.com> Date: Tue, 23 Jan 2024 20:51:46 -0600 Subject: [PATCH] Updated javadocs for addVisionMeasurement. Signed-off-by: thenetworkgrinch --- src/main/java/swervelib/SwerveDrive.java | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/main/java/swervelib/SwerveDrive.java b/src/main/java/swervelib/SwerveDrive.java index 0244c577d..82d548fc1 100644 --- a/src/main/java/swervelib/SwerveDrive.java +++ b/src/main/java/swervelib/SwerveDrive.java @@ -1030,9 +1030,7 @@ public void addVisionMeasurement(Pose2d robotPose, double timestamp, /** * Add a vision measurement to the {@link SwerveDrivePoseEstimator} and update the {@link SwerveIMU} gyro reading with - * the given timestamp of the vision measurement.
IT IS HIGHLY RECOMMENDED TO UPDATE YOUR GYROSCOPE OFFSET - * AFTER USING THIS FUNCTION!
To update your gyroscope readings directly use - * {@link SwerveDrive#setGyroOffset(Rotation3d)}. + * the given timestamp of the vision measurement. * * @param robotPose Robot {@link Pose2d} as measured by vision. * @param timestamp Timestamp the measurement was taken as time since startup, should be taken from