Skip to content
This repository was archived by the owner on Feb 16, 2026. It is now read-only.
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 9 additions & 7 deletions src/main/java/swervelib/motors/SparkFlexSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@
import edu.wpi.first.wpilibj.Alert.AlertType;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Timer;

import java.util.Optional;
import java.util.function.Supplier;
import swervelib.encoders.SwerveAbsoluteEncoder;
import swervelib.parser.PIDFConfig;
Expand All @@ -48,7 +50,7 @@ public class SparkFlexSwerve extends SwerveMotor
/**
* Absolute encoder attached to the SparkFlex (if exists)
*/
public SwerveAbsoluteEncoder absoluteEncoder;
public Optional<SwerveAbsoluteEncoder> absoluteEncoder = Optional.empty();
/**
* Closed-loop PID controller.
*/
Expand Down Expand Up @@ -224,7 +226,7 @@ public DCMotor getSimMotor()
@Override
public boolean isAttachedAbsoluteEncoder()
{
return absoluteEncoder != null;
return absoluteEncoder.isPresent();
}

/**
Expand Down Expand Up @@ -256,18 +258,18 @@ public SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
{
if (encoder == null)
{
absoluteEncoder = null;
this.absoluteEncoder = Optional.empty();
cfg.closedLoop.feedbackSensor(FeedbackSensor.kPrimaryEncoder);

velocity = this.encoder::getVelocity;
position = this.encoder::getPosition;
} else if (encoder.getAbsoluteEncoder() instanceof AbsoluteEncoder)
{
cfg.closedLoop.feedbackSensor(FeedbackSensor.kAbsoluteEncoder);
absoluteEncoder = encoder;
this.absoluteEncoder = Optional.of(encoder);

velocity = absoluteEncoder::getVelocity;
position = absoluteEncoder::getAbsolutePosition;
velocity = this.absoluteEncoder.get()::getVelocity;
position = this.absoluteEncoder.get()::getAbsolutePosition;
}
return this;
}
Expand Down Expand Up @@ -329,7 +331,7 @@ public void configureIntegratedEncoder(double positionConversionFactor)
// Some of the frames can probably be adjusted to decrease CAN utilization, with 65535 being the max.
// From testing, 20ms on frame 5 sometimes returns the same value while constantly powering the azimuth but 8ms may be overkill,
// with limited testing 19ms did not return the same value while the module was constatntly rotating.
if (absoluteEncoder.getAbsoluteEncoder() instanceof AbsoluteEncoder)
if (absoluteEncoder.get().getAbsoluteEncoder() instanceof AbsoluteEncoder)
{
cfg.closedLoop.feedbackSensor(FeedbackSensor.kAbsoluteEncoder);

Expand Down
14 changes: 7 additions & 7 deletions src/main/java/swervelib/motors/SparkMaxBrushedMotorSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ public class SparkMaxBrushedMotorSwerve extends SwerveMotor
/**
* Absolute encoder attached to the SparkMax (if exists)
*/
public SwerveAbsoluteEncoder absoluteEncoder;
public Optional<SwerveAbsoluteEncoder> absoluteEncoder;
/**
* Integrated encoder.
*/
Expand Down Expand Up @@ -290,7 +290,7 @@ public DCMotor getSimMotor()
@Override
public boolean isAttachedAbsoluteEncoder()
{
return absoluteEncoder != null;
return absoluteEncoder.isPresent();
}

/**
Expand Down Expand Up @@ -322,7 +322,7 @@ public SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
{
if (encoder == null)
{
absoluteEncoder = null;
this.absoluteEncoder = Optional.empty();
cfg.closedLoop.feedbackSensor(FeedbackSensor.kPrimaryEncoder);

this.encoder.ifPresentOrElse((RelativeEncoder enc) -> {
Expand All @@ -337,9 +337,9 @@ public SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
cfg.closedLoop.feedbackSensor(encoder instanceof SparkMaxAnalogEncoderSwerve
? FeedbackSensor.kAnalogSensor : FeedbackSensor.kAbsoluteEncoder);

absoluteEncoder = encoder;
velocity = absoluteEncoder::getVelocity;
position = absoluteEncoder::getAbsolutePosition;
this.absoluteEncoder = Optional.of(encoder);
velocity = this.absoluteEncoder.get()::getVelocity;
position = this.absoluteEncoder.get()::getAbsolutePosition;
noEncoderDefinedAlert.set(false);
}
if (absoluteEncoder == null && this.encoder.isEmpty())
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This check is wrong now too

Expand Down Expand Up @@ -404,7 +404,7 @@ public void configureIntegratedEncoder(double positionConversionFactor)
// Some of the frames can probably be adjusted to decrease CAN utilization, with 65535 being the max.
// From testing, 20ms on frame 5 sometimes returns the same value while constantly powering the azimuth but 8ms may be overkill,
// with limited testing 19ms did not return the same value while the module was constatntly rotating.
if (absoluteEncoder.getAbsoluteEncoder() instanceof AbsoluteEncoder)
if (absoluteEncoder.get().getAbsoluteEncoder() instanceof AbsoluteEncoder)
{
cfg.closedLoop.feedbackSensor(FeedbackSensor.kAbsoluteEncoder);

Expand Down
6 changes: 3 additions & 3 deletions src/main/java/swervelib/motors/SparkMaxSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,7 @@ public DCMotor getSimMotor()
@Override
public boolean isAttachedAbsoluteEncoder()
{
return absoluteEncoder != null;
return absoluteEncoder.isPresent();
}

/**
Expand Down Expand Up @@ -268,8 +268,8 @@ public SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
? FeedbackSensor.kAnalogSensor : FeedbackSensor.kAbsoluteEncoder);

this.absoluteEncoder = Optional.of(encoder);
velocity = encoder::getVelocity;
position = encoder::getAbsolutePosition;
velocity = this.absoluteEncoder.get()::getVelocity;
position = this.absoluteEncoder.get()::getAbsolutePosition;
}
return this;
}
Expand Down