Skip to content

Commit

Permalink
Fixed alert's to prevent null pointer dereference.
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 Jan 17, 2024
1 parent f6d2e91 commit 35ff0b8
Show file tree
Hide file tree
Showing 11 changed files with 128 additions and 102 deletions.
31 changes: 17 additions & 14 deletions src/main/java/swervelib/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,14 @@ public class SwerveModule
* Absolute encoder for swerve drive.
*/
private final SwerveAbsoluteEncoder absoluteEncoder;
/**
* An {@link Alert} for if pushing the Absolute Encoder offset to the encoder fails.
*/
private final Alert encoderOffsetWarning;
/**
* An {@link Alert} for if there is no Absolute Encoder on the module.
*/
private final Alert noEncoderWarning;
/**
* Module number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right.
*/
Expand Down Expand Up @@ -61,20 +69,6 @@ public class SwerveModule
* Encoder synchronization queued.
*/
private boolean synchronizeEncoderQueued = false;
/**
* An {@link Alert} for if pushing the Absolute Encoder offset to the encoder fails.
*/
private Alert encoderOffsetWarning = new Alert("Motors",
"Pushing the Absolute Encoder offset to the encoder failed on module #" +
moduleNumber,
Alert.AlertType.WARNING);
/**
* An {@link Alert} for if there is no Absolute Encoder on the module.
*/
private Alert noEncoderWarning = new Alert("Motors",
"There is no Absolute Encoder on module #" +
moduleNumber,
Alert.AlertType.WARNING);

/**
* Construct the swerve module and initialize the swerve module motors and absolute encoder.
Expand Down Expand Up @@ -143,6 +137,15 @@ public SwerveModule(int moduleNumber, SwerveModuleConfiguration moduleConfigurat
}

lastState = getState();

noEncoderWarning = new Alert("Motors",
"There is no Absolute Encoder on module #" +
moduleNumber,
Alert.AlertType.WARNING);
encoderOffsetWarning = new Alert("Motors",
"Pushing the Absolute Encoder offset to the encoder failed on module #" +
moduleNumber,
Alert.AlertType.WARNING);
}

/**
Expand Down
20 changes: 11 additions & 9 deletions src/main/java/swervelib/encoders/AnalogAbsoluteEncoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,21 +18,15 @@ public class AnalogAbsoluteEncoderSwerve extends SwerveAbsoluteEncoder
/**
* Inversion state of the encoder.
*/
private boolean inverted = false;
private boolean inverted = false;
/**
* An {@link Alert} for if the absolute encoder offset cannot be set.
*/
private Alert cannotSetOffset = new Alert(
"Encoders",
"Cannot Set Absolute Encoder Offset of Analog Encoders Channel #" + encoder.getChannel(),
Alert.AlertType.WARNING);
private Alert cannotSetOffset;
/**
* An {@link Alert} detailing how the analog absolute encoder may not report accurate velocities.
*/
private Alert inaccurateVelocities = new Alert(
"Encoders",
"The Analog Absolute encoder may not report accurate velocities!",
Alert.AlertType.WARNING_TRACE);
private Alert inaccurateVelocities;

/**
* Construct the Thrifty Encoder as a Swerve Absolute Encoder.
Expand All @@ -42,6 +36,14 @@ public class AnalogAbsoluteEncoderSwerve extends SwerveAbsoluteEncoder
public AnalogAbsoluteEncoderSwerve(AnalogInput encoder)
{
this.encoder = encoder;
cannotSetOffset = new Alert(
"Encoders",
"Cannot Set Absolute Encoder Offset of Analog Encoders Channel #" + encoder.getChannel(),
Alert.AlertType.WARNING);
inaccurateVelocities = new Alert(
"Encoders",
"The Analog Absolute encoder may not report accurate velocities!",
Alert.AlertType.WARNING_TRACE);
}

/**
Expand Down
40 changes: 22 additions & 18 deletions src/main/java/swervelib/encoders/CANCoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,33 +24,19 @@ public class CANCoderSwerve extends SwerveAbsoluteEncoder
/**
* An {@link Alert} for if the CANCoder magnet field is less than ideal.
*/
private Alert magnetFieldLessThanIdeal = new Alert(
"Encoders",
"CANCoder " + encoder.getDeviceID() + " magnetic field is less than ideal.",
Alert.AlertType.WARNING);
private Alert magnetFieldLessThanIdeal;
/**
* An {@link Alert} for if the CANCoder reading is faulty.
*/
private Alert readingFaulty = new Alert(
"Encoders",
"CANCoder " + encoder.getDeviceID() + " reading was faulty.",
Alert.AlertType.WARNING);
private Alert readingFaulty;
/**
* An {@link Alert} for if the CANCoder reading is faulty and the reading is ignored.
*/
private Alert readingIgnored = new Alert(
"Encoders",
"CANCoder " + encoder.getDeviceID() + " reading was faulty, ignoring.",
Alert.AlertType.WARNING);
private Alert readingIgnored;
/**
* An {@link Alert} for if the absolute encoder offset cannot be set.
*/
private Alert cannotSetOffset = new Alert(
"Encoders",
"Failure to set CANCoder "
+ encoder.getDeviceID()
+ " Absolute Encoder Offset",
Alert.AlertType.WARNING);
private Alert cannotSetOffset;

/**
* Initialize the CANCoder on the standard CANBus.
Expand All @@ -71,6 +57,24 @@ public CANCoderSwerve(int id)
public CANCoderSwerve(int id, String canbus)
{
encoder = new CANcoder(id, canbus);
magnetFieldLessThanIdeal = new Alert(
"Encoders",
"CANCoder " + encoder.getDeviceID() + " magnetic field is less than ideal.",
Alert.AlertType.WARNING);
readingFaulty = new Alert(
"Encoders",
"CANCoder " + encoder.getDeviceID() + " reading was faulty.",
Alert.AlertType.WARNING);
readingIgnored = new Alert(
"Encoders",
"CANCoder " + encoder.getDeviceID() + " reading was faulty, ignoring.",
Alert.AlertType.WARNING);
cannotSetOffset = new Alert(
"Encoders",
"Failure to set CANCoder "
+ encoder.getDeviceID()
+ " Absolute Encoder Offset",
Alert.AlertType.WARNING);
}

/**
Expand Down
11 changes: 6 additions & 5 deletions src/main/java/swervelib/encoders/PWMDutyCycleEncoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,7 @@ public class PWMDutyCycleEncoderSwerve extends SwerveAbsoluteEncoder
/**
* An {@link Alert} for if the encoder cannot report accurate velocities.
*/
private Alert inaccurateVelocities = new Alert(
"Encoders",
"The PWM Duty Cycle encoder may not report accurate velocities!",
Alert.AlertType.WARNING_TRACE);

private Alert inaccurateVelocities;

/**
* Constructor for the PWM duty cycle encoder.
Expand All @@ -39,6 +35,11 @@ public class PWMDutyCycleEncoderSwerve extends SwerveAbsoluteEncoder
public PWMDutyCycleEncoderSwerve(int pin)
{
encoder = new DutyCycleEncoder(pin);
inaccurateVelocities = new Alert(
"Encoders",
"The PWM Duty Cycle encoder may not report accurate velocities!",
Alert.AlertType.WARNING_TRACE);

}

/**
Expand Down
19 changes: 11 additions & 8 deletions src/main/java/swervelib/encoders/SparkMaxAnalogEncoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,17 +21,11 @@ public class SparkMaxAnalogEncoderSwerve extends SwerveAbsoluteEncoder
/**
* An {@link Alert} for if there is a failure configuring the encoder.
*/
private Alert failureConfiguring = new Alert(
"Encoders",
"Failure configuring SparkMax Analog Encoder",
Alert.AlertType.WARNING_TRACE);
private Alert failureConfiguring;
/**
* An {@link Alert} for if the absolute encoder does not support integrated offsets.
*/
private Alert doesNotSupportIntegratedOffsets = new Alert(
"Encoders",
"SparkMax Analog Sensors do not support integrated offsets",
Alert.AlertType.WARNING_TRACE);
private Alert doesNotSupportIntegratedOffsets;


/**
Expand All @@ -49,6 +43,15 @@ public SparkMaxAnalogEncoderSwerve(SwerveMotor motor)
{
throw new RuntimeException("Motor given to instantiate SparkMaxEncoder is not a CANSparkMax");
}
failureConfiguring = new Alert(
"Encoders",
"Failure configuring SparkMax Analog Encoder",
Alert.AlertType.WARNING_TRACE);
doesNotSupportIntegratedOffsets = new Alert(
"Encoders",
"SparkMax Analog Sensors do not support integrated offsets",
Alert.AlertType.WARNING_TRACE);

}

/**
Expand Down
21 changes: 13 additions & 8 deletions src/main/java/swervelib/encoders/SparkMaxEncoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,14 +21,11 @@ public class SparkMaxEncoderSwerve extends SwerveAbsoluteEncoder
/**
* An {@link Alert} for if there is a failure configuring the encoder.
*/
private Alert failureConfiguring = new Alert(
"Encoders",
"Failure configuring SparkMax Analog Encoder",
Alert.AlertType.WARNING_TRACE);
private Alert offsetFailure = new Alert(
"Encoders",
"Failure to set Absolute Encoder Offset",
Alert.AlertType.WARNING_TRACE);
private Alert failureConfiguring;
/**
* An {@link Alert} for if there is a failure configuring the encoder offset.
*/
private Alert offsetFailure;

/**
* Create the {@link SparkMaxEncoderSwerve} object as a duty cycle from the {@link CANSparkMax} motor.
Expand All @@ -47,6 +44,14 @@ public SparkMaxEncoderSwerve(SwerveMotor motor, int conversionFactor)
{
throw new RuntimeException("Motor given to instantiate SparkMaxEncoder is not a CANSparkMax");
}
failureConfiguring = new Alert(
"Encoders",
"Failure configuring SparkMax Analog Encoder",
Alert.AlertType.WARNING_TRACE);
offsetFailure = new Alert(
"Encoders",
"Failure to set Absolute Encoder Offset",
Alert.AlertType.WARNING_TRACE);
}

/**
Expand Down
5 changes: 3 additions & 2 deletions src/main/java/swervelib/imu/NavXSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,11 +23,11 @@ public class NavXSwerve extends SwerveIMU
/**
* Offset for the NavX.
*/
private Rotation3d offset = new Rotation3d();
private Rotation3d offset = new Rotation3d();
/**
* An {@link Alert} for if there is an error instantiating the NavX.
*/
private Alert navXError = new Alert("IMU", "Error instantiating NavX.", Alert.AlertType.ERROR_TRACE);
private Alert navXError;

/**
* Constructor for the NavX swerve.
Expand All @@ -36,6 +36,7 @@ public class NavXSwerve extends SwerveIMU
*/
public NavXSwerve(SerialPort.Port port)
{
navXError = new Alert("IMU", "Error instantiating NavX.", Alert.AlertType.ERROR_TRACE);
try
{
/* Communicate w/navX-MXP via the MXP SPI Bus. */
Expand Down
21 changes: 12 additions & 9 deletions src/main/java/swervelib/motors/SparkFlexSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -43,21 +43,15 @@ public class SparkFlexSwerve extends SwerveMotor
/**
* Factory default already occurred.
*/
private boolean factoryDefaultOccurred = false;
private boolean factoryDefaultOccurred = false;
/**
* An {@link Alert} for if there is an error configuring the motor.
*/
private Alert failureConfiguring = new Alert("Motors",
"Failure configuring motor " +
motor.getDeviceId(),
Alert.AlertType.WARNING_TRACE);
private Alert failureConfiguring;
/**
* An {@link Alert} for if the absolute encoder's offset is set in the json instead of the hardware client.
*/
private Alert absoluteEncoderOffsetWarning = new Alert("Motors",
"IF possible configure the duty cycle encoder offset in the REV Hardware Client instead of using the " +
"absoluteEncoderOffset in the Swerve Module JSON!",
Alert.AlertType.WARNING);
private Alert absoluteEncoderOffsetWarning;

/**
* Initialize the swerve motor.
Expand All @@ -79,6 +73,15 @@ public SparkFlexSwerve(CANSparkFlex motor, boolean isDriveMotor)

// Spin off configurations in a different thread.
// configureSparkMax(() -> motor.setCANTimeout(0)); // Commented out because it prevents feedback.
failureConfiguring = new Alert("Motors",
"Failure configuring motor " +
motor.getDeviceId(),
Alert.AlertType.WARNING_TRACE);
absoluteEncoderOffsetWarning = new Alert("Motors",
"IF possible configure the duty cycle encoder offset in the REV Hardware Client instead of using the " +
"absoluteEncoderOffset in the Swerve Module JSON!",
Alert.AlertType.WARNING);

}

/**
Expand Down
24 changes: 14 additions & 10 deletions src/main/java/swervelib/motors/SparkMaxBrushedMotorSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,25 +42,19 @@ public class SparkMaxBrushedMotorSwerve extends SwerveMotor
/**
* Factory default already occurred.
*/
private boolean factoryDefaultOccurred = false;
private boolean factoryDefaultOccurred = false;
/**
* An {@link Alert} for if the motor has no encoder.
*/
private Alert noEncoderAlert = new Alert("Motors",
"Cannot use motor without encoder.",
Alert.AlertType.ERROR_TRACE);
private Alert noEncoderAlert;
/**
* An {@link Alert} for if there is an error configuring the motor.
*/
private Alert failureConfiguringAlert = new Alert("Motors",
"Failure configuring motor " + motor.getDeviceId(),
Alert.AlertType.WARNING_TRACE);
private Alert failureConfiguringAlert;
/**
* An {@link Alert} for if the motor has no encoder defined.
*/
private Alert noEncoderDefinedAlert = new Alert("Motors",
"An encoder MUST be defined to work with a SparkMAX",
Alert.AlertType.ERROR_TRACE);
private Alert noEncoderDefinedAlert;

/**
* Initialize the swerve motor.
Expand Down Expand Up @@ -108,6 +102,16 @@ public SparkMaxBrushedMotorSwerve(CANSparkMax motor, boolean isDriveMotor, Type
}
// Spin off configurations in a different thread.
// configureSparkMax(() -> motor.setCANTimeout(0)); // Commented it out because it prevents feedback.

noEncoderAlert = new Alert("Motors",
"Cannot use motor without encoder.",
Alert.AlertType.ERROR_TRACE);
failureConfiguringAlert = new Alert("Motors",
"Failure configuring motor " + motor.getDeviceId(),
Alert.AlertType.WARNING_TRACE);
noEncoderDefinedAlert = new Alert("Motors",
"An encoder MUST be defined to work with a SparkMAX",
Alert.AlertType.ERROR_TRACE);
}

/**
Expand Down
10 changes: 5 additions & 5 deletions src/main/java/swervelib/motors/TalonFXSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,19 +20,19 @@ public class TalonFXSwerve extends SwerveMotor
/**
* Factory default already occurred.
*/
private final boolean factoryDefaultOccurred = false;
private final boolean factoryDefaultOccurred = false;
/**
* Whether the absolute encoder is integrated.
*/
private final boolean absoluteEncoder = false;
private final boolean absoluteEncoder = false;
/**
* Motion magic angle voltage setter.
*/
private final MotionMagicVoltage m_angleVoltageSetter = new MotionMagicVoltage(0);
private final MotionMagicVoltage m_angleVoltageSetter = new MotionMagicVoltage(0);
/**
* Velocity voltage setter for controlling drive motor.
*/
private final VelocityVoltage m_velocityVoltageSetter = new VelocityVoltage(0);
private final VelocityVoltage m_velocityVoltageSetter = new VelocityVoltage(0);
// /**
// * Motion Magic exponential voltage setters.
// */
Expand All @@ -44,7 +44,7 @@ public class TalonFXSwerve extends SwerveMotor
/**
* Current TalonFX configuration.
*/
private TalonFXConfiguration configuration = new TalonFXConfiguration();
private TalonFXConfiguration configuration = new TalonFXConfiguration();

/**
* Constructor for TalonFX swerve motor.
Expand Down
Loading

0 comments on commit 35ff0b8

Please sign in to comment.