Skip to content

Commit

Permalink
Fixed NetworkAlerts
Browse files Browse the repository at this point in the history
  • Loading branch information
thenetworkgrinch committed Jan 17, 2024
1 parent f16ca43 commit 1ca3db2
Show file tree
Hide file tree
Showing 19 changed files with 510 additions and 108 deletions.
23 changes: 11 additions & 12 deletions swervelib/SwerveDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.geometry.Twist2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
Expand Down Expand Up @@ -67,6 +66,10 @@ public class SwerveDrive
* Odometry lock to ensure thread safety.
*/
private final Lock odometryLock = new ReentrantLock();
/**
* Deadband for speeds in heading correction.
*/
private final double HEADING_CORRECTION_DEADBAND = 0.01;
/**
* Field object.
*/
Expand Down Expand Up @@ -100,14 +103,14 @@ public class SwerveDrive
* correction.
*/
public boolean chassisVelocityCorrection = true;
/**
* Whether heading correction PID is currently active.
*/
private boolean correctionEnabled = false;
/**
* Whether to correct heading when driving translationally. Set to true to enable.
*/
public boolean headingCorrection = false;
/**
* Whether heading correction PID is currently active.
*/
private boolean correctionEnabled = false;
/**
* Swerve IMU device for sensing the heading of the robot.
*/
Expand All @@ -120,10 +123,6 @@ public class SwerveDrive
* Counter to synchronize the modules relative encoder with absolute encoder when not moving.
*/
private int moduleSynchronizationCounter = 0;
/**
* Deadband for speeds in heading correction.
*/
private final double HEADING_CORRECTION_DEADBAND = 0.01;
/**
* The last heading set in radians.
*/
Expand Down Expand Up @@ -413,10 +412,10 @@ public void drive(ChassisSpeeds velocity, boolean isOpenLoop, Translation2d cent
if (headingCorrection)
{
if (Math.abs(velocity.omegaRadiansPerSecond) < HEADING_CORRECTION_DEADBAND
&& (Math.abs(velocity.vxMetersPerSecond) > HEADING_CORRECTION_DEADBAND
|| Math.abs(velocity.vyMetersPerSecond) > HEADING_CORRECTION_DEADBAND))
&& (Math.abs(velocity.vxMetersPerSecond) > HEADING_CORRECTION_DEADBAND
|| Math.abs(velocity.vyMetersPerSecond) > HEADING_CORRECTION_DEADBAND))
{
if (!correctionEnabled)
if (!correctionEnabled)
{
lastHeadingRadians = getYaw().getRadians();
correctionEnabled = true;
Expand Down
24 changes: 20 additions & 4 deletions swervelib/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,13 @@
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import swervelib.encoders.SwerveAbsoluteEncoder;
import swervelib.math.SwerveMath;
import swervelib.motors.SwerveMotor;
import swervelib.parser.SwerveModuleConfiguration;
import swervelib.simulation.SwerveModuleSimulation;
import swervelib.telemetry.Alert;
import swervelib.telemetry.SwerveDriveTelemetry;
import swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity;

Expand All @@ -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 @@ -129,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 Expand Up @@ -399,12 +416,11 @@ public void pushOffsetsToControllers()
angleOffset = 0;
} else
{
DriverStation.reportWarning(
"Pushing the Absolute Encoder offset to the encoder failed on module #" + moduleNumber, false);
encoderOffsetWarning.set(true);
}
} else
{
DriverStation.reportWarning("There is no Absolute Encoder on module #" + moduleNumber, false);
noEncoderWarning.set(true);
}
}

Expand Down
23 changes: 19 additions & 4 deletions swervelib/encoders/AnalogAbsoluteEncoderSwerve.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
package swervelib.encoders;

import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotController;
import swervelib.telemetry.Alert;

/**
* Swerve Absolute Encoder for Thrifty Encoders and other analog encoders.
Expand All @@ -19,6 +19,14 @@ public class AnalogAbsoluteEncoderSwerve extends SwerveAbsoluteEncoder
* Inversion state of the encoder.
*/
private boolean inverted = false;
/**
* An {@link Alert} for if the absolute encoder offset cannot be set.
*/
private Alert cannotSetOffset;
/**
* An {@link Alert} detailing how the analog absolute encoder may not report accurate velocities.
*/
private Alert inaccurateVelocities;

/**
* Construct the Thrifty Encoder as a Swerve Absolute Encoder.
Expand All @@ -28,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 Expand Up @@ -101,8 +117,7 @@ public Object getAbsoluteEncoder()
public boolean setAbsoluteEncoderOffset(double offset)
{
//Do Nothing
DriverStation.reportWarning(
"Cannot Set Absolute Encoder Offset of Analog Encoders Channel #" + encoder.getChannel(), false);
cannotSetOffset.set(true);
return false;
}

Expand All @@ -114,7 +129,7 @@ public boolean setAbsoluteEncoderOffset(double offset)
@Override
public double getVelocity()
{
DriverStation.reportWarning("The Analog Absolute encoder may not report accurate velocities!", true);
inaccurateVelocities.set(true);
return encoder.getValue();
}
}
64 changes: 53 additions & 11 deletions swervelib/encoders/CANCoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
import com.ctre.phoenix6.signals.AbsoluteSensorRangeValue;
import com.ctre.phoenix6.signals.MagnetHealthValue;
import com.ctre.phoenix6.signals.SensorDirectionValue;
import edu.wpi.first.wpilibj.DriverStation;
import swervelib.telemetry.Alert;

/**
* Swerve Absolute Encoder for CTRE CANCoders.
Expand All @@ -20,7 +20,23 @@ public class CANCoderSwerve extends SwerveAbsoluteEncoder
/**
* CANCoder with WPILib sendable and support.
*/
public CANcoder encoder;
public CANcoder encoder;
/**
* An {@link Alert} for if the CANCoder magnet field is less than ideal.
*/
private Alert magnetFieldLessThanIdeal;
/**
* An {@link Alert} for if the CANCoder reading is faulty.
*/
private Alert readingFaulty;
/**
* An {@link Alert} for if the CANCoder reading is faulty and the reading is ignored.
*/
private Alert readingIgnored;
/**
* An {@link Alert} for if the absolute encoder offset cannot be set.
*/
private Alert cannotSetOffset;

/**
* Initialize the CANCoder on the standard CANBus.
Expand All @@ -41,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 Expand Up @@ -89,17 +123,17 @@ public double getAbsolutePosition()
readingError = false;
MagnetHealthValue strength = encoder.getMagnetHealth().getValue();

if (strength != MagnetHealthValue.Magnet_Green)
{
DriverStation.reportWarning(
"CANCoder " + encoder.getDeviceID() + " magnetic field is less than ideal.\n", false);
}
magnetFieldLessThanIdeal.set(strength != MagnetHealthValue.Magnet_Green);
if (strength == MagnetHealthValue.Magnet_Invalid || strength == MagnetHealthValue.Magnet_Red)
{
readingError = true;
DriverStation.reportWarning("CANCoder " + encoder.getDeviceID() + " reading was faulty.\n", false);
readingFaulty.set(true);
return 0;
} else
{
readingFaulty.set(false);
}

StatusSignal<Double> angle = encoder.getAbsolutePosition().refresh();

// Taken from democat's library.
Expand All @@ -115,7 +149,10 @@ public double getAbsolutePosition()
if (angle.getStatus() != StatusCode.OK)
{
readingError = true;
DriverStation.reportWarning("CANCoder " + encoder.getDeviceID() + " reading was faulty, ignoring.\n", false);
readingIgnored.set(true);
} else
{
readingIgnored.set(false);
}

return angle.getValue() * 360;
Expand Down Expand Up @@ -149,12 +186,17 @@ public boolean setAbsoluteEncoderOffset(double offset)
return false;
}
error = cfg.apply(magCfg.withMagnetOffset(offset / 360));
cannotSetOffset.setText(
"Failure to set CANCoder "
+ encoder.getDeviceID()
+ " Absolute Encoder Offset Error: "
+ error);
if (error == StatusCode.OK)
{
cannotSetOffset.set(false);
return true;
}
DriverStation.reportWarning(
"Failure to set CANCoder " + encoder.getDeviceID() + " Absolute Encoder Offset Error: " + error, false);
cannotSetOffset.set(true);
return false;
}

Expand Down
2 changes: 1 addition & 1 deletion swervelib/encoders/CanAndCoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ public CanAndCoderSwerve(int canid)

/**
* Reset the encoder to factory defaults.
*
* <p>
* This will not clear the stored zero offset.
*/
@Override
Expand Down
13 changes: 11 additions & 2 deletions swervelib/encoders/PWMDutyCycleEncoderSwerve.java
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
package swervelib.encoders;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DutyCycleEncoder;
import swervelib.telemetry.Alert;

/**
* DutyCycle encoders such as "US Digital MA3 with PWM Output, the CTRE Mag Encoder, the Rev Hex Encoder, and the AM Mag
Expand All @@ -22,6 +22,10 @@ public class PWMDutyCycleEncoderSwerve extends SwerveAbsoluteEncoder
* Inversion state.
*/
private boolean isInverted;
/**
* An {@link Alert} for if the encoder cannot report accurate velocities.
*/
private Alert inaccurateVelocities;

/**
* Constructor for the PWM duty cycle encoder.
Expand All @@ -31,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 Expand Up @@ -74,7 +83,7 @@ public Object getAbsoluteEncoder()
@Override
public double getVelocity()
{
DriverStation.reportWarning("The PWM Duty Cycle encoder may not report accurate velocities!", true);
inaccurateVelocities.set(true);
return encoder.get();
}

Expand Down
Loading

0 comments on commit 1ca3db2

Please sign in to comment.