diff --git a/src/main/java/swervelib/SwerveModule.java b/src/main/java/swervelib/SwerveModule.java index 6441c76f..efc3aefe 100644 --- a/src/main/java/swervelib/SwerveModule.java +++ b/src/main/java/swervelib/SwerveModule.java @@ -43,7 +43,7 @@ public class SwerveModule /** * Module number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right. */ - public final int moduleNumber; + public final int moduleNumber; /** * Swerve Motors. */ diff --git a/src/main/java/swervelib/encoders/SparkMaxAnalogEncoderSwerve.java b/src/main/java/swervelib/encoders/SparkMaxAnalogEncoderSwerve.java index 2ef7197d..bbf9fb6c 100644 --- a/src/main/java/swervelib/encoders/SparkMaxAnalogEncoderSwerve.java +++ b/src/main/java/swervelib/encoders/SparkMaxAnalogEncoderSwerve.java @@ -32,13 +32,15 @@ public class SparkMaxAnalogEncoderSwerve extends SwerveAbsoluteEncoder * Create the {@link SparkMaxAnalogEncoderSwerve} object as a analog sensor from the {@link CANSparkMax} motor data * port analog pin. * - * @param motor Motor to create the encoder from. + * @param motor Motor to create the encoder from. + * @param maxVoltage Maximum voltage for analog input reading. */ - public SparkMaxAnalogEncoderSwerve(SwerveMotor motor) + public SparkMaxAnalogEncoderSwerve(SwerveMotor motor, double maxVoltage) { if (motor.getMotor() instanceof CANSparkMax) { encoder = ((CANSparkMax) motor.getMotor()).getAnalog(Mode.kAbsolute); + encoder.setPositionConversionFactor(360 / maxVoltage); } else { throw new RuntimeException("Motor given to instantiate SparkMaxEncoder is not a CANSparkMax"); @@ -108,7 +110,7 @@ public void configure(boolean inverted) @Override public double getAbsolutePosition() { - return encoder.getPosition() * (360 / 3.3); + return encoder.getPosition(); } /** diff --git a/src/main/java/swervelib/imu/ADIS16448Swerve.java b/src/main/java/swervelib/imu/ADIS16448Swerve.java index 531b30d7..be6efa5b 100644 --- a/src/main/java/swervelib/imu/ADIS16448Swerve.java +++ b/src/main/java/swervelib/imu/ADIS16448Swerve.java @@ -112,9 +112,11 @@ public Optional getAccel() /** * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty. + * * @return {@link Double} of the rotation rate as an {@link Optional}. */ - public double getRate() { + public double getRate() + { return imu.getRate(); } diff --git a/src/main/java/swervelib/imu/ADIS16470Swerve.java b/src/main/java/swervelib/imu/ADIS16470Swerve.java index fd01a3d0..81eb3b11 100644 --- a/src/main/java/swervelib/imu/ADIS16470Swerve.java +++ b/src/main/java/swervelib/imu/ADIS16470Swerve.java @@ -112,9 +112,11 @@ public Optional getAccel() /** * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty. + * * @return {@link Double} of the rotation rate as an {@link Optional}. */ - public double getRate() { + public double getRate() + { return imu.getRate(); } diff --git a/src/main/java/swervelib/imu/ADXRS450Swerve.java b/src/main/java/swervelib/imu/ADXRS450Swerve.java index dd9a72d9..e0be2e8b 100644 --- a/src/main/java/swervelib/imu/ADXRS450Swerve.java +++ b/src/main/java/swervelib/imu/ADXRS450Swerve.java @@ -110,9 +110,11 @@ public Optional getAccel() /** * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty. + * * @return {@link Double} of the rotation rate as an {@link Optional}. */ - public double getRate() { + public double getRate() + { return imu.getRate(); } diff --git a/src/main/java/swervelib/imu/AnalogGyroSwerve.java b/src/main/java/swervelib/imu/AnalogGyroSwerve.java index e789d97e..1f3d134f 100644 --- a/src/main/java/swervelib/imu/AnalogGyroSwerve.java +++ b/src/main/java/swervelib/imu/AnalogGyroSwerve.java @@ -117,9 +117,11 @@ public Optional getAccel() /** * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty. + * * @return {@link Double} of the rotation rate as an {@link Optional}. */ - public double getRate() { + public double getRate() + { return imu.getRate(); } diff --git a/src/main/java/swervelib/imu/NavXSwerve.java b/src/main/java/swervelib/imu/NavXSwerve.java index 05c50a30..1adb6e19 100644 --- a/src/main/java/swervelib/imu/NavXSwerve.java +++ b/src/main/java/swervelib/imu/NavXSwerve.java @@ -179,9 +179,11 @@ public Optional getAccel() /** * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty. + * * @return {@link Double} of the rotation rate as an {@link Optional}. */ - public double getRate() { + public double getRate() + { return imu.getRate(); } diff --git a/src/main/java/swervelib/imu/Pigeon2Swerve.java b/src/main/java/swervelib/imu/Pigeon2Swerve.java index 6498dba3..f29970e2 100644 --- a/src/main/java/swervelib/imu/Pigeon2Swerve.java +++ b/src/main/java/swervelib/imu/Pigeon2Swerve.java @@ -140,9 +140,11 @@ public Optional getAccel() /** * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty. + * * @return {@link Double} of the rotation rate as an {@link Optional}. */ - public double getRate() { + public double getRate() + { return imu.getRate(); } diff --git a/src/main/java/swervelib/imu/PigeonSwerve.java b/src/main/java/swervelib/imu/PigeonSwerve.java index 25e12fbc..9515b0d1 100644 --- a/src/main/java/swervelib/imu/PigeonSwerve.java +++ b/src/main/java/swervelib/imu/PigeonSwerve.java @@ -115,11 +115,13 @@ public Optional getAccel() return Optional.of(new Translation3d(initial[0], initial[1], initial[2]).times(9.81 / 16384.0)); } - /** + /** * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty. + * * @return {@link Double} of the rotation rate as an {@link Optional}. */ - public double getRate() { + public double getRate() + { return imu.getRate(); } diff --git a/src/main/java/swervelib/imu/SwerveIMU.java b/src/main/java/swervelib/imu/SwerveIMU.java index ca2b2344..1b1e5ece 100644 --- a/src/main/java/swervelib/imu/SwerveIMU.java +++ b/src/main/java/swervelib/imu/SwerveIMU.java @@ -58,6 +58,7 @@ public abstract class SwerveIMU /** * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty. + * * @return {@link Double} of the rotation rate as an {@link Optional}. */ public abstract double getRate(); diff --git a/src/main/java/swervelib/parser/json/DeviceJson.java b/src/main/java/swervelib/parser/json/DeviceJson.java index 5239c449..776cc6e1 100644 --- a/src/main/java/swervelib/parser/json/DeviceJson.java +++ b/src/main/java/swervelib/parser/json/DeviceJson.java @@ -71,7 +71,7 @@ public SwerveAbsoluteEncoder createEncoder(SwerveMotor motor) case "attached": return new SparkMaxEncoderSwerve(motor, 1); case "sparkmax_analog": - return new SparkMaxAnalogEncoderSwerve(motor); + return new SparkMaxAnalogEncoderSwerve(motor, 3.3); case "canandcoder": return new SparkMaxEncoderSwerve(motor, 360); case "canandcoder_can":