Added new SparkMAX analog encoder option, fixed 'none' absolute encoder type

This commit is contained in:
thenetworkgrinch
2023-12-05 16:25:42 -06:00
parent 04466ef81d
commit e0d572b5a5
126 changed files with 1012 additions and 343 deletions

View File

@@ -1,6 +1,7 @@
package swervelib.encoders;
import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotController;
/**
@@ -89,4 +90,16 @@ public class AnalogAbsoluteEncoderSwerve extends SwerveAbsoluteEncoder
{
return encoder;
}
/**
* Get the velocity in degrees/sec.
*
* @return velocity in degrees/sec.
*/
@Override
public double getVelocity()
{
DriverStation.reportWarning("The Analog Absolute encoder may not report accurate velocities!",true);
return encoder.getValue();
}
}

View File

@@ -137,4 +137,15 @@ public class CANCoderSwerve extends SwerveAbsoluteEncoder
{
return encoder;
}
/**
* Get the velocity in degrees/sec.
*
* @return velocity in degrees/sec.
*/
@Override
public double getVelocity()
{
return encoder.getVelocity();
}
}

View File

@@ -77,4 +77,15 @@ public class CanAndCoderSwerve extends SwerveAbsoluteEncoder
{
return encoder;
}
/**
* Get the velocity in degrees/sec.
*
* @return velocity in degrees/sec.
*/
@Override
public double getVelocity()
{
return encoder.getVelocity();
}
}

View File

@@ -1,5 +1,6 @@
package swervelib.encoders;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DutyCycleEncoder;
/**
@@ -65,6 +66,18 @@ public class PWMDutyCycleEncoderSwerve extends SwerveAbsoluteEncoder
return encoder;
}
/**
* Get the velocity in degrees/sec.
*
* @return velocity in degrees/sec.
*/
@Override
public double getVelocity()
{
DriverStation.reportWarning("The PWM Duty Cycle encoder may not report accurate velocities!", true);
return encoder.get();
}
/**
* Reset the encoder to factory defaults.
*/

View File

@@ -0,0 +1,117 @@
package swervelib.encoders;
import com.revrobotics.AbsoluteEncoder;
import com.revrobotics.CANSparkMax;
import com.revrobotics.REVLibError;
import com.revrobotics.SparkMaxAnalogSensor;
import com.revrobotics.SparkMaxAnalogSensor.Mode;
import edu.wpi.first.wpilibj.DriverStation;
import java.util.function.Supplier;
import swervelib.motors.SwerveMotor;
/**
* SparkMax absolute encoder, attached through the data port analog pin.
*/
public class SparkMaxAnalogEncoderSwerve extends SwerveAbsoluteEncoder
{
/**
* The {@link AbsoluteEncoder} representing the duty cycle encoder attached to the SparkMax.
*/
public SparkMaxAnalogSensor encoder;
/**
* Create the {@link SparkMaxAnalogEncoderSwerve} object as a analog sensor from the {@link CANSparkMax} motor data port analog pin.
*
* @param motor Motor to create the encoder from.
*/
public SparkMaxAnalogEncoderSwerve(SwerveMotor motor)
{
if (motor.getMotor() instanceof CANSparkMax)
{
encoder = ((CANSparkMax) motor.getMotor()).getAnalog(Mode.kAbsolute);
} else
{
throw new RuntimeException("Motor given to instantiate SparkMaxEncoder is not a CANSparkMax");
}
}
/**
* Run the configuration until it succeeds or times out.
*
* @param config Lambda supplier returning the error state.
*/
private void configureSparkMax(Supplier<REVLibError> config)
{
for (int i = 0; i < maximumRetries; i++)
{
if (config.get() == REVLibError.kOk)
{
return;
}
}
DriverStation.reportWarning("Failure configuring encoder", true);
}
/**
* Reset the encoder to factory defaults.
*/
@Override
public void factoryDefault()
{
// Do nothing
}
/**
* Clear sticky faults on the encoder.
*/
@Override
public void clearStickyFaults()
{
// Do nothing
}
/**
* Configure the absolute encoder to read from [0, 360) per second.
*
* @param inverted Whether the encoder is inverted.
*/
@Override
public void configure(boolean inverted)
{
encoder.setInverted(inverted);
}
/**
* Get the absolute position of the encoder.
*
* @return Absolute position in degrees from [0, 360).
*/
@Override
public double getAbsolutePosition()
{
return encoder.getPosition();
}
/**
* Get the instantiated absolute encoder Object.
*
* @return Absolute encoder object.
*/
@Override
public Object getAbsoluteEncoder()
{
return encoder;
}
/**
* Get the velocity in degrees/sec.
*
* @return velocity in degrees/sec.
*/
@Override
public double getVelocity()
{
return encoder.getVelocity();
}
}

View File

@@ -105,4 +105,15 @@ public class SparkMaxEncoderSwerve extends SwerveAbsoluteEncoder
{
return encoder;
}
/**
* Get the velocity in degrees/sec.
*
* @return velocity in degrees/sec.
*/
@Override
public double getVelocity()
{
return encoder.getVelocity();
}
}

View File

@@ -45,4 +45,10 @@ public abstract class SwerveAbsoluteEncoder
* @return Absolute encoder object.
*/
public abstract Object getAbsoluteEncoder();
/**
* Get the velocity in degrees/sec.
* @return velocity in degrees/sec.
*/
public abstract double getVelocity();
}

View File

@@ -24,8 +24,8 @@ public class SwerveMath
{
/**
* Calculate the meters per rotation for the integrated encoder. Calculation: 4in diameter wheels * pi [circumfrence]
* / gear ratio.
* Calculate the meters per rotation for the integrated encoder. Calculation: (PI * WHEEL DIAMETER IN METERS) / (GEAR
* RATIO * ENCODER RESOLUTION)
*
* @param wheelDiameter Wheel diameter in meters.
* @param driveGearRatio The gear ratio of the drive motor.

View File

@@ -6,8 +6,10 @@ import com.revrobotics.CANSparkMax.ControlType;
import com.revrobotics.CANSparkMax.IdleMode;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import com.revrobotics.CANSparkMaxLowLevel.PeriodicFrame;
import com.revrobotics.MotorFeedbackSensor;
import com.revrobotics.REVLibError;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.SparkMaxAnalogSensor;
import com.revrobotics.SparkMaxPIDController;
import edu.wpi.first.wpilibj.DriverStation;
import java.util.function.Supplier;
@@ -31,7 +33,7 @@ public class SparkMaxSwerve extends SwerveMotor
/**
* Absolute encoder attached to the SparkMax (if exists)
*/
public AbsoluteEncoder absoluteEncoder;
public SwerveAbsoluteEncoder absoluteEncoder;
/**
* Closed-loop PID controller.
*/
@@ -179,14 +181,14 @@ public class SparkMaxSwerve extends SwerveMotor
@Override
public SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
{
if (encoder.getAbsoluteEncoder() instanceof AbsoluteEncoder)
if (encoder.getAbsoluteEncoder() instanceof MotorFeedbackSensor)
{
DriverStation.reportWarning(
"IF possible configure the duty cycle encoder offset in the REV Hardware Client instead of using the" +
" absoluteEncoderOffset in the Swerve Module JSON!",
false);
absoluteEncoder = (AbsoluteEncoder) encoder.getAbsoluteEncoder();
configureSparkMax(() -> pid.setFeedbackDevice(absoluteEncoder));
absoluteEncoder = encoder;
configureSparkMax(() -> pid.setFeedbackDevice((MotorFeedbackSensor) absoluteEncoder.getAbsoluteEncoder()));
}
return this;
}
@@ -209,8 +211,24 @@ public class SparkMaxSwerve extends SwerveMotor
configureCANStatusFrames(10, 20, 20, 500, 500);
} else
{
configureSparkMax(() -> absoluteEncoder.setPositionConversionFactor(positionConversionFactor));
configureSparkMax(() -> absoluteEncoder.setVelocityConversionFactor(positionConversionFactor / 60));
configureSparkMax(() -> {
if (absoluteEncoder.getAbsoluteEncoder() instanceof AbsoluteEncoder)
{
return ((AbsoluteEncoder) absoluteEncoder.getAbsoluteEncoder()).setPositionConversionFactor(positionConversionFactor);
} else
{
return ((SparkMaxAnalogSensor)absoluteEncoder.getAbsoluteEncoder()).setPositionConversionFactor(positionConversionFactor);
}
});
configureSparkMax(() -> {
if (absoluteEncoder.getAbsoluteEncoder() instanceof AbsoluteEncoder)
{
return ((AbsoluteEncoder) absoluteEncoder.getAbsoluteEncoder()).setVelocityConversionFactor(positionConversionFactor / 60);
} else
{
return ((SparkMaxAnalogSensor)absoluteEncoder.getAbsoluteEncoder()).setVelocityConversionFactor(positionConversionFactor / 60);
}
});
}
}
@@ -381,7 +399,7 @@ public class SparkMaxSwerve extends SwerveMotor
@Override
public double getPosition()
{
return absoluteEncoder == null ? encoder.getPosition() : absoluteEncoder.getPosition();
return absoluteEncoder == null ? encoder.getPosition() : absoluteEncoder.getAbsolutePosition();
}
/**

View File

@@ -23,8 +23,10 @@ public class SwerveControllerConfiguration
public double maxAngularVelocity;
/**
* Construct the swerve controller configuration.
* Construct the swerve controller configuration. Assumes robot is square to fetch maximum angular velocity.
*
* @param driveCfg {@link SwerveDriveConfiguration} to fetch the first module X and Y used to
* calculate the maximum angular velocity.
* @param headingPIDF Heading PIDF configuration.
* @param angleJoyStickRadiusDeadband Deadband on radius of angle joystick.
* @param maxSpeedMPS Maximum speed in meters per second for angular velocity, remember if you have

View File

@@ -39,10 +39,11 @@ public class SwerveDriveConfiguration
/**
* Create swerve drive configuration.
*
* @param moduleConfigs Module configuration.
* @param swerveIMU Swerve IMU.
* @param invertedIMU Invert the IMU.
* @param driveFeedforward The drive motor feedforward to use for the {@link SwerveModule}.
* @param moduleConfigs Module configuration.
* @param swerveIMU Swerve IMU.
* @param invertedIMU Invert the IMU.
* @param driveFeedforward The drive motor feedforward to use for the {@link SwerveModule}.
* @param physicalCharacteristics {@link SwerveModulePhysicalCharacteristics} to store in association with self.
*/
public SwerveDriveConfiguration(
SwerveModuleConfiguration[] moduleConfigs,

View File

@@ -17,7 +17,7 @@ public class SwerveModuleConfiguration
* {@link swervelib.math.SwerveMath#calculateDegreesPerSteeringRotation(double, double)} respectively to calculate the
* conversion factors.
*/
public final MotorConfigDouble conversionFactors;
public final MotorConfigDouble conversionFactors;
/**
* Angle offset in degrees for the Swerve Module.
*/
@@ -79,6 +79,7 @@ public class SwerveModuleConfiguration
* @param velocityPIDF Velocity PIDF configuration.
* @param physicalCharacteristics Physical characteristics of the swerve module.
* @param name The name for the swerve module.
* @param conversionFactors Conversion factors to be applied to the drive and angle motors.
*/
public SwerveModuleConfiguration(
SwerveMotor driveMotor,

View File

@@ -9,6 +9,7 @@ import swervelib.encoders.AnalogAbsoluteEncoderSwerve;
import swervelib.encoders.CANCoderSwerve;
import swervelib.encoders.CanAndCoderSwerve;
import swervelib.encoders.PWMDutyCycleEncoderSwerve;
import swervelib.encoders.SparkMaxAnalogEncoderSwerve;
import swervelib.encoders.SparkMaxEncoderSwerve;
import swervelib.encoders.SwerveAbsoluteEncoder;
import swervelib.imu.ADIS16448Swerve;
@@ -61,9 +62,12 @@ public class DeviceJson
switch (type)
{
case "none":
return null;
case "integrated":
case "attached":
return null;
return new SparkMaxEncoderSwerve(motor, 1);
case "sparkmax_analog":
return new SparkMaxAnalogEncoderSwerve(motor);
case "canandcoder":
return new SparkMaxEncoderSwerve(motor, 360);
case "canandcoder_can":
@@ -180,24 +184,4 @@ public class DeviceJson
throw new RuntimeException(type + " is not a recognized absolute encoder type.");
}
}
/**
* Create a {@link SwerveAbsoluteEncoder} from the data port on the motor controller.
*
* @param motor The motor to create the absolute encoder from.
* @return {@link SwerveAbsoluteEncoder} from the motor controller.
*/
public SwerveAbsoluteEncoder createIntegratedEncoder(SwerveMotor motor)
{
switch (type)
{
case "sparkmax":
return new SparkMaxEncoderSwerve(motor, 1);
case "falcon":
case "talonfx":
return null;
}
throw new RuntimeException(
"Could not create absolute encoder from data port of " + type + " id " + id);
}
}

View File

@@ -1,5 +1,7 @@
package swervelib.parser.json;
import com.revrobotics.CANSparkMax;
import com.revrobotics.MotorFeedbackSensor;
import edu.wpi.first.math.util.Units;
import swervelib.encoders.SwerveAbsoluteEncoder;
import swervelib.motors.SwerveMotor;
@@ -30,7 +32,7 @@ public class ModuleJson
* {@link swervelib.math.SwerveMath#calculateDegreesPerSteeringRotation(double, double)} for angle motors or
* {@link swervelib.math.SwerveMath#calculateMetersPerRotation(double, double, double)} for drive motors.
*/
public MotorConfigDouble conversionFactor = new MotorConfigDouble(0, 0);
public MotorConfigDouble conversionFactor = new MotorConfigDouble(0, 0);
/**
* Absolute encoder device configuration.
*/
@@ -71,10 +73,12 @@ public class ModuleJson
SwerveAbsoluteEncoder absEncoder = encoder.createEncoder(angleMotor);
// If the absolute encoder is attached.
if (absEncoder == null)
if (absEncoder != null && angleMotor.getMotor() instanceof CANSparkMax)
{
absEncoder = angle.createIntegratedEncoder(angleMotor);
angleMotor.setAbsoluteEncoder(absEncoder);
if (absEncoder.getAbsoluteEncoder() instanceof MotorFeedbackSensor)
{
angleMotor.setAbsoluteEncoder(absEncoder);
}
}
// Set the conversion factors to null if they are both 0.