diff --git a/examples/drivebase_only_2026/src/main/deploy/swerve/falcon/modules/backleft.json b/examples/drivebase_only_2026/src/main/deploy/swerve/falcon/modules/backleft.json index 547032e..4aa80af 100644 --- a/examples/drivebase_only_2026/src/main/deploy/swerve/falcon/modules/backleft.json +++ b/examples/drivebase_only_2026/src/main/deploy/swerve/falcon/modules/backleft.json @@ -1,4 +1,15 @@ { + "conversionFactors": { + "angle": { + "gearRatio": 1.4285714286, + "factor": 0 + }, + "drive": { + "gearRatio": 8.14, + "diameter": 4, + "factor": 0 + } + }, "drive": { "type": "talonfx", "id": 4, diff --git a/yagsl/java/swervelib/SwerveDrive.java b/yagsl/java/swervelib/SwerveDrive.java index 46ddce2..8140c29 100644 --- a/yagsl/java/swervelib/SwerveDrive.java +++ b/yagsl/java/swervelib/SwerveDrive.java @@ -36,7 +36,6 @@ import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Force; import edu.wpi.first.units.measure.LinearVelocity; -import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.Notifier; @@ -51,19 +50,18 @@ import java.util.Optional; import java.util.concurrent.locks.Lock; import java.util.concurrent.locks.ReentrantLock; -import swervelib.parser.deserializer.ReflectionsManager; -import swervelib.parser.deserializer.ReflectionsManager.VENDOR; -import swervelib.simulation.ironmaple.simulation.SimulatedArena; -import swervelib.simulation.ironmaple.simulation.drivesims.AbstractDriveTrainSimulation; -import swervelib.simulation.ironmaple.simulation.drivesims.SwerveDriveSimulation; -import swervelib.simulation.ironmaple.simulation.drivesims.configs.DriveTrainSimulationConfig; -import swervelib.simulation.ironmaple.simulation.drivesims.configs.SwerveModuleSimulationConfig; import swervelib.imu.SwerveIMU; import swervelib.math.SwerveMath; import swervelib.parser.Cache; import swervelib.parser.SwerveControllerConfiguration; import swervelib.parser.SwerveDriveConfiguration; import swervelib.simulation.SwerveIMUSimulation; +import swervelib.simulation.ironmaple.simulation.SimulatedArena; +import swervelib.simulation.ironmaple.simulation.drivesims.AbstractDriveTrainSimulation; +import swervelib.simulation.ironmaple.simulation.drivesims.SwerveDriveSimulation; +import swervelib.simulation.ironmaple.simulation.drivesims.configs.DriveTrainSimulationConfig; +import swervelib.simulation.ironmaple.simulation.drivesims.configs.SwerveModuleSimulationConfig; +import swervelib.telemetry.Alert; import swervelib.telemetry.SwerveDriveTelemetry; import swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity; diff --git a/yagsl/java/swervelib/SwerveModule.java b/yagsl/java/swervelib/SwerveModule.java index b639280..dd1dc27 100644 --- a/yagsl/java/swervelib/SwerveModule.java +++ b/yagsl/java/swervelib/SwerveModule.java @@ -14,7 +14,6 @@ import edu.wpi.first.networktables.NetworkTableInstance; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.LinearVelocity; -import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import swervelib.encoders.SparkMaxEncoderSwerve; @@ -28,6 +27,7 @@ import swervelib.parser.SwerveModuleConfiguration; import swervelib.parser.SwerveModulePhysicalCharacteristics; import swervelib.simulation.SwerveModuleSimulation; +import swervelib.telemetry.Alert; import swervelib.telemetry.SwerveDriveTelemetry; import swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity; diff --git a/yagsl/java/swervelib/encoders/AnalogAbsoluteEncoderSwerve.java b/yagsl/java/swervelib/encoders/AnalogAbsoluteEncoderSwerve.java index 3d91c6f..2fc0f5c 100644 --- a/yagsl/java/swervelib/encoders/AnalogAbsoluteEncoderSwerve.java +++ b/yagsl/java/swervelib/encoders/AnalogAbsoluteEncoderSwerve.java @@ -1,9 +1,9 @@ package swervelib.encoders; -import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj.AnalogInput; import edu.wpi.first.wpilibj.RobotController; +import swervelib.telemetry.Alert; /** * Swerve Absolute Encoder for Thrifty Encoders and other analog encoders. diff --git a/yagsl/java/swervelib/encoders/DIODutyCycleEncoderSwerve.java b/yagsl/java/swervelib/encoders/DIODutyCycleEncoderSwerve.java index f8841bc..799eda8 100644 --- a/yagsl/java/swervelib/encoders/DIODutyCycleEncoderSwerve.java +++ b/yagsl/java/swervelib/encoders/DIODutyCycleEncoderSwerve.java @@ -1,9 +1,9 @@ package swervelib.encoders; -import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj.DutyCycleEncoder; import edu.wpi.first.wpilibj.Timer; +import swervelib.telemetry.Alert; /** * DutyCycle encoders such as "US Digital MA3 with DIO Output, the CTRE Mag Encoder, the Rev Hex Encoder, and the AM Mag diff --git a/yagsl/java/swervelib/encoders/SparkMaxEncoderSwerve.java b/yagsl/java/swervelib/encoders/SparkMaxEncoderSwerve.java index e23a256..4213868 100644 --- a/yagsl/java/swervelib/encoders/SparkMaxEncoderSwerve.java +++ b/yagsl/java/swervelib/encoders/SparkMaxEncoderSwerve.java @@ -5,12 +5,12 @@ import com.revrobotics.spark.SparkAbsoluteEncoder; import com.revrobotics.spark.SparkMax; import com.revrobotics.spark.config.SparkMaxConfig; -import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import java.util.function.Supplier; import swervelib.motors.SparkMaxBrushedMotorSwerve; import swervelib.motors.SparkMaxSwerve; import swervelib.motors.SwerveMotor; +import swervelib.telemetry.Alert; /** * SparkMax absolute encoder, attached through the data port. diff --git a/yagsl/java/swervelib/imu/NavX3Swerve.java b/yagsl/java/swervelib/imu/NavX3Swerve.java index d9e095e..93b0cac 100644 --- a/yagsl/java/swervelib/imu/NavX3Swerve.java +++ b/yagsl/java/swervelib/imu/NavX3Swerve.java @@ -1,18 +1,15 @@ package swervelib.imu; -import static edu.wpi.first.units.Units.Degree; import static edu.wpi.first.units.Units.DegreesPerSecond; -import static edu.wpi.first.units.Units.Milliseconds; import com.studica.frc.Navx; import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.MutAngularVelocity; -import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; -import edu.wpi.first.wpilibj.Timer; import java.util.Optional; +import swervelib.telemetry.Alert; /** * Communicates with the NavX({@link Navx}) as the IMU. diff --git a/yagsl/java/swervelib/imu/NavXSwerve.java b/yagsl/java/swervelib/imu/NavXSwerve.java index c4b8322..47844b6 100644 --- a/yagsl/java/swervelib/imu/NavXSwerve.java +++ b/yagsl/java/swervelib/imu/NavXSwerve.java @@ -7,9 +7,9 @@ import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.units.measure.MutAngularVelocity; -import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import java.util.Optional; +import swervelib.telemetry.Alert; /** * Communicates with the NavX({@link AHRS}) as the IMU. diff --git a/yagsl/java/swervelib/motors/SparkFlexSwerve.java b/yagsl/java/swervelib/motors/SparkFlexSwerve.java index 9e3cab6..346817f 100644 --- a/yagsl/java/swervelib/motors/SparkFlexSwerve.java +++ b/yagsl/java/swervelib/motors/SparkFlexSwerve.java @@ -17,7 +17,6 @@ import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; import com.revrobotics.spark.config.SparkFlexConfig; import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.Timer; @@ -25,6 +24,7 @@ import java.util.function.Supplier; import swervelib.encoders.SwerveAbsoluteEncoder; import swervelib.parser.PIDFConfig; +import swervelib.telemetry.Alert; import swervelib.telemetry.SwerveDriveTelemetry; /** diff --git a/yagsl/java/swervelib/motors/SparkMaxBrushedMotorSwerve.java b/yagsl/java/swervelib/motors/SparkMaxBrushedMotorSwerve.java index 46e96d5..96797b1 100644 --- a/yagsl/java/swervelib/motors/SparkMaxBrushedMotorSwerve.java +++ b/yagsl/java/swervelib/motors/SparkMaxBrushedMotorSwerve.java @@ -16,7 +16,6 @@ import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; import com.revrobotics.spark.config.SparkMaxConfig; import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.Timer; @@ -26,6 +25,7 @@ import swervelib.encoders.SparkMaxEncoderSwerve; import swervelib.encoders.SwerveAbsoluteEncoder; import swervelib.parser.PIDFConfig; +import swervelib.telemetry.Alert; import swervelib.telemetry.SwerveDriveTelemetry; /** diff --git a/yagsl/java/swervelib/parser/json/PhysicalPropertiesJson.java b/yagsl/java/swervelib/parser/json/PhysicalPropertiesJson.java index 197089d..aaca133 100644 --- a/yagsl/java/swervelib/parser/json/PhysicalPropertiesJson.java +++ b/yagsl/java/swervelib/parser/json/PhysicalPropertiesJson.java @@ -3,8 +3,6 @@ import static edu.wpi.first.units.Units.Kilogram; import static edu.wpi.first.units.Units.Pounds; -import edu.wpi.first.wpilibj.Alert; -import edu.wpi.first.wpilibj.Alert.AlertType; import swervelib.parser.SwerveModulePhysicalCharacteristics; import swervelib.parser.json.modules.ConversionFactorsJson; diff --git a/yagsl/java/swervelib/telemetry/Alert.java b/yagsl/java/swervelib/telemetry/Alert.java new file mode 100644 index 0000000..4f4cd73 --- /dev/null +++ b/yagsl/java/swervelib/telemetry/Alert.java @@ -0,0 +1,90 @@ +package swervelib.telemetry; + +import edu.wpi.first.wpilibj.Alert.AlertType; +import edu.wpi.first.wpilibj.DriverStation; + +/** + * Thread-safe psuedo-Alert class + */ +public class Alert +{ + + /** + * Group of the alert + */ + public final String group; + /** + * Text of the alert + */ + private String text; + /** + * Type of the alert + */ + public final AlertType type; + private boolean toggle = false; + + /** + * Create a new Alert + * + * @param group Group of the alert + * @param text Text of the alert + * @param type Type of the alert + */ + public Alert(String group, String text, AlertType type) + { + this.group = group; + this.text = text; + this.type = type; + } + + /** + * Create a new Alert + * + * @param text Text of the alert + * @param type Type of the alert + */ + public Alert(String text, AlertType type) + { + this("", text, type); + } + + + /** + * Toggle the alert + * + * @param toggle + */ + public void set(boolean toggle) + { + this.toggle = toggle; + if (toggle) + { + String msg = "[" + group + "] " + text; + switch (type) + { + case kError: + DriverStation.reportError(msg, toggle); + break; + case kInfo: + case kWarning: + DriverStation.reportWarning(msg, toggle); + break; + } + } + } + + /*** + * Set the text of the alert + * @param text Text of the alert + */ + public void setText(String text) + { + this.text = text; + } + + /// Does nothing + public void close() + { + set(false); + } +} diff --git a/yagsl/java/swervelib/telemetry/SwerveDriveTelemetry.java b/yagsl/java/swervelib/telemetry/SwerveDriveTelemetry.java index a069792..9cb7cc5 100644 --- a/yagsl/java/swervelib/telemetry/SwerveDriveTelemetry.java +++ b/yagsl/java/swervelib/telemetry/SwerveDriveTelemetry.java @@ -9,7 +9,6 @@ import edu.wpi.first.networktables.StringPublisher; import edu.wpi.first.networktables.StructArrayPublisher; import edu.wpi.first.networktables.StructPublisher; -import edu.wpi.first.wpilibj.Alert; import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.RobotBase;