Update reliability

This commit is contained in:
thenetworkgrinch
2024-08-24 17:40:19 -05:00
parent 1b464310d3
commit 73b253bce8
123 changed files with 149 additions and 129 deletions

View File

@@ -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.
*/

View File

@@ -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 class SparkMaxAnalogEncoderSwerve extends SwerveAbsoluteEncoder
@Override
public double getAbsolutePosition()
{
return encoder.getPosition() * (360 / 3.3);
return encoder.getPosition();
}
/**

View File

@@ -112,9 +112,11 @@ public class ADIS16448Swerve extends 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 double getRate() {
public double getRate()
{
return imu.getRate();
}

View File

@@ -112,9 +112,11 @@ public class ADIS16470Swerve extends 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 double getRate() {
public double getRate()
{
return imu.getRate();
}

View File

@@ -110,9 +110,11 @@ public class ADXRS450Swerve extends 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 double getRate() {
public double getRate()
{
return imu.getRate();
}

View File

@@ -117,9 +117,11 @@ public class AnalogGyroSwerve extends 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 double getRate() {
public double getRate()
{
return imu.getRate();
}

View File

@@ -179,9 +179,11 @@ public class NavXSwerve extends 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 double getRate() {
public double getRate()
{
return imu.getRate();
}

View File

@@ -140,9 +140,11 @@ public class Pigeon2Swerve extends 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 double getRate() {
public double getRate()
{
return imu.getRate();
}

View File

@@ -115,11 +115,13 @@ public class PigeonSwerve extends SwerveIMU
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();
}

View File

@@ -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();

View File

@@ -71,7 +71,7 @@ public class DeviceJson
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":