Included PR's

This commit is contained in:
thenetworkgrinch
2024-01-16 16:53:07 -06:00
parent 0d790c3cdd
commit bf59167648
2 changed files with 10 additions and 17 deletions

View File

@@ -1,7 +1,6 @@
package swervelib.encoders;
import com.reduxrobotics.sensors.canandcoder.Canandcoder;
import edu.wpi.first.wpilibj.DriverStation;
/**
* HELIUM {@link Canandcoder} from ReduxRobotics absolute encoder, attached through the CAN bus.
@@ -12,11 +11,7 @@ public class CanAndCoderSwerve extends SwerveAbsoluteEncoder
/**
* The {@link Canandcoder} representing the CANandCoder on the CAN bus.
*/
public Canandcoder encoder;
/**
* Inversion state of the encoder.
*/
private boolean inverted = false;
public Canandcoder encoder;
/**
* Create the {@link Canandcoder}
@@ -30,6 +25,8 @@ public class CanAndCoderSwerve extends SwerveAbsoluteEncoder
/**
* Reset the encoder to factory defaults.
*
* This will not clear the stored zero offset.
*/
@Override
public void factoryDefault()
@@ -47,14 +44,14 @@ public class CanAndCoderSwerve extends SwerveAbsoluteEncoder
}
/**
* Configure the CANandCoder to read from [0, 360) per second.
* Configure the Canandcoder to read from [0, 360) per second.
*
* @param inverted Whether the encoder is inverted.
*/
@Override
public void configure(boolean inverted)
{
this.inverted = inverted;
encoder.setSettings(new Canandcoder.Settings().setInvertDirection(inverted));
}
/**
@@ -65,7 +62,7 @@ public class CanAndCoderSwerve extends SwerveAbsoluteEncoder
@Override
public double getAbsolutePosition()
{
return (inverted ? -1.0 : 1.0) * encoder.getPosition() * 360;
return encoder.getAbsPosition() * 360;
}
/**
@@ -80,18 +77,15 @@ public class CanAndCoderSwerve extends SwerveAbsoluteEncoder
}
/**
* Cannot set the offset of the CanAndCoder.
* Cannot set the offset of the Canandcoder.
*
* @param offset the offset the Absolute Encoder uses as the zero point.
* @return always false due to CanAndCoder not supporting offset changing.
* @return true if setting the zero point succeeded, false otherwise
*/
@Override
public boolean setAbsoluteEncoderOffset(double offset)
{
//CanAndCoder does not support Absolute Offset Changing
DriverStation.reportWarning("Cannot Set Absolute Encoder Offset of CanAndCoders ID: " + encoder.getAddress(),
false);
return false;
return encoder.setSettings(new Canandcoder.Settings().setZeroOffset(offset));
}
/**
@@ -102,6 +96,6 @@ public class CanAndCoderSwerve extends SwerveAbsoluteEncoder
@Override
public double getVelocity()
{
return encoder.getVelocity();
return encoder.getVelocity() * 360;
}
}

View File

@@ -116,7 +116,6 @@ public class ModuleJson
throw new RuntimeException(
"Conversion factors cannot be 0, please configure conversion factors in physicalproperties.json or the module JSON files.");
}
System.out.println(conversionFactor.drive);
return new SwerveModuleConfiguration(
drive.createMotor(true),