Skip to content

Commit

Permalink
Fix canandmag names.
Browse files Browse the repository at this point in the history
Signed-off-by: thenetworkgrinch <thenetworkgrinch@users.noreply.github.com>
  • Loading branch information
thenetworkgrinch committed Aug 24, 2024
1 parent 3a24331 commit 4c9304e
Show file tree
Hide file tree
Showing 6 changed files with 43 additions and 26 deletions.
22 changes: 17 additions & 5 deletions src/main/java/swervelib/SwerveModule.java
Original file line number Diff line number Diff line change
@@ -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;
Expand Down Expand Up @@ -591,13 +593,23 @@ public void pushOffsetsToEncoders()
{
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);
Expand Down
16 changes: 8 additions & 8 deletions src/main/java/swervelib/encoders/CanAndCoderSwerve.java
Original file line number Diff line number Diff line change
@@ -1,26 +1,26 @@
package swervelib.encoders;

import com.reduxrobotics.sensors.canandcoder.Canandcoder;
import com.reduxrobotics.sensors.canandmag.Canandmag;

/**
* HELIUM {@link Canandcoder} from ReduxRobotics absolute encoder, attached through the CAN bus.
* HELIUM {@link Canandmag} from ReduxRobotics absolute encoder, attached through the CAN bus.
*/
public class CanAndCoderSwerve extends SwerveAbsoluteEncoder
{

/**
* The {@link Canandcoder} representing the CANandCoder on the CAN bus.
* The {@link Canandmag} representing the CANandCoder on the CAN bus.
*/
public Canandcoder encoder;
public Canandmag encoder;

/**
* Create the {@link Canandcoder}
* Create the {@link Canandmag}
*
* @param canid The CAN ID whenever the CANandCoder is operating on the CANBus.
*/
public CanAndCoderSwerve(int canid)
{
encoder = new Canandcoder(canid);
encoder = new Canandmag(canid);
}

/**
Expand Down Expand Up @@ -51,7 +51,7 @@ public void clearStickyFaults()
@Override
public void configure(boolean inverted)
{
encoder.setSettings(new Canandcoder.Settings().setInvertDirection(inverted));
encoder.setSettings(new Canandmag.Settings().setInvertDirection(inverted));
}

/**
Expand Down Expand Up @@ -85,7 +85,7 @@ public Object getAbsoluteEncoder()
@Override
public boolean setAbsoluteEncoderOffset(double offset)
{
return encoder.setSettings(new Canandcoder.Settings().setZeroOffset(offset));
return encoder.setSettings(new Canandmag.Settings().setZeroOffset(offset));
}

/**
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 @@ -200,7 +200,11 @@ public void clearStickyFaults()
@Override
public SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
{
if (encoder.getAbsoluteEncoder() instanceof MotorFeedbackSensor)
if (encoder == null)
{
absoluteEncoder = null;
configureSparkFlex(() -> pid.setFeedbackDevice(this.encoder));
} else if (encoder.getAbsoluteEncoder() instanceof MotorFeedbackSensor)
{
absoluteEncoderOffsetWarning.set(true);
absoluteEncoder = encoder;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -237,7 +237,11 @@ public void clearStickyFaults()
@Override
public SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
{
if (encoder.getAbsoluteEncoder() instanceof AbsoluteEncoder)
if (encoder == null)
{
absoluteEncoder = null;
configureSparkMax(() -> pid.setFeedbackDevice(this.encoder));
} else if (encoder.getAbsoluteEncoder() instanceof AbsoluteEncoder)
{
absoluteEncoder = (AbsoluteEncoder) encoder.getAbsoluteEncoder();
configureSparkMax(() -> pid.setFeedbackDevice(absoluteEncoder));
Expand Down
10 changes: 8 additions & 2 deletions src/main/java/swervelib/motors/SparkMaxSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -192,10 +192,16 @@ public void clearStickyFaults()
@Override
public SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
{
if (encoder.getAbsoluteEncoder() instanceof MotorFeedbackSensor)
if (encoder == null)
{
absoluteEncoder = null;
configureSparkMax(() -> pid.setFeedbackDevice(this.encoder));
velocity = this.encoder::getVelocity;
position = this.encoder::getPosition;
} else if (encoder.getAbsoluteEncoder() instanceof MotorFeedbackSensor)
{
DriverStation.reportWarning(
"IF possible configure the duty cycle encoder offset in the REV Hardware Client instead of using the" +
"IF possible configure the encoder offset in the REV Hardware Client instead of using the" +
" absoluteEncoderOffset in the Swerve Module JSON!",
false);
absoluteEncoder = encoder;
Expand Down
9 changes: 0 additions & 9 deletions src/main/java/swervelib/parser/json/ModuleJson.java
Original file line number Diff line number Diff line change
Expand Up @@ -81,15 +81,6 @@ public SwerveModuleConfiguration createModuleConfiguration(
SwerveMotor angleMotor = angle.createMotor(false);
SwerveAbsoluteEncoder absEncoder = encoder.createEncoder(angleMotor);

// If the absolute encoder is attached.
if (absEncoder != null && angleMotor.getMotor() instanceof CANSparkMax)
{
if (absEncoder.getAbsoluteEncoder() instanceof MotorFeedbackSensor)
{
angleMotor.setAbsoluteEncoder(absEncoder);
}
}

// Setup deprecation notice.
// if (this.conversionFactor.drive != 0 && this.conversionFactor.angle != 0)
// {
Expand Down

0 comments on commit 4c9304e

Please sign in to comment.