Update to 2024.5.0.3

This commit is contained in:
thenetworkgrinch
2024-08-24 17:27:03 -05:00
parent 89e4163951
commit 44af2d1978
131 changed files with 705 additions and 416 deletions

View File

@@ -1,5 +1,7 @@
package swervelib;
import com.revrobotics.CANSparkMax;
import com.revrobotics.MotorFeedbackSensor;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
@@ -38,6 +40,10 @@ public class SwerveModule
* Drive motor velocity cache.
*/
public final Cache<Double> driveVelocityCache;
/**
* Module number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right.
*/
public final int moduleNumber;
/**
* Swerve Motors.
*/
@@ -78,10 +84,6 @@ public class SwerveModule
* NT3 Raw drive motor.
*/
private final String rawDriveVelName;
/**
* Module number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right.
*/
public final int moduleNumber;
/**
* Maximum speed of the drive motors in meters per second.
*/
@@ -591,13 +593,23 @@ public class SwerveModule
{
if (absoluteEncoder != null && angleOffset == configuration.angleOffset)
{
if (absoluteEncoder.setAbsoluteEncoderOffset(angleOffset))
// If the absolute encoder is attached.
if (angleMotor.getMotor() instanceof CANSparkMax)
{
angleOffset = 0;
} else
{
encoderOffsetWarning.set(true);
if (absoluteEncoder.getAbsoluteEncoder() instanceof MotorFeedbackSensor)
{
angleMotor.setAbsoluteEncoder(absoluteEncoder);
if (absoluteEncoder.setAbsoluteEncoderOffset(angleOffset))
{
angleOffset = 0;
} else
{
angleMotor.setAbsoluteEncoder(null);
encoderOffsetWarning.set(true);
}
}
}
} else
{
noEncoderWarning.set(true);