Upgrading to 2025.1.0

This commit is contained in:
thenetworkgrinch
2024-12-09 23:26:04 +00:00
parent 9fe6551d88
commit 4bc6978a20
35 changed files with 1902 additions and 1122 deletions

View File

@@ -1,12 +1,16 @@
package swervelib.encoders;
import com.revrobotics.AbsoluteEncoder;
import com.revrobotics.CANSparkMax;
import com.revrobotics.REVLibError;
import com.revrobotics.SparkAbsoluteEncoder.Type;
import com.revrobotics.spark.SparkAbsoluteEncoder;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.config.SparkMaxConfig;
import edu.wpi.first.wpilibj.Alert;
import edu.wpi.first.wpilibj.Alert.AlertType;
import java.util.function.Supplier;
import swervelib.motors.SparkMaxBrushedMotorSwerve;
import swervelib.motors.SparkMaxSwerve;
import swervelib.motors.SwerveMotor;
import swervelib.telemetry.Alert;
/**
* SparkMax absolute encoder, attached through the data port.
@@ -17,18 +21,23 @@ public class SparkMaxEncoderSwerve extends SwerveAbsoluteEncoder
/**
* The {@link AbsoluteEncoder} representing the duty cycle encoder attached to the SparkMax.
*/
public AbsoluteEncoder encoder;
public SparkAbsoluteEncoder encoder;
/**
* An {@link Alert} for if there is a failure configuring the encoder.
*/
private Alert failureConfiguring;
private Alert failureConfiguring;
/**
* An {@link Alert} for if there is a failure configuring the encoder offset.
*/
private Alert offsetFailure;
private Alert offsetFailure;
/**
* {@link SparkMaxBrushedMotorSwerve} or {@link SparkMaxSwerve} instance.
*/
private SwerveMotor sparkMax;
/**
* Create the {@link SparkMaxEncoderSwerve} object as a duty cycle from the {@link CANSparkMax} motor.
* Create the {@link SparkMaxEncoderSwerve} object as a duty cycle from the {@link com.revrobotics.spark.SparkMax}
* motor.
*
* @param motor Motor to create the encoder from.
* @param conversionFactor The conversion factor to set if the output is not from 0 to 360.
@@ -38,16 +47,17 @@ public class SparkMaxEncoderSwerve extends SwerveAbsoluteEncoder
failureConfiguring = new Alert(
"Encoders",
"Failure configuring SparkMax Analog Encoder",
Alert.AlertType.WARNING_TRACE);
AlertType.kWarning);
offsetFailure = new Alert(
"Encoders",
"Failure to set Absolute Encoder Offset",
Alert.AlertType.WARNING_TRACE);
if (motor.getMotor() instanceof CANSparkMax)
AlertType.kWarning);
if (motor.getMotor() instanceof SparkMax)
{
encoder = ((CANSparkMax) motor.getMotor()).getAbsoluteEncoder(Type.kDutyCycle);
configureSparkMax(() -> encoder.setVelocityConversionFactor(conversionFactor));
configureSparkMax(() -> encoder.setPositionConversionFactor(conversionFactor));
sparkMax = motor;
encoder = ((SparkMax) motor.getMotor()).getAbsoluteEncoder();
motor.setAbsoluteEncoder(this);
motor.configureIntegratedEncoder(conversionFactor);
} else
{
throw new RuntimeException("Motor given to instantiate SparkMaxEncoder is not a CANSparkMax");
@@ -97,7 +107,17 @@ public class SparkMaxEncoderSwerve extends SwerveAbsoluteEncoder
@Override
public void configure(boolean inverted)
{
encoder.setInverted(inverted);
if (sparkMax instanceof SparkMaxSwerve)
{
SparkMaxConfig cfg = ((SparkMaxSwerve) sparkMax).getConfig();
cfg.analogSensor.inverted(true);
((SparkMaxSwerve) sparkMax).updateConfig(cfg);
} else if (sparkMax instanceof SparkMaxBrushedMotorSwerve)
{
SparkMaxConfig cfg = ((SparkMaxBrushedMotorSwerve) sparkMax).getConfig();
cfg.analogSensor.inverted(true);
((SparkMaxBrushedMotorSwerve) sparkMax).updateConfig(cfg);
}
}
/**
@@ -131,17 +151,19 @@ public class SparkMaxEncoderSwerve extends SwerveAbsoluteEncoder
@Override
public boolean setAbsoluteEncoderOffset(double offset)
{
REVLibError error = null;
for (int i = 0; i < maximumRetries; i++)
if (sparkMax instanceof SparkMaxSwerve)
{
error = encoder.setZeroOffset(offset);
if (error == REVLibError.kOk)
{
return true;
}
SparkMaxConfig cfg = ((SparkMaxSwerve) sparkMax).getConfig();
cfg.absoluteEncoder.zeroOffset(offset);
((SparkMaxSwerve) sparkMax).updateConfig(cfg);
return true;
} else if (sparkMax instanceof SparkMaxBrushedMotorSwerve)
{
SparkMaxConfig cfg = ((SparkMaxBrushedMotorSwerve) sparkMax).getConfig();
cfg.absoluteEncoder.zeroOffset(offset);
((SparkMaxBrushedMotorSwerve) sparkMax).updateConfig(cfg);
return true;
}
offsetFailure.setText("Failure to set Absolute Encoder Offset Error: " + error);
offsetFailure.set(true);
return false;
}