Skip to content

Commit

Permalink
Optimized and fixed absolute encoder inversion for SparkMAX attached …
Browse files Browse the repository at this point in the history
…encoders.

Signed-off-by: thenetworkgrinch <thenetworkgrinch@users.noreply.github.com>
  • Loading branch information
thenetworkgrinch committed Jan 10, 2025
1 parent f3f59ca commit ddd58e0
Show file tree
Hide file tree
Showing 5 changed files with 20 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -110,12 +110,12 @@ public void configure(boolean inverted)
if (sparkMax instanceof SparkMaxSwerve)
{
SparkMaxConfig cfg = ((SparkMaxSwerve) sparkMax).getConfig();
cfg.analogSensor.inverted(true);
cfg.analogSensor.inverted(inverted);
((SparkMaxSwerve) sparkMax).updateConfig(cfg);
} else if (sparkMax instanceof SparkMaxBrushedMotorSwerve)
{
SparkMaxConfig cfg = ((SparkMaxBrushedMotorSwerve) sparkMax).getConfig();
cfg.analogSensor.inverted(true);
cfg.analogSensor.inverted(inverted);
((SparkMaxBrushedMotorSwerve) sparkMax).updateConfig(cfg);
}
}
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/swervelib/encoders/SparkMaxEncoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ public SparkMaxEncoderSwerve(SwerveMotor motor, int conversionFactor)
{
failureConfiguring = new Alert(
"Encoders",
"Failure configuring SparkMax Analog Encoder",
"Failure configuring SparkMax Absolute Encoder",
AlertType.kWarning);
offsetFailure = new Alert(
"Encoders",
Expand Down Expand Up @@ -110,12 +110,12 @@ public void configure(boolean inverted)
if (sparkMax instanceof SparkMaxSwerve)
{
SparkMaxConfig cfg = ((SparkMaxSwerve) sparkMax).getConfig();
cfg.analogSensor.inverted(true);
cfg.absoluteEncoder.inverted(inverted);
((SparkMaxSwerve) sparkMax).updateConfig(cfg);
} else if (sparkMax instanceof SparkMaxBrushedMotorSwerve)
{
SparkMaxConfig cfg = ((SparkMaxBrushedMotorSwerve) sparkMax).getConfig();
cfg.analogSensor.inverted(true);
cfg.absoluteEncoder.inverted(inverted);
((SparkMaxBrushedMotorSwerve) sparkMax).updateConfig(cfg);
}
}
Expand Down
6 changes: 5 additions & 1 deletion src/main/java/swervelib/motors/SparkFlexSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,10 @@
public class SparkFlexSwerve extends SwerveMotor
{

/**
* Config retry delay.
*/
private final double configDelay = Milliseconds.of(5).in(Seconds);
/**
* {@link SparkFlex} Instance.
*/
Expand Down Expand Up @@ -120,7 +124,7 @@ private void configureSparkFlex(Supplier<REVLibError> config)
{
return;
}
Timer.delay(Milliseconds.of(5).in(Seconds));
Timer.delay(configDelay);
}
failureConfiguring.set(true);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,10 @@
public class SparkMaxBrushedMotorSwerve extends SwerveMotor
{

/**
* Config retry delay.
*/
private final double configDelay = Milliseconds.of(5).in(Seconds);
/**
* SparkMAX Instance.
*/
Expand Down Expand Up @@ -187,7 +191,7 @@ private void configureSparkMax(Supplier<REVLibError> config)
{
return;
}
Timer.delay(Milliseconds.of(5).in(Seconds));
Timer.delay(configDelay);
}
failureConfiguringAlert.set(true);
}
Expand Down
6 changes: 5 additions & 1 deletion src/main/java/swervelib/motors/SparkMaxSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,10 @@
public class SparkMaxSwerve extends SwerveMotor
{

/**
* Config retry delay.
*/
private final double configDelay = Milliseconds.of(5).in(Seconds);
/**
* {@link SparkMax} Instance.
*/
Expand Down Expand Up @@ -119,7 +123,7 @@ private void configureSparkMax(Supplier<REVLibError> config)
{
return;
}
Timer.delay(Milliseconds.of(5).in(Seconds));
Timer.delay(configDelay);
}
DriverStation.reportWarning("Failure configuring motor " + motor.getDeviceId(), true);
}
Expand Down

0 comments on commit ddd58e0

Please sign in to comment.