diff --git a/README.md b/README.md index 0685a05..bc5be07 100644 --- a/README.md +++ b/README.md @@ -11,6 +11,6 @@ We use these a lot and highly recommend them! # TRIGONLib [![](https://jitpack.io/v/Programming-TRIGON/TRIGONLib.svg)](https://jitpack.io/#Programming-TRIGON/TRIGONLib) -[TRIGON 5990's library](https://github.com/Programming-TRIGON/TRIGONLib) for automatic Advantage Kit and Simulation -hardware wrappers, utilities, commands, and more. -This library is used from the `org.trigon` import. +[TRIGON 5990's library](https://github.com/Programming-TRIGON/RobotCodeOffSeason2025/tree/main/src/main/java/lib) for +automatic Advantage Kit and Simulation +hardware wrappers, utilities, commands, and more. \ No newline at end of file diff --git a/src/main/java/frc/trigon/robot/Robot.java b/src/main/java/frc/trigon/robot/Robot.java index 0ee7917..e418b1d 100644 --- a/src/main/java/frc/trigon/robot/Robot.java +++ b/src/main/java/frc/trigon/robot/Robot.java @@ -14,7 +14,7 @@ import org.littletonrobotics.junction.networktables.NT4Publisher; import org.littletonrobotics.junction.wpilog.WPILOGReader; import org.littletonrobotics.junction.wpilog.WPILOGWriter; -import trigon.hardware.RobotHardwareStats; +import lib.hardware.RobotHardwareStats; public class Robot extends LoggedRobot { public static final boolean IS_REAL = Robot.isReal(); diff --git a/src/main/java/frc/trigon/robot/RobotContainer.java b/src/main/java/frc/trigon/robot/RobotContainer.java index 1a871d6..5c6e9e3 100644 --- a/src/main/java/frc/trigon/robot/RobotContainer.java +++ b/src/main/java/frc/trigon/robot/RobotContainer.java @@ -21,7 +21,7 @@ import frc.trigon.robot.subsystems.MotorSubsystem; import frc.trigon.robot.subsystems.swerve.Swerve; import org.littletonrobotics.junction.networktables.LoggedDashboardChooser; -import trigon.utilities.flippable.Flippable; +import lib.utilities.flippable.Flippable; public class RobotContainer { public static final PoseEstimator ROBOT_POSE_ESTIMATOR = new PoseEstimator(); diff --git a/src/main/java/frc/trigon/robot/commands/CommandConstants.java b/src/main/java/frc/trigon/robot/commands/CommandConstants.java index cc1c4e2..dc45c90 100644 --- a/src/main/java/frc/trigon/robot/commands/CommandConstants.java +++ b/src/main/java/frc/trigon/robot/commands/CommandConstants.java @@ -10,10 +10,10 @@ import frc.trigon.robot.constants.OperatorConstants; import frc.trigon.robot.constants.PathPlannerConstants; import frc.trigon.robot.subsystems.swerve.SwerveCommands; -import trigon.commands.CameraPositionCalculationCommand; -import trigon.commands.WheelRadiusCharacterizationCommand; -import trigon.hardware.misc.XboxController; -import trigon.utilities.flippable.FlippableRotation2d; +import lib.commands.CameraPositionCalculationCommand; +import lib.commands.WheelRadiusCharacterizationCommand; +import lib.hardware.misc.XboxController; +import lib.utilities.flippable.FlippableRotation2d; /** * A class that contains commands that only use parameters and don't require logic. diff --git a/src/main/java/frc/trigon/robot/commands/commandclasses/GamePieceAutoDriveCommand.java b/src/main/java/frc/trigon/robot/commands/commandclasses/GamePieceAutoDriveCommand.java index 2e8f3f0..e0663de 100644 --- a/src/main/java/frc/trigon/robot/commands/commandclasses/GamePieceAutoDriveCommand.java +++ b/src/main/java/frc/trigon/robot/commands/commandclasses/GamePieceAutoDriveCommand.java @@ -11,7 +11,7 @@ import frc.trigon.robot.misc.simulatedfield.SimulatedGamePieceConstants; import frc.trigon.robot.subsystems.swerve.SwerveCommands; import org.littletonrobotics.junction.Logger; -import trigon.utilities.flippable.FlippableRotation2d; +import lib.utilities.flippable.FlippableRotation2d; import java.util.function.Supplier; diff --git a/src/main/java/frc/trigon/robot/commands/commandclasses/IntakeAssistCommand.java b/src/main/java/frc/trigon/robot/commands/commandclasses/IntakeAssistCommand.java index 4241468..a57f347 100644 --- a/src/main/java/frc/trigon/robot/commands/commandclasses/IntakeAssistCommand.java +++ b/src/main/java/frc/trigon/robot/commands/commandclasses/IntakeAssistCommand.java @@ -12,7 +12,7 @@ import frc.trigon.robot.constants.OperatorConstants; import frc.trigon.robot.subsystems.swerve.SwerveCommands; import org.littletonrobotics.junction.Logger; -import trigon.hardware.RobotHardwareStats; +import lib.hardware.RobotHardwareStats; import java.util.function.Supplier; diff --git a/src/main/java/frc/trigon/robot/commands/commandfactories/AutonomousCommands.java b/src/main/java/frc/trigon/robot/commands/commandfactories/AutonomousCommands.java index 2bddea2..c6d3f53 100644 --- a/src/main/java/frc/trigon/robot/commands/commandfactories/AutonomousCommands.java +++ b/src/main/java/frc/trigon/robot/commands/commandfactories/AutonomousCommands.java @@ -7,7 +7,7 @@ import edu.wpi.first.wpilibj2.command.InstantCommand; import frc.trigon.robot.RobotContainer; import org.json.simple.parser.ParseException; -import trigon.utilities.flippable.FlippablePose2d; +import lib.utilities.flippable.FlippablePose2d; import java.io.IOException; import java.util.function.Supplier; diff --git a/src/main/java/frc/trigon/robot/constants/FieldConstants.java b/src/main/java/frc/trigon/robot/constants/FieldConstants.java index 1eaa9a3..9061418 100644 --- a/src/main/java/frc/trigon/robot/constants/FieldConstants.java +++ b/src/main/java/frc/trigon/robot/constants/FieldConstants.java @@ -7,7 +7,7 @@ import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Transform3d; -import trigon.utilities.FilesHandler; +import lib.utilities.FilesHandler; import java.io.IOException; import java.util.HashMap; diff --git a/src/main/java/frc/trigon/robot/constants/OperatorConstants.java b/src/main/java/frc/trigon/robot/constants/OperatorConstants.java index 614b73f..4863e1e 100644 --- a/src/main/java/frc/trigon/robot/constants/OperatorConstants.java +++ b/src/main/java/frc/trigon/robot/constants/OperatorConstants.java @@ -3,8 +3,8 @@ import edu.wpi.first.wpilibj.RobotController; import edu.wpi.first.wpilibj2.command.button.Trigger; import frc.trigon.robot.commands.commandclasses.IntakeAssistCommand; -import trigon.hardware.misc.KeyboardController; -import trigon.hardware.misc.XboxController; +import lib.hardware.misc.KeyboardController; +import lib.hardware.misc.XboxController; public class OperatorConstants { public static final double DRIVER_CONTROLLER_DEADBAND = 0.07; diff --git a/src/main/java/frc/trigon/robot/constants/PathPlannerConstants.java b/src/main/java/frc/trigon/robot/constants/PathPlannerConstants.java index 9fd554f..8b93566 100644 --- a/src/main/java/frc/trigon/robot/constants/PathPlannerConstants.java +++ b/src/main/java/frc/trigon/robot/constants/PathPlannerConstants.java @@ -11,9 +11,9 @@ import edu.wpi.first.math.trajectory.TrapezoidProfile; import frc.trigon.robot.RobotContainer; import org.json.simple.parser.ParseException; -import trigon.hardware.RobotHardwareStats; -import trigon.utilities.LocalADStarAK; -import trigon.utilities.flippable.Flippable; +import lib.hardware.RobotHardwareStats; +import lib.utilities.LocalADStarAK; +import lib.utilities.flippable.Flippable; import java.io.IOException; diff --git a/src/main/java/frc/trigon/robot/constants/RobotConstants.java b/src/main/java/frc/trigon/robot/constants/RobotConstants.java index 7748305..7105d43 100644 --- a/src/main/java/frc/trigon/robot/constants/RobotConstants.java +++ b/src/main/java/frc/trigon/robot/constants/RobotConstants.java @@ -1,8 +1,8 @@ package frc.trigon.robot.constants; import frc.trigon.robot.Robot; -import trigon.hardware.RobotHardwareStats; -import trigon.utilities.FilesHandler; +import lib.hardware.RobotHardwareStats; +import lib.utilities.FilesHandler; public class RobotConstants { public static final String CANIVORE_NAME = "SwerveCANivore"; diff --git a/src/main/java/frc/trigon/robot/misc/objectdetectioncamera/ObjectDetectionCamera.java b/src/main/java/frc/trigon/robot/misc/objectdetectioncamera/ObjectDetectionCamera.java index 14672ff..51c211a 100644 --- a/src/main/java/frc/trigon/robot/misc/objectdetectioncamera/ObjectDetectionCamera.java +++ b/src/main/java/frc/trigon/robot/misc/objectdetectioncamera/ObjectDetectionCamera.java @@ -7,7 +7,7 @@ import frc.trigon.robot.misc.objectdetectioncamera.io.SimulationObjectDetectionCameraIO; import frc.trigon.robot.misc.simulatedfield.SimulatedGamePieceConstants; import org.littletonrobotics.junction.Logger; -import trigon.hardware.RobotHardwareStats; +import lib.hardware.RobotHardwareStats; /** * An object detection camera is a class that represents a camera that detects objects other than apriltags, most likely game pieces. diff --git a/src/main/java/frc/trigon/robot/misc/simulatedfield/SimulatedGamePieceConstants.java b/src/main/java/frc/trigon/robot/misc/simulatedfield/SimulatedGamePieceConstants.java index e8cbfa0..6f7ead5 100644 --- a/src/main/java/frc/trigon/robot/misc/simulatedfield/SimulatedGamePieceConstants.java +++ b/src/main/java/frc/trigon/robot/misc/simulatedfield/SimulatedGamePieceConstants.java @@ -1,8 +1,8 @@ package frc.trigon.robot.misc.simulatedfield; import edu.wpi.first.math.geometry.Rotation3d; -import trigon.utilities.flippable.FlippablePose3d; -import trigon.utilities.flippable.FlippableTranslation2d; +import lib.utilities.flippable.FlippablePose3d; +import lib.utilities.flippable.FlippableTranslation2d; import java.util.ArrayList; import java.util.List; diff --git a/src/main/java/frc/trigon/robot/misc/simulatedfield/SimulationScoringHandler.java b/src/main/java/frc/trigon/robot/misc/simulatedfield/SimulationScoringHandler.java index f42ed7f..b614d69 100644 --- a/src/main/java/frc/trigon/robot/misc/simulatedfield/SimulationScoringHandler.java +++ b/src/main/java/frc/trigon/robot/misc/simulatedfield/SimulationScoringHandler.java @@ -1,7 +1,7 @@ package frc.trigon.robot.misc.simulatedfield; import edu.wpi.first.math.geometry.Pose3d; -import trigon.utilities.flippable.FlippablePose3d; +import lib.utilities.flippable.FlippablePose3d; import java.util.ArrayList; import java.util.List; diff --git a/src/main/java/frc/trigon/robot/poseestimation/apriltagcamera/AprilTagCameraConstants.java b/src/main/java/frc/trigon/robot/poseestimation/apriltagcamera/AprilTagCameraConstants.java index e7c1b4e..81534ba 100644 --- a/src/main/java/frc/trigon/robot/poseestimation/apriltagcamera/AprilTagCameraConstants.java +++ b/src/main/java/frc/trigon/robot/poseestimation/apriltagcamera/AprilTagCameraConstants.java @@ -10,7 +10,7 @@ import org.photonvision.PhotonPoseEstimator; import org.photonvision.simulation.SimCameraProperties; import org.photonvision.simulation.VisionSystemSim; -import trigon.hardware.RobotHardwareStats; +import lib.hardware.RobotHardwareStats; import java.util.function.BiFunction; diff --git a/src/main/java/frc/trigon/robot/poseestimation/apriltagcamera/AprilTagCameraIO.java b/src/main/java/frc/trigon/robot/poseestimation/apriltagcamera/AprilTagCameraIO.java index f87eba0..1e6270a 100644 --- a/src/main/java/frc/trigon/robot/poseestimation/apriltagcamera/AprilTagCameraIO.java +++ b/src/main/java/frc/trigon/robot/poseestimation/apriltagcamera/AprilTagCameraIO.java @@ -3,7 +3,7 @@ import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Transform3d; import org.littletonrobotics.junction.AutoLog; -import trigon.hardware.RobotHardwareStats; +import lib.hardware.RobotHardwareStats; public class AprilTagCameraIO { static AprilTagCameraIO generateIO(AprilTagCameraConstants.AprilTagCameraType aprilTagCameraType, String name, Transform3d robotToCamera) { diff --git a/src/main/java/frc/trigon/robot/poseestimation/apriltagcamera/io/AprilTagLimelightIO.java b/src/main/java/frc/trigon/robot/poseestimation/apriltagcamera/io/AprilTagLimelightIO.java index 270c711..3d673c9 100644 --- a/src/main/java/frc/trigon/robot/poseestimation/apriltagcamera/io/AprilTagLimelightIO.java +++ b/src/main/java/frc/trigon/robot/poseestimation/apriltagcamera/io/AprilTagLimelightIO.java @@ -4,7 +4,7 @@ import edu.wpi.first.math.geometry.Transform3d; import frc.trigon.robot.poseestimation.apriltagcamera.AprilTagCameraIO; import frc.trigon.robot.poseestimation.apriltagcamera.AprilTagCameraInputsAutoLogged; -import trigon.utilities.LimelightHelpers; +import lib.utilities.LimelightHelpers; // TODO: Fully implement this class, Limelight currently not supported. public class AprilTagLimelightIO extends AprilTagCameraIO { diff --git a/src/main/java/frc/trigon/robot/poseestimation/poseestimator/PoseEstimator.java b/src/main/java/frc/trigon/robot/poseestimation/poseestimator/PoseEstimator.java index 1fb75fe..c4c9c3d 100644 --- a/src/main/java/frc/trigon/robot/poseestimation/poseestimator/PoseEstimator.java +++ b/src/main/java/frc/trigon/robot/poseestimation/poseestimator/PoseEstimator.java @@ -19,8 +19,8 @@ import frc.trigon.robot.subsystems.swerve.SwerveConstants; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -import trigon.utilities.QuickSortHandler; -import trigon.utilities.flippable.Flippable; +import lib.utilities.QuickSortHandler; +import lib.utilities.flippable.Flippable; import java.util.Arrays; import java.util.Map; diff --git a/src/main/java/frc/trigon/robot/poseestimation/relativerobotposesource/RelativeRobotPoseSourceIO.java b/src/main/java/frc/trigon/robot/poseestimation/relativerobotposesource/RelativeRobotPoseSourceIO.java index 5cca0b7..6314332 100644 --- a/src/main/java/frc/trigon/robot/poseestimation/relativerobotposesource/RelativeRobotPoseSourceIO.java +++ b/src/main/java/frc/trigon/robot/poseestimation/relativerobotposesource/RelativeRobotPoseSourceIO.java @@ -4,7 +4,7 @@ import frc.trigon.robot.poseestimation.relativerobotposesource.io.RelativeRobotPoseSourceSimulationIO; import frc.trigon.robot.poseestimation.relativerobotposesource.io.RelativeRobotPoseSourceT265IO; import org.littletonrobotics.junction.AutoLog; -import trigon.hardware.RobotHardwareStats; +import lib.hardware.RobotHardwareStats; public class RelativeRobotPoseSourceIO { static RelativeRobotPoseSourceIO generateIO(String hostname) { diff --git a/src/main/java/frc/trigon/robot/poseestimation/relativerobotposesource/io/RelativeRobotPoseSourceT265IO.java b/src/main/java/frc/trigon/robot/poseestimation/relativerobotposesource/io/RelativeRobotPoseSourceT265IO.java index a9b49fe..a590f97 100644 --- a/src/main/java/frc/trigon/robot/poseestimation/relativerobotposesource/io/RelativeRobotPoseSourceT265IO.java +++ b/src/main/java/frc/trigon/robot/poseestimation/relativerobotposesource/io/RelativeRobotPoseSourceT265IO.java @@ -7,7 +7,7 @@ import edu.wpi.first.networktables.NetworkTableInstance; import frc.trigon.robot.poseestimation.relativerobotposesource.RelativeRobotPoseSourceIO; import frc.trigon.robot.poseestimation.relativerobotposesource.RelativeRobotPoseSourceInputsAutoLogged; -import trigon.utilities.JsonHandler; +import lib.utilities.JsonHandler; public class RelativeRobotPoseSourceT265IO extends RelativeRobotPoseSourceIO { private final NetworkTableEntry jsonDumpEntry; diff --git a/src/main/java/frc/trigon/robot/subsystems/MotorSubsystem.java b/src/main/java/frc/trigon/robot/subsystems/MotorSubsystem.java index 75b736f..8e74ec3 100644 --- a/src/main/java/frc/trigon/robot/subsystems/MotorSubsystem.java +++ b/src/main/java/frc/trigon/robot/subsystems/MotorSubsystem.java @@ -9,7 +9,7 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import frc.trigon.robot.RobotContainer; import org.littletonrobotics.junction.networktables.LoggedNetworkBoolean; -import trigon.hardware.RobotHardwareStats; +import lib.hardware.RobotHardwareStats; import java.util.ArrayList; import java.util.List; diff --git a/src/main/java/frc/trigon/robot/subsystems/swerve/Swerve.java b/src/main/java/frc/trigon/robot/subsystems/swerve/Swerve.java index be0af82..cad6cfb 100644 --- a/src/main/java/frc/trigon/robot/subsystems/swerve/Swerve.java +++ b/src/main/java/frc/trigon/robot/subsystems/swerve/Swerve.java @@ -20,13 +20,13 @@ import frc.trigon.robot.subsystems.swerve.swervemodule.SwerveModuleConstants; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.phoenix6.Phoenix6SignalThread; -import trigon.hardware.phoenix6.pigeon2.Pigeon2Gyro; -import trigon.hardware.phoenix6.pigeon2.Pigeon2Signal; -import trigon.utilities.flippable.Flippable; -import trigon.utilities.flippable.FlippablePose2d; -import trigon.utilities.flippable.FlippableRotation2d; +import lib.hardware.RobotHardwareStats; +import lib.hardware.phoenix6.Phoenix6SignalThread; +import lib.hardware.phoenix6.pigeon2.Pigeon2Gyro; +import lib.hardware.phoenix6.pigeon2.Pigeon2Signal; +import lib.utilities.flippable.Flippable; +import lib.utilities.flippable.FlippablePose2d; +import lib.utilities.flippable.FlippableRotation2d; public class Swerve extends MotorSubsystem { private final Pigeon2Gyro gyro = SwerveConstants.GYRO; diff --git a/src/main/java/frc/trigon/robot/subsystems/swerve/SwerveCommands.java b/src/main/java/frc/trigon/robot/subsystems/swerve/SwerveCommands.java index b62469c..5784116 100644 --- a/src/main/java/frc/trigon/robot/subsystems/swerve/SwerveCommands.java +++ b/src/main/java/frc/trigon/robot/subsystems/swerve/SwerveCommands.java @@ -4,9 +4,9 @@ import com.pathplanner.lib.path.PathConstraints; import edu.wpi.first.wpilibj2.command.*; import frc.trigon.robot.RobotContainer; -import trigon.commands.InitExecuteCommand; -import trigon.utilities.flippable.FlippablePose2d; -import trigon.utilities.flippable.FlippableRotation2d; +import lib.commands.InitExecuteCommand; +import lib.utilities.flippable.FlippablePose2d; +import lib.utilities.flippable.FlippableRotation2d; import java.util.Set; import java.util.function.DoubleSupplier; diff --git a/src/main/java/frc/trigon/robot/subsystems/swerve/SwerveConstants.java b/src/main/java/frc/trigon/robot/subsystems/swerve/SwerveConstants.java index 3269a17..7dd5c25 100644 --- a/src/main/java/frc/trigon/robot/subsystems/swerve/SwerveConstants.java +++ b/src/main/java/frc/trigon/robot/subsystems/swerve/SwerveConstants.java @@ -12,9 +12,9 @@ import frc.trigon.robot.constants.RobotConstants; import frc.trigon.robot.poseestimation.poseestimator.PoseEstimatorConstants; import frc.trigon.robot.subsystems.swerve.swervemodule.SwerveModule; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.phoenix6.pigeon2.Pigeon2Gyro; -import trigon.hardware.phoenix6.pigeon2.Pigeon2Signal; +import lib.hardware.RobotHardwareStats; +import lib.hardware.phoenix6.pigeon2.Pigeon2Gyro; +import lib.hardware.phoenix6.pigeon2.Pigeon2Signal; public class SwerveConstants { private static final int GYRO_ID = 0; diff --git a/src/main/java/frc/trigon/robot/subsystems/swerve/swervemodule/SwerveModule.java b/src/main/java/frc/trigon/robot/subsystems/swerve/swervemodule/SwerveModule.java index 18bedad..dcaf72e 100644 --- a/src/main/java/frc/trigon/robot/subsystems/swerve/swervemodule/SwerveModule.java +++ b/src/main/java/frc/trigon/robot/subsystems/swerve/swervemodule/SwerveModule.java @@ -12,11 +12,11 @@ import frc.trigon.robot.constants.RobotConstants; import frc.trigon.robot.poseestimation.poseestimator.PoseEstimatorConstants; import frc.trigon.robot.subsystems.swerve.SwerveConstants; -import trigon.hardware.phoenix6.cancoder.CANcoderEncoder; -import trigon.hardware.phoenix6.cancoder.CANcoderSignal; -import trigon.hardware.phoenix6.talonfx.TalonFXMotor; -import trigon.hardware.phoenix6.talonfx.TalonFXSignal; -import trigon.utilities.Conversions; +import lib.hardware.phoenix6.cancoder.CANcoderEncoder; +import lib.hardware.phoenix6.cancoder.CANcoderSignal; +import lib.hardware.phoenix6.talonfx.TalonFXMotor; +import lib.hardware.phoenix6.talonfx.TalonFXSignal; +import lib.utilities.Conversions; public class SwerveModule { private final TalonFXMotor diff --git a/src/main/java/frc/trigon/robot/subsystems/swerve/swervemodule/SwerveModuleConstants.java b/src/main/java/frc/trigon/robot/subsystems/swerve/swervemodule/SwerveModuleConstants.java index 2e05449..f5e999c 100644 --- a/src/main/java/frc/trigon/robot/subsystems/swerve/swervemodule/SwerveModuleConstants.java +++ b/src/main/java/frc/trigon/robot/subsystems/swerve/swervemodule/SwerveModuleConstants.java @@ -10,8 +10,8 @@ import edu.wpi.first.units.Units; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import frc.trigon.robot.constants.PathPlannerConstants; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.simulation.SimpleMotorSimulation; +import lib.hardware.RobotHardwareStats; +import lib.hardware.simulation.SimpleMotorSimulation; public class SwerveModuleConstants { private static final double diff --git a/src/main/java/trigon/commands/CameraPositionCalculationCommand.java b/src/main/java/lib/commands/CameraPositionCalculationCommand.java similarity index 99% rename from src/main/java/trigon/commands/CameraPositionCalculationCommand.java rename to src/main/java/lib/commands/CameraPositionCalculationCommand.java index 869ae0c..558770b 100644 --- a/src/main/java/trigon/commands/CameraPositionCalculationCommand.java +++ b/src/main/java/lib/commands/CameraPositionCalculationCommand.java @@ -1,4 +1,4 @@ -package trigon.commands; +package lib.commands; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; diff --git a/src/main/java/trigon/commands/ExecuteEndCommand.java b/src/main/java/lib/commands/ExecuteEndCommand.java similarity index 96% rename from src/main/java/trigon/commands/ExecuteEndCommand.java rename to src/main/java/lib/commands/ExecuteEndCommand.java index 0f99c5c..c4bb5e6 100644 --- a/src/main/java/trigon/commands/ExecuteEndCommand.java +++ b/src/main/java/lib/commands/ExecuteEndCommand.java @@ -1,4 +1,4 @@ -package trigon.commands; +package lib.commands; import edu.wpi.first.wpilibj2.command.FunctionalCommand; import edu.wpi.first.wpilibj2.command.SubsystemBase; diff --git a/src/main/java/trigon/commands/GearRatioCalculationCommand.java b/src/main/java/lib/commands/GearRatioCalculationCommand.java similarity index 97% rename from src/main/java/trigon/commands/GearRatioCalculationCommand.java rename to src/main/java/lib/commands/GearRatioCalculationCommand.java index 96cd8fc..e64caa0 100644 --- a/src/main/java/trigon/commands/GearRatioCalculationCommand.java +++ b/src/main/java/lib/commands/GearRatioCalculationCommand.java @@ -1,4 +1,4 @@ -package trigon.commands; +package lib.commands; import com.ctre.phoenix6.controls.VoltageOut; import edu.wpi.first.wpilibj.Timer; @@ -6,10 +6,10 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; import org.littletonrobotics.junction.Logger; import org.littletonrobotics.junction.networktables.LoggedNetworkNumber; -import trigon.hardware.phoenix6.cancoder.CANcoderEncoder; -import trigon.hardware.phoenix6.cancoder.CANcoderSignal; -import trigon.hardware.phoenix6.talonfx.TalonFXMotor; -import trigon.hardware.phoenix6.talonfx.TalonFXSignal; +import lib.hardware.phoenix6.cancoder.CANcoderEncoder; +import lib.hardware.phoenix6.cancoder.CANcoderSignal; +import lib.hardware.phoenix6.talonfx.TalonFXMotor; +import lib.hardware.phoenix6.talonfx.TalonFXSignal; import java.util.function.DoubleConsumer; import java.util.function.DoubleSupplier; diff --git a/src/main/java/trigon/commands/InitExecuteCommand.java b/src/main/java/lib/commands/InitExecuteCommand.java similarity index 97% rename from src/main/java/trigon/commands/InitExecuteCommand.java rename to src/main/java/lib/commands/InitExecuteCommand.java index 95aef05..bd4a695 100644 --- a/src/main/java/trigon/commands/InitExecuteCommand.java +++ b/src/main/java/lib/commands/InitExecuteCommand.java @@ -1,4 +1,4 @@ -package trigon.commands; +package lib.commands; import edu.wpi.first.wpilibj2.command.FunctionalCommand; import edu.wpi.first.wpilibj2.command.SubsystemBase; diff --git a/src/main/java/trigon/commands/NetworkTablesCommand.java b/src/main/java/lib/commands/NetworkTablesCommand.java similarity index 99% rename from src/main/java/trigon/commands/NetworkTablesCommand.java rename to src/main/java/lib/commands/NetworkTablesCommand.java index 7d1a75b..a5e7d69 100644 --- a/src/main/java/trigon/commands/NetworkTablesCommand.java +++ b/src/main/java/lib/commands/NetworkTablesCommand.java @@ -1,4 +1,4 @@ -package trigon.commands; +package lib.commands; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Subsystem; diff --git a/src/main/java/trigon/commands/WheelRadiusCharacterizationCommand.java b/src/main/java/lib/commands/WheelRadiusCharacterizationCommand.java similarity index 99% rename from src/main/java/trigon/commands/WheelRadiusCharacterizationCommand.java rename to src/main/java/lib/commands/WheelRadiusCharacterizationCommand.java index 0c60473..e2fda46 100644 --- a/src/main/java/trigon/commands/WheelRadiusCharacterizationCommand.java +++ b/src/main/java/lib/commands/WheelRadiusCharacterizationCommand.java @@ -5,7 +5,7 @@ // license that can be found in the LICENSE file at // the root directory of this project. -package trigon.commands; +package lib.commands; import edu.wpi.first.math.filter.SlewRateLimiter; import edu.wpi.first.math.geometry.Translation2d; diff --git a/src/main/java/trigon/hardware/InputsBase.java b/src/main/java/lib/hardware/InputsBase.java similarity index 99% rename from src/main/java/trigon/hardware/InputsBase.java rename to src/main/java/lib/hardware/InputsBase.java index a4f74db..27c07f3 100644 --- a/src/main/java/trigon/hardware/InputsBase.java +++ b/src/main/java/lib/hardware/InputsBase.java @@ -1,4 +1,4 @@ -package trigon.hardware; +package lib.hardware; import edu.wpi.first.wpilibj.Timer; import org.littletonrobotics.junction.LogTable; diff --git a/src/main/java/trigon/hardware/RobotHardwareStats.java b/src/main/java/lib/hardware/RobotHardwareStats.java similarity index 98% rename from src/main/java/trigon/hardware/RobotHardwareStats.java rename to src/main/java/lib/hardware/RobotHardwareStats.java index 6b37624..7945256 100644 --- a/src/main/java/trigon/hardware/RobotHardwareStats.java +++ b/src/main/java/lib/hardware/RobotHardwareStats.java @@ -1,4 +1,4 @@ -package trigon.hardware; +package lib.hardware; /** * A class that contains stats about the robot's hardware. diff --git a/src/main/java/trigon/hardware/SignalThreadBase.java b/src/main/java/lib/hardware/SignalThreadBase.java similarity index 95% rename from src/main/java/trigon/hardware/SignalThreadBase.java rename to src/main/java/lib/hardware/SignalThreadBase.java index f3745d8..88566a0 100644 --- a/src/main/java/trigon/hardware/SignalThreadBase.java +++ b/src/main/java/lib/hardware/SignalThreadBase.java @@ -1,9 +1,7 @@ -package trigon.hardware; +package lib.hardware; import org.littletonrobotics.junction.AutoLog; import org.littletonrobotics.junction.Logger; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.ThreadInputsAutoLogged; import java.util.Queue; import java.util.concurrent.ArrayBlockingQueue; diff --git a/src/main/java/trigon/hardware/grapple/lasercan/LaserCAN.java b/src/main/java/lib/hardware/grapple/lasercan/LaserCAN.java similarity index 96% rename from src/main/java/trigon/hardware/grapple/lasercan/LaserCAN.java rename to src/main/java/lib/hardware/grapple/lasercan/LaserCAN.java index a043f6b..854ea95 100644 --- a/src/main/java/trigon/hardware/grapple/lasercan/LaserCAN.java +++ b/src/main/java/lib/hardware/grapple/lasercan/LaserCAN.java @@ -1,10 +1,8 @@ -package trigon.hardware.grapple.lasercan; +package lib.hardware.grapple.lasercan; import au.grapplerobotics.ConfigurationFailedException; import au.grapplerobotics.LaserCan; import org.littletonrobotics.junction.Logger; -import trigon.hardware.grapple.lasercan.LaserCANIO; -import trigon.hardware.grapple.lasercan.LaserCANInputsAutoLogged; import java.util.function.DoubleSupplier; diff --git a/src/main/java/trigon/hardware/grapple/lasercan/LaserCANIO.java b/src/main/java/lib/hardware/grapple/lasercan/LaserCANIO.java similarity index 89% rename from src/main/java/trigon/hardware/grapple/lasercan/LaserCANIO.java rename to src/main/java/lib/hardware/grapple/lasercan/LaserCANIO.java index b6c146d..cd59da8 100644 --- a/src/main/java/trigon/hardware/grapple/lasercan/LaserCANIO.java +++ b/src/main/java/lib/hardware/grapple/lasercan/LaserCANIO.java @@ -1,12 +1,11 @@ -package trigon.hardware.grapple.lasercan; +package lib.hardware.grapple.lasercan; import au.grapplerobotics.ConfigurationFailedException; import au.grapplerobotics.LaserCan; +import lib.hardware.RobotHardwareStats; +import lib.hardware.grapple.lasercan.io.RealLaserCANIO; +import lib.hardware.grapple.lasercan.io.SimulationLaserCANIO; import org.littletonrobotics.junction.AutoLog; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.grapple.lasercan.LaserCANInputsAutoLogged; -import trigon.hardware.grapple.lasercan.io.RealLaserCANIO; -import trigon.hardware.grapple.lasercan.io.SimulationLaserCANIO; import java.util.function.DoubleSupplier; diff --git a/src/main/java/trigon/hardware/grapple/lasercan/io/RealLaserCANIO.java b/src/main/java/lib/hardware/grapple/lasercan/io/RealLaserCANIO.java similarity index 91% rename from src/main/java/trigon/hardware/grapple/lasercan/io/RealLaserCANIO.java rename to src/main/java/lib/hardware/grapple/lasercan/io/RealLaserCANIO.java index 6c87e9f..59f5a32 100644 --- a/src/main/java/trigon/hardware/grapple/lasercan/io/RealLaserCANIO.java +++ b/src/main/java/lib/hardware/grapple/lasercan/io/RealLaserCANIO.java @@ -1,9 +1,9 @@ -package trigon.hardware.grapple.lasercan.io; +package lib.hardware.grapple.lasercan.io; import au.grapplerobotics.ConfigurationFailedException; import au.grapplerobotics.LaserCan; -import trigon.hardware.grapple.lasercan.LaserCANIO; -import trigon.hardware.grapple.lasercan.LaserCANInputsAutoLogged; +import lib.hardware.grapple.lasercan.LaserCANIO; +import lib.hardware.grapple.lasercan.LaserCANInputsAutoLogged; public class RealLaserCANIO extends LaserCANIO { private final LaserCan laserCan; diff --git a/src/main/java/trigon/hardware/grapple/lasercan/io/SimulationLaserCANIO.java b/src/main/java/lib/hardware/grapple/lasercan/io/SimulationLaserCANIO.java similarity index 78% rename from src/main/java/trigon/hardware/grapple/lasercan/io/SimulationLaserCANIO.java rename to src/main/java/lib/hardware/grapple/lasercan/io/SimulationLaserCANIO.java index 62dbd00..4af7fe5 100644 --- a/src/main/java/trigon/hardware/grapple/lasercan/io/SimulationLaserCANIO.java +++ b/src/main/java/lib/hardware/grapple/lasercan/io/SimulationLaserCANIO.java @@ -1,7 +1,7 @@ -package trigon.hardware.grapple.lasercan.io; +package lib.hardware.grapple.lasercan.io; -import trigon.hardware.grapple.lasercan.LaserCANIO; -import trigon.hardware.grapple.lasercan.LaserCANInputsAutoLogged; +import lib.hardware.grapple.lasercan.LaserCANIO; +import lib.hardware.grapple.lasercan.LaserCANInputsAutoLogged; import java.util.function.DoubleSupplier; diff --git a/src/main/java/trigon/hardware/misc/KeyboardController.java b/src/main/java/lib/hardware/misc/KeyboardController.java similarity index 99% rename from src/main/java/trigon/hardware/misc/KeyboardController.java rename to src/main/java/lib/hardware/misc/KeyboardController.java index e4e8bb4..93829c3 100644 --- a/src/main/java/trigon/hardware/misc/KeyboardController.java +++ b/src/main/java/lib/hardware/misc/KeyboardController.java @@ -1,4 +1,4 @@ -package trigon.hardware.misc; +package lib.hardware.misc; import edu.wpi.first.wpilibj2.command.button.Trigger; import org.littletonrobotics.junction.networktables.LoggedNetworkBoolean; diff --git a/src/main/java/trigon/hardware/misc/XboxController.java b/src/main/java/lib/hardware/misc/XboxController.java similarity index 99% rename from src/main/java/trigon/hardware/misc/XboxController.java rename to src/main/java/lib/hardware/misc/XboxController.java index 16cb8bf..b88ab97 100644 --- a/src/main/java/trigon/hardware/misc/XboxController.java +++ b/src/main/java/lib/hardware/misc/XboxController.java @@ -1,4 +1,4 @@ -package trigon.hardware.misc; +package lib.hardware.misc; import edu.wpi.first.wpilibj.GenericHID; import edu.wpi.first.wpilibj2.command.Command; diff --git a/src/main/java/trigon/hardware/misc/leds/AddressableLEDStrip.java b/src/main/java/lib/hardware/misc/leds/AddressableLEDStrip.java similarity index 99% rename from src/main/java/trigon/hardware/misc/leds/AddressableLEDStrip.java rename to src/main/java/lib/hardware/misc/leds/AddressableLEDStrip.java index 17ed84e..d3d7461 100644 --- a/src/main/java/trigon/hardware/misc/leds/AddressableLEDStrip.java +++ b/src/main/java/lib/hardware/misc/leds/AddressableLEDStrip.java @@ -1,11 +1,10 @@ -package trigon.hardware.misc.leds; +package lib.hardware.misc.leds; import com.ctre.phoenix.led.LarsonAnimation; import edu.wpi.first.wpilibj.AddressableLED; import edu.wpi.first.wpilibj.AddressableLEDBuffer; import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.util.Color; -import trigon.hardware.misc.leds.LEDStrip; import java.util.function.Supplier; diff --git a/src/main/java/trigon/hardware/misc/leds/CANdleLEDStrip.java b/src/main/java/lib/hardware/misc/leds/CANdleLEDStrip.java similarity index 97% rename from src/main/java/trigon/hardware/misc/leds/CANdleLEDStrip.java rename to src/main/java/lib/hardware/misc/leds/CANdleLEDStrip.java index d355fa4..b08fa97 100644 --- a/src/main/java/trigon/hardware/misc/leds/CANdleLEDStrip.java +++ b/src/main/java/lib/hardware/misc/leds/CANdleLEDStrip.java @@ -1,10 +1,8 @@ -package trigon.hardware.misc.leds; +package lib.hardware.misc.leds; import com.ctre.phoenix.led.*; import edu.wpi.first.wpilibj.util.Color; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.misc.leds.AddressableLEDStrip; -import trigon.hardware.misc.leds.LEDStrip; +import lib.hardware.RobotHardwareStats; import java.util.function.Supplier; diff --git a/src/main/java/trigon/hardware/misc/leds/LEDBoard.java b/src/main/java/lib/hardware/misc/leds/LEDBoard.java similarity index 98% rename from src/main/java/trigon/hardware/misc/leds/LEDBoard.java rename to src/main/java/lib/hardware/misc/leds/LEDBoard.java index d6b3bbd..576cd31 100644 --- a/src/main/java/trigon/hardware/misc/leds/LEDBoard.java +++ b/src/main/java/lib/hardware/misc/leds/LEDBoard.java @@ -1,10 +1,9 @@ -package trigon.hardware.misc.leds; +package lib.hardware.misc.leds; import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.util.Color; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import trigon.hardware.misc.leds.LEDStrip; -import trigon.utilities.RGBArrayUtils; +import lib.utilities.RGBArrayUtils; import java.io.IOException; diff --git a/src/main/java/trigon/hardware/misc/leds/LEDCommands.java b/src/main/java/lib/hardware/misc/leds/LEDCommands.java similarity index 73% rename from src/main/java/trigon/hardware/misc/leds/LEDCommands.java rename to src/main/java/lib/hardware/misc/leds/LEDCommands.java index 6207067..8dbd8e7 100644 --- a/src/main/java/trigon/hardware/misc/leds/LEDCommands.java +++ b/src/main/java/lib/hardware/misc/leds/LEDCommands.java @@ -1,13 +1,10 @@ -package trigon.hardware.misc.leds; +package lib.hardware.misc.leds; import com.ctre.phoenix.led.LarsonAnimation; import edu.wpi.first.wpilibj.util.Color; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.FunctionalCommand; import edu.wpi.first.wpilibj2.command.StartEndCommand; -import trigon.hardware.misc.leds.LEDBoard; -import trigon.hardware.misc.leds.LEDStrip; -import trigon.hardware.misc.leds.LEDStripAnimationSettings; import java.util.function.Consumer; import java.util.function.Supplier; @@ -23,13 +20,13 @@ public class LEDCommands { * @param ledStrips the LED strips to animate * @return the command */ - public static Command getAnimateCommand(LEDStripAnimationSettings.LEDAnimationSettings settings, trigon.hardware.misc.leds.LEDStrip... ledStrips) { + public static Command getAnimateCommand(LEDStripAnimationSettings.LEDAnimationSettings settings, LEDStrip... ledStrips) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips); - runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(trigon.hardware.misc.leds.LEDStrip.applyAnimation(ledStrip, settings)), ledStrips); + runForLEDs(LEDStrip::clearLEDColors, ledStrips); + runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(LEDStrip.applyAnimation(ledStrip, settings)), ledStrips); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips), + () -> runForLEDs(LEDStrip::clearLEDColors, ledStrips), ledStrips ).ignoringDisable(true); } @@ -41,13 +38,13 @@ public static Command getAnimateCommand(LEDStripAnimationSettings.LEDAnimationSe * @param ledBoard the LED board to animate * @return the command */ - public static Command getAnimateCommand(LEDStripAnimationSettings.LEDAnimationSettings settings, trigon.hardware.misc.leds.LEDBoard ledBoard) { + public static Command getAnimateCommand(LEDStripAnimationSettings.LEDAnimationSettings settings, LEDBoard ledBoard) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledBoard.getLEDStrips()); - runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(trigon.hardware.misc.leds.LEDStrip.applyAnimation(ledStrip, settings)), ledBoard.getLEDStrips()); + runForLEDs(LEDStrip::clearLEDColors, ledBoard.getLEDStrips()); + runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(LEDStrip.applyAnimation(ledStrip, settings)), ledBoard.getLEDStrips()); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledBoard.getLEDStrips()), + () -> runForLEDs(LEDStrip::clearLEDColors, ledBoard.getLEDStrips()), ledBoard ).ignoringDisable(true); } @@ -59,13 +56,13 @@ public static Command getAnimateCommand(LEDStripAnimationSettings.LEDAnimationSe * @param ledStrips the LED strips to animate * @return the command */ - public static Command getStaticColorCommand(Color color, trigon.hardware.misc.leds.LEDStrip... ledStrips) { + public static Command getStaticColorCommand(Color color, LEDStrip... ledStrips) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips); + runForLEDs(LEDStrip::clearLEDColors, ledStrips); runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(() -> ledStrip.staticColor(color)), ledStrips); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips), + () -> runForLEDs(LEDStrip::clearLEDColors, ledStrips), ledStrips ).ignoringDisable(true); } @@ -77,13 +74,13 @@ public static Command getStaticColorCommand(Color color, trigon.hardware.misc.le * @param ledBoard the LED board to animate * @return the command */ - public static Command getStaticColorCommand(Color color, trigon.hardware.misc.leds.LEDBoard ledBoard) { + public static Command getStaticColorCommand(Color color, LEDBoard ledBoard) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledBoard.getLEDStrips()); + runForLEDs(LEDStrip::clearLEDColors, ledBoard.getLEDStrips()); runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(() -> ledStrip.staticColor(color)), ledBoard.getLEDStrips()); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledBoard.getLEDStrips()), + () -> runForLEDs(LEDStrip::clearLEDColors, ledBoard.getLEDStrips()), ledBoard ).ignoringDisable(true); } @@ -96,13 +93,13 @@ public static Command getStaticColorCommand(Color color, trigon.hardware.misc.le * @param ledStrips the LED strips to animate * @return the command */ - public static Command getBlinkCommand(Color color, double speed, trigon.hardware.misc.leds.LEDStrip... ledStrips) { + public static Command getBlinkCommand(Color color, double speed, LEDStrip... ledStrips) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips); + runForLEDs(LEDStrip::clearLEDColors, ledStrips); runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(() -> ledStrip.blink(color, speed)), ledStrips); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips), + () -> runForLEDs(LEDStrip::clearLEDColors, ledStrips), ledStrips ).ignoringDisable(true); } @@ -115,13 +112,13 @@ public static Command getBlinkCommand(Color color, double speed, trigon.hardware * @param ledBoard the LED board to animate * @return the command */ - public static Command getBlinkCommand(Color color, double speed, trigon.hardware.misc.leds.LEDBoard ledBoard) { + public static Command getBlinkCommand(Color color, double speed, LEDBoard ledBoard) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledBoard.getLEDStrips()); + runForLEDs(LEDStrip::clearLEDColors, ledBoard.getLEDStrips()); runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(() -> ledStrip.blink(color, speed)), ledBoard.getLEDStrips()); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledBoard.getLEDStrips()), + () -> runForLEDs(LEDStrip::clearLEDColors, ledBoard.getLEDStrips()), ledBoard ).ignoringDisable(true); } @@ -137,13 +134,13 @@ public static Command getBlinkCommand(Color color, double speed, trigon.hardware * @param ledStrips the LED strips to animate * @return the command */ - public static Command getBreatheCommand(Color color, int numberOfBreathingLEDs, double speed, boolean inverted, LarsonAnimation.BounceMode bounceMode, trigon.hardware.misc.leds.LEDStrip... ledStrips) { + public static Command getBreatheCommand(Color color, int numberOfBreathingLEDs, double speed, boolean inverted, LarsonAnimation.BounceMode bounceMode, LEDStrip... ledStrips) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips); + runForLEDs(LEDStrip::clearLEDColors, ledStrips); runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(() -> ledStrip.breathe(color, numberOfBreathingLEDs, speed, inverted, bounceMode)), ledStrips); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips), + () -> runForLEDs(LEDStrip::clearLEDColors, ledStrips), ledStrips ).ignoringDisable(true); } @@ -159,7 +156,7 @@ public static Command getBreatheCommand(Color color, int numberOfBreathingLEDs, * @param ledBoard the LED board to animate * @return the command */ - public static Command getBreatheCommand(Color color, int numberOfBreathingLEDs, int speedLEDsPerSecond, int ledSpacing, boolean inverted, trigon.hardware.misc.leds.LEDBoard ledBoard) { + public static Command getBreatheCommand(Color color, int numberOfBreathingLEDs, int speedLEDsPerSecond, int ledSpacing, boolean inverted, LEDBoard ledBoard) { return new FunctionalCommand( () -> ledBoard.breathe(color, numberOfBreathingLEDs, speedLEDsPerSecond, ledSpacing, inverted), ledBoard::updateBreathingPeriodically, @@ -178,13 +175,13 @@ public static Command getBreatheCommand(Color color, int numberOfBreathingLEDs, * @param ledStrips the LED strips to animate * @return the command */ - public static Command getColorFlowCommand(Color color, double speed, boolean inverted, trigon.hardware.misc.leds.LEDStrip... ledStrips) { + public static Command getColorFlowCommand(Color color, double speed, boolean inverted, LEDStrip... ledStrips) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips); + runForLEDs(LEDStrip::clearLEDColors, ledStrips); runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(() -> ledStrip.colorFlow(color, speed, inverted)), ledStrips); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips), + () -> runForLEDs(LEDStrip::clearLEDColors, ledStrips), ledStrips ).ignoringDisable(true); } @@ -198,13 +195,13 @@ public static Command getColorFlowCommand(Color color, double speed, boolean inv * @param ledBoard the LED board to animate * @return the command */ - public static Command getColorFlowCommand(Color color, double speed, boolean inverted, trigon.hardware.misc.leds.LEDBoard ledBoard) { + public static Command getColorFlowCommand(Color color, double speed, boolean inverted, LEDBoard ledBoard) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledBoard.getLEDStrips()); + runForLEDs(LEDStrip::clearLEDColors, ledBoard.getLEDStrips()); runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(() -> ledStrip.colorFlow(color, speed, inverted)), ledBoard.getLEDStrips()); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledBoard.getLEDStrips()), + () -> runForLEDs(LEDStrip::clearLEDColors, ledBoard.getLEDStrips()), ledBoard ).ignoringDisable(true); } @@ -217,13 +214,13 @@ public static Command getColorFlowCommand(Color color, double speed, boolean inv * @param ledStrips the LED strips to animate * @return the command */ - public static Command getAlternateColorCommand(Color firstColor, Color secondColor, trigon.hardware.misc.leds.LEDStrip... ledStrips) { + public static Command getAlternateColorCommand(Color firstColor, Color secondColor, LEDStrip... ledStrips) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips); + runForLEDs(LEDStrip::clearLEDColors, ledStrips); runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(() -> ledStrip.alternateColor(firstColor, secondColor)), ledStrips); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips), + () -> runForLEDs(LEDStrip::clearLEDColors, ledStrips), ledStrips ).ignoringDisable(true); } @@ -236,13 +233,13 @@ public static Command getAlternateColorCommand(Color firstColor, Color secondCol * @param ledBoard the LED board to animate * @return the command */ - public static Command getAlternateColorCommand(Color firstColor, Color secondColor, trigon.hardware.misc.leds.LEDBoard ledBoard) { + public static Command getAlternateColorCommand(Color firstColor, Color secondColor, LEDBoard ledBoard) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledBoard.getLEDStrips()); + runForLEDs(LEDStrip::clearLEDColors, ledBoard.getLEDStrips()); runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(() -> ledStrip.alternateColor(firstColor, secondColor)), ledBoard.getLEDStrips()); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledBoard.getLEDStrips()), + () -> runForLEDs(LEDStrip::clearLEDColors, ledBoard.getLEDStrips()), ledBoard ).ignoringDisable(true); } @@ -254,13 +251,13 @@ public static Command getAlternateColorCommand(Color firstColor, Color secondCol * @param ledStrips the LED strips to animate * @return the command */ - public static Command getSectionColorCommand(Supplier[] colors, trigon.hardware.misc.leds.LEDStrip... ledStrips) { + public static Command getSectionColorCommand(Supplier[] colors, LEDStrip... ledStrips) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips); + runForLEDs(LEDStrip::clearLEDColors, ledStrips); runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(() -> ledStrip.sectionColor(colors)), ledStrips); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips), + () -> runForLEDs(LEDStrip::clearLEDColors, ledStrips), ledStrips ).ignoringDisable(true); } @@ -272,13 +269,13 @@ public static Command getSectionColorCommand(Supplier[] colors, trigon.ha * @param ledBoard the LED board to animate * @return the command */ - public static Command getSectionColorCommand(Supplier[] colors, trigon.hardware.misc.leds.LEDBoard ledBoard) { + public static Command getSectionColorCommand(Supplier[] colors, LEDBoard ledBoard) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledBoard.getLEDStrips()); + runForLEDs(LEDStrip::clearLEDColors, ledBoard.getLEDStrips()); runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(() -> ledStrip.sectionColor(colors)), ledBoard.getLEDStrips()); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledBoard.getLEDStrips()), + () -> runForLEDs(LEDStrip::clearLEDColors, ledBoard.getLEDStrips()), ledBoard ).ignoringDisable(true); } @@ -291,13 +288,13 @@ public static Command getSectionColorCommand(Supplier[] colors, trigon.ha * @param ledStrips the LED strips to animate * @return the command */ - public static Command getRainbowCommand(double brightness, double speed, boolean inverted, trigon.hardware.misc.leds.LEDStrip... ledStrips) { + public static Command getRainbowCommand(double brightness, double speed, boolean inverted, LEDStrip... ledStrips) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips); + runForLEDs(LEDStrip::clearLEDColors, ledStrips); runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(() -> ledStrip.rainbow(brightness, speed, inverted)), ledStrips); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips), + () -> runForLEDs(LEDStrip::clearLEDColors, ledStrips), ledStrips ).ignoringDisable(true); } @@ -310,13 +307,13 @@ public static Command getRainbowCommand(double brightness, double speed, boolean * @param ledBoard the LED board to animate * @return the command */ - public static Command getRainbowCommand(double brightness, double speed, boolean inverted, trigon.hardware.misc.leds.LEDBoard ledBoard) { + public static Command getRainbowCommand(double brightness, double speed, boolean inverted, LEDBoard ledBoard) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledBoard.getLEDStrips()); + runForLEDs(LEDStrip::clearLEDColors, ledBoard.getLEDStrips()); runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(() -> ledStrip.rainbow(brightness, speed, inverted)), ledBoard.getLEDStrips()); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledBoard.getLEDStrips()), + () -> runForLEDs(LEDStrip::clearLEDColors, ledBoard.getLEDStrips()), ledBoard ).ignoringDisable(true); } @@ -328,7 +325,7 @@ public static Command getRainbowCommand(double brightness, double speed, boolean * @param ledBoard the LED board to animate * @return the command */ - public static Command getSetImageCommand(String filePath, trigon.hardware.misc.leds.LEDBoard ledBoard) { + public static Command getSetImageCommand(String filePath, LEDBoard ledBoard) { return new StartEndCommand( () -> ledBoard.setImage(filePath), ledBoard::clearBoard, @@ -346,7 +343,7 @@ public static Command getSetImageCommand(String filePath, trigon.hardware.misc.l * @param ledBoard the LED board to animate * @return the command */ - public static Command getSetBoardAnimationCommand(String[] filePaths, int framesPerSecond, boolean shouldLoop, boolean shouldKeepLastFrame, trigon.hardware.misc.leds.LEDBoard ledBoard) { + public static Command getSetBoardAnimationCommand(String[] filePaths, int framesPerSecond, boolean shouldLoop, boolean shouldKeepLastFrame, LEDBoard ledBoard) { return new FunctionalCommand( () -> ledBoard.setAnimation(filePaths, framesPerSecond), ledBoard::updateAnimationPeriodically, @@ -388,13 +385,13 @@ public static Command getSetBoardBounceCommand(Color color, int numberOfMovingLE * @param ledStrips the LED strips to animate * @return the command */ - public static Command getDefaultAnimateCommand(LEDStripAnimationSettings.LEDAnimationSettings settings, trigon.hardware.misc.leds.LEDStrip... ledStrips) { + public static Command getDefaultAnimateCommand(LEDStripAnimationSettings.LEDAnimationSettings settings, LEDStrip... ledStrips) { return new StartEndCommand( () -> { - runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips); - runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(trigon.hardware.misc.leds.LEDStrip.applyAnimation(ledStrip, settings)), ledStrips); + runForLEDs(LEDStrip::clearLEDColors, ledStrips); + runForLEDs(ledStrip -> ledStrip.setCurrentAnimation(LEDStrip.applyAnimation(ledStrip, settings)), ledStrips); }, - () -> runForLEDs(trigon.hardware.misc.leds.LEDStrip::clearLEDColors, ledStrips), + () -> runForLEDs(LEDStrip::clearLEDColors, ledStrips), ledStrips ).ignoringDisable(true); } @@ -402,9 +399,9 @@ public static Command getDefaultAnimateCommand(LEDStripAnimationSettings.LEDAnim /** * Runs an action on all LED strips. */ - private static void runForLEDs(Consumer action, trigon.hardware.misc.leds.LEDStrip... ledStrips) { + private static void runForLEDs(Consumer action, LEDStrip... ledStrips) { if (ledStrips.length == 0) - ledStrips = trigon.hardware.misc.leds.LEDStrip.LED_STRIPS; + ledStrips = LEDStrip.LED_STRIPS; for (LEDStrip ledStrip : ledStrips) action.accept(ledStrip); diff --git a/src/main/java/trigon/hardware/misc/leds/LEDStrip.java b/src/main/java/lib/hardware/misc/leds/LEDStrip.java similarity index 93% rename from src/main/java/trigon/hardware/misc/leds/LEDStrip.java rename to src/main/java/lib/hardware/misc/leds/LEDStrip.java index 17d8470..830e1fc 100644 --- a/src/main/java/trigon/hardware/misc/leds/LEDStrip.java +++ b/src/main/java/lib/hardware/misc/leds/LEDStrip.java @@ -1,13 +1,9 @@ -package trigon.hardware.misc.leds; +package lib.hardware.misc.leds; import com.ctre.phoenix.led.LarsonAnimation; import edu.wpi.first.wpilibj.util.Color; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.misc.leds.AddressableLEDStrip; -import trigon.hardware.misc.leds.CANdleLEDStrip; -import trigon.hardware.misc.leds.LEDCommands; -import trigon.hardware.misc.leds.LEDStripAnimationSettings; +import lib.hardware.RobotHardwareStats; import java.util.function.Supplier; diff --git a/src/main/java/trigon/hardware/misc/leds/LEDStripAnimationSettings.java b/src/main/java/lib/hardware/misc/leds/LEDStripAnimationSettings.java similarity index 86% rename from src/main/java/trigon/hardware/misc/leds/LEDStripAnimationSettings.java rename to src/main/java/lib/hardware/misc/leds/LEDStripAnimationSettings.java index b71e339..d117aa1 100644 --- a/src/main/java/trigon/hardware/misc/leds/LEDStripAnimationSettings.java +++ b/src/main/java/lib/hardware/misc/leds/LEDStripAnimationSettings.java @@ -1,8 +1,7 @@ -package trigon.hardware.misc.leds; +package lib.hardware.misc.leds; import com.ctre.phoenix.led.LarsonAnimation; import edu.wpi.first.wpilibj.util.Color; -import trigon.hardware.misc.leds.LEDStrip; import java.util.function.Supplier; @@ -11,7 +10,7 @@ */ public class LEDStripAnimationSettings { public interface LEDAnimationSettings { - void apply(trigon.hardware.misc.leds.LEDStrip ledStrip); + void apply(LEDStrip ledStrip); } /** @@ -21,7 +20,7 @@ public interface LEDAnimationSettings { */ public record StaticColorSettings(Color color) implements LEDAnimationSettings { @Override - public void apply(trigon.hardware.misc.leds.LEDStrip ledStrip) { + public void apply(LEDStrip ledStrip) { ledStrip.staticColor(color); } } @@ -34,7 +33,7 @@ public void apply(trigon.hardware.misc.leds.LEDStrip ledStrip) { */ public record BlinkSettings(Color color, double speed) implements LEDAnimationSettings { @Override - public void apply(trigon.hardware.misc.leds.LEDStrip ledStrip) { + public void apply(LEDStrip ledStrip) { ledStrip.blink(color, speed); } } @@ -51,7 +50,7 @@ public void apply(trigon.hardware.misc.leds.LEDStrip ledStrip) { public record BreatheSettings(Color color, int numberOfBreathingLEDs, double speed, boolean inverted, LarsonAnimation.BounceMode bounceMode) implements LEDAnimationSettings { @Override - public void apply(trigon.hardware.misc.leds.LEDStrip ledStrip) { + public void apply(LEDStrip ledStrip) { ledStrip.breathe(color, numberOfBreathingLEDs, speed, inverted, bounceMode); } } @@ -65,7 +64,7 @@ public void apply(trigon.hardware.misc.leds.LEDStrip ledStrip) { */ public record ColorFlowSettings(Color color, double speed, boolean inverted) implements LEDAnimationSettings { @Override - public void apply(trigon.hardware.misc.leds.LEDStrip ledStrip) { + public void apply(LEDStrip ledStrip) { ledStrip.colorFlow(color, speed, inverted); } } @@ -78,7 +77,7 @@ public void apply(trigon.hardware.misc.leds.LEDStrip ledStrip) { */ public record AlternateColorSettings(Color firstColor, Color secondColor) implements LEDAnimationSettings { @Override - public void apply(trigon.hardware.misc.leds.LEDStrip ledStrip) { + public void apply(LEDStrip ledStrip) { ledStrip.alternateColor(firstColor, secondColor); } } @@ -90,7 +89,7 @@ public void apply(trigon.hardware.misc.leds.LEDStrip ledStrip) { */ public record SectionColorSettings(Supplier[] colors) implements LEDAnimationSettings { @Override - public void apply(trigon.hardware.misc.leds.LEDStrip ledStrip) { + public void apply(LEDStrip ledStrip) { ledStrip.sectionColor(colors); } } diff --git a/src/main/java/trigon/hardware/misc/servo/Servo.java b/src/main/java/lib/hardware/misc/servo/Servo.java similarity index 99% rename from src/main/java/trigon/hardware/misc/servo/Servo.java rename to src/main/java/lib/hardware/misc/servo/Servo.java index 0aa3795..91533c2 100644 --- a/src/main/java/trigon/hardware/misc/servo/Servo.java +++ b/src/main/java/lib/hardware/misc/servo/Servo.java @@ -1,4 +1,4 @@ -package trigon.hardware.misc.servo; +package lib.hardware.misc.servo; import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.Logger; diff --git a/src/main/java/trigon/hardware/misc/servo/ServoIO.java b/src/main/java/lib/hardware/misc/servo/ServoIO.java similarity index 86% rename from src/main/java/trigon/hardware/misc/servo/ServoIO.java rename to src/main/java/lib/hardware/misc/servo/ServoIO.java index 5ead90f..89a4184 100644 --- a/src/main/java/trigon/hardware/misc/servo/ServoIO.java +++ b/src/main/java/lib/hardware/misc/servo/ServoIO.java @@ -1,10 +1,10 @@ -package trigon.hardware.misc.servo; +package lib.hardware.misc.servo; import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.AutoLog; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.misc.servo.io.RealServoIO; -import trigon.hardware.misc.servo.io.SimulationServoIO; +import lib.hardware.RobotHardwareStats; +import lib.hardware.misc.servo.io.RealServoIO; +import lib.hardware.misc.servo.io.SimulationServoIO; public class ServoIO { static ServoIO generateServoIO(int channel) { diff --git a/src/main/java/trigon/hardware/misc/servo/io/RealServoIO.java b/src/main/java/lib/hardware/misc/servo/io/RealServoIO.java similarity index 93% rename from src/main/java/trigon/hardware/misc/servo/io/RealServoIO.java rename to src/main/java/lib/hardware/misc/servo/io/RealServoIO.java index 704b0f1..b6fa616 100644 --- a/src/main/java/trigon/hardware/misc/servo/io/RealServoIO.java +++ b/src/main/java/lib/hardware/misc/servo/io/RealServoIO.java @@ -1,10 +1,10 @@ -package trigon.hardware.misc.servo.io; +package lib.hardware.misc.servo.io; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.Servo; -import trigon.hardware.misc.servo.ServoIO; -import trigon.hardware.misc.servo.ServoInputsAutoLogged; +import lib.hardware.misc.servo.ServoIO; +import lib.hardware.misc.servo.ServoInputsAutoLogged; public class RealServoIO extends ServoIO { private final Servo servo; diff --git a/src/main/java/trigon/hardware/misc/servo/io/SimulationServoIO.java b/src/main/java/lib/hardware/misc/servo/io/SimulationServoIO.java similarity index 90% rename from src/main/java/trigon/hardware/misc/servo/io/SimulationServoIO.java rename to src/main/java/lib/hardware/misc/servo/io/SimulationServoIO.java index 2672e1a..cc2cbe3 100644 --- a/src/main/java/trigon/hardware/misc/servo/io/SimulationServoIO.java +++ b/src/main/java/lib/hardware/misc/servo/io/SimulationServoIO.java @@ -1,9 +1,9 @@ -package trigon.hardware.misc.servo.io; +package lib.hardware.misc.servo.io; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Rotation2d; -import trigon.hardware.misc.servo.ServoIO; -import trigon.hardware.misc.servo.ServoInputsAutoLogged; +import lib.hardware.misc.servo.ServoIO; +import lib.hardware.misc.servo.ServoInputsAutoLogged; public class SimulationServoIO extends ServoIO { private Rotation2d maximumServoAngle = Rotation2d.fromDegrees(180); diff --git a/src/main/java/trigon/hardware/misc/simplesensor/SimpleSensor.java b/src/main/java/lib/hardware/misc/simplesensor/SimpleSensor.java similarity index 90% rename from src/main/java/trigon/hardware/misc/simplesensor/SimpleSensor.java rename to src/main/java/lib/hardware/misc/simplesensor/SimpleSensor.java index cecd049..cdfcf28 100644 --- a/src/main/java/trigon/hardware/misc/simplesensor/SimpleSensor.java +++ b/src/main/java/lib/hardware/misc/simplesensor/SimpleSensor.java @@ -1,13 +1,11 @@ -package trigon.hardware.misc.simplesensor; +package lib.hardware.misc.simplesensor; +import lib.hardware.RobotHardwareStats; +import lib.hardware.misc.simplesensor.io.AnalogSensorIO; +import lib.hardware.misc.simplesensor.io.DigitalSensorIO; +import lib.hardware.misc.simplesensor.io.DutyCycleSensorIO; +import lib.hardware.misc.simplesensor.io.SimpleSensorSimulationIO; import org.littletonrobotics.junction.Logger; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.misc.simplesensor.SimpleSensorIO; -import trigon.hardware.misc.simplesensor.SimpleSensorInputsAutoLogged; -import trigon.hardware.misc.simplesensor.io.AnalogSensorIO; -import trigon.hardware.misc.simplesensor.io.DigitalSensorIO; -import trigon.hardware.misc.simplesensor.io.DutyCycleSensorIO; -import trigon.hardware.misc.simplesensor.io.SimpleSensorSimulationIO; import java.util.function.DoubleSupplier; diff --git a/src/main/java/trigon/hardware/misc/simplesensor/SimpleSensorIO.java b/src/main/java/lib/hardware/misc/simplesensor/SimpleSensorIO.java similarity index 78% rename from src/main/java/trigon/hardware/misc/simplesensor/SimpleSensorIO.java rename to src/main/java/lib/hardware/misc/simplesensor/SimpleSensorIO.java index 693cdfb..fcd02a3 100644 --- a/src/main/java/trigon/hardware/misc/simplesensor/SimpleSensorIO.java +++ b/src/main/java/lib/hardware/misc/simplesensor/SimpleSensorIO.java @@ -1,7 +1,6 @@ -package trigon.hardware.misc.simplesensor; +package lib.hardware.misc.simplesensor; import org.littletonrobotics.junction.AutoLog; -import trigon.hardware.misc.simplesensor.SimpleSensorInputsAutoLogged; import java.util.function.DoubleSupplier; diff --git a/src/main/java/trigon/hardware/misc/simplesensor/io/AnalogSensorIO.java b/src/main/java/lib/hardware/misc/simplesensor/io/AnalogSensorIO.java similarity index 67% rename from src/main/java/trigon/hardware/misc/simplesensor/io/AnalogSensorIO.java rename to src/main/java/lib/hardware/misc/simplesensor/io/AnalogSensorIO.java index d5a12be..592cd85 100644 --- a/src/main/java/trigon/hardware/misc/simplesensor/io/AnalogSensorIO.java +++ b/src/main/java/lib/hardware/misc/simplesensor/io/AnalogSensorIO.java @@ -1,8 +1,8 @@ -package trigon.hardware.misc.simplesensor.io; +package lib.hardware.misc.simplesensor.io; import edu.wpi.first.wpilibj.AnalogInput; -import trigon.hardware.misc.simplesensor.SimpleSensorIO; -import trigon.hardware.misc.simplesensor.SimpleSensorInputsAutoLogged; +import lib.hardware.misc.simplesensor.SimpleSensorIO; +import lib.hardware.misc.simplesensor.SimpleSensorInputsAutoLogged; public class AnalogSensorIO extends SimpleSensorIO { private final AnalogInput analogInput; diff --git a/src/main/java/trigon/hardware/misc/simplesensor/io/DigitalSensorIO.java b/src/main/java/lib/hardware/misc/simplesensor/io/DigitalSensorIO.java similarity index 68% rename from src/main/java/trigon/hardware/misc/simplesensor/io/DigitalSensorIO.java rename to src/main/java/lib/hardware/misc/simplesensor/io/DigitalSensorIO.java index 574d57b..81f6d4d 100644 --- a/src/main/java/trigon/hardware/misc/simplesensor/io/DigitalSensorIO.java +++ b/src/main/java/lib/hardware/misc/simplesensor/io/DigitalSensorIO.java @@ -1,8 +1,8 @@ -package trigon.hardware.misc.simplesensor.io; +package lib.hardware.misc.simplesensor.io; import edu.wpi.first.wpilibj.DigitalInput; -import trigon.hardware.misc.simplesensor.SimpleSensorIO; -import trigon.hardware.misc.simplesensor.SimpleSensorInputsAutoLogged; +import lib.hardware.misc.simplesensor.SimpleSensorIO; +import lib.hardware.misc.simplesensor.SimpleSensorInputsAutoLogged; public class DigitalSensorIO extends SimpleSensorIO { private final DigitalInput digitalInput; diff --git a/src/main/java/trigon/hardware/misc/simplesensor/io/DutyCycleSensorIO.java b/src/main/java/lib/hardware/misc/simplesensor/io/DutyCycleSensorIO.java similarity index 71% rename from src/main/java/trigon/hardware/misc/simplesensor/io/DutyCycleSensorIO.java rename to src/main/java/lib/hardware/misc/simplesensor/io/DutyCycleSensorIO.java index 3e5ddd9..0147113 100644 --- a/src/main/java/trigon/hardware/misc/simplesensor/io/DutyCycleSensorIO.java +++ b/src/main/java/lib/hardware/misc/simplesensor/io/DutyCycleSensorIO.java @@ -1,9 +1,9 @@ -package trigon.hardware.misc.simplesensor.io; +package lib.hardware.misc.simplesensor.io; import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.DutyCycle; -import trigon.hardware.misc.simplesensor.SimpleSensorIO; -import trigon.hardware.misc.simplesensor.SimpleSensorInputsAutoLogged; +import lib.hardware.misc.simplesensor.SimpleSensorIO; +import lib.hardware.misc.simplesensor.SimpleSensorInputsAutoLogged; public class DutyCycleSensorIO extends SimpleSensorIO { private final DutyCycle dutyCycle; diff --git a/src/main/java/trigon/hardware/misc/simplesensor/io/SimpleSensorSimulationIO.java b/src/main/java/lib/hardware/misc/simplesensor/io/SimpleSensorSimulationIO.java similarity index 74% rename from src/main/java/trigon/hardware/misc/simplesensor/io/SimpleSensorSimulationIO.java rename to src/main/java/lib/hardware/misc/simplesensor/io/SimpleSensorSimulationIO.java index ac7c9ed..0db12db 100644 --- a/src/main/java/trigon/hardware/misc/simplesensor/io/SimpleSensorSimulationIO.java +++ b/src/main/java/lib/hardware/misc/simplesensor/io/SimpleSensorSimulationIO.java @@ -1,7 +1,7 @@ -package trigon.hardware.misc.simplesensor.io; +package lib.hardware.misc.simplesensor.io; -import trigon.hardware.misc.simplesensor.SimpleSensorIO; -import trigon.hardware.misc.simplesensor.SimpleSensorInputsAutoLogged; +import lib.hardware.misc.simplesensor.SimpleSensorIO; +import lib.hardware.misc.simplesensor.SimpleSensorInputsAutoLogged; import java.util.function.DoubleSupplier; diff --git a/src/main/java/trigon/hardware/phoenix6/Phoenix6Inputs.java b/src/main/java/lib/hardware/phoenix6/Phoenix6Inputs.java similarity index 95% rename from src/main/java/trigon/hardware/phoenix6/Phoenix6Inputs.java rename to src/main/java/lib/hardware/phoenix6/Phoenix6Inputs.java index 1f2aa5c..9346083 100644 --- a/src/main/java/trigon/hardware/phoenix6/Phoenix6Inputs.java +++ b/src/main/java/lib/hardware/phoenix6/Phoenix6Inputs.java @@ -1,11 +1,10 @@ -package trigon.hardware.phoenix6; +package lib.hardware.phoenix6; import com.ctre.phoenix6.BaseStatusSignal; import org.littletonrobotics.junction.LogTable; -import trigon.hardware.InputsBase; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.SignalThreadBase; -import trigon.hardware.phoenix6.Phoenix6SignalThread; +import lib.hardware.InputsBase; +import lib.hardware.RobotHardwareStats; +import lib.hardware.SignalThreadBase; import java.util.HashMap; import java.util.Map; diff --git a/src/main/java/trigon/hardware/phoenix6/Phoenix6SignalThread.java b/src/main/java/lib/hardware/phoenix6/Phoenix6SignalThread.java similarity index 96% rename from src/main/java/trigon/hardware/phoenix6/Phoenix6SignalThread.java rename to src/main/java/lib/hardware/phoenix6/Phoenix6SignalThread.java index 01d706e..319d2bb 100644 --- a/src/main/java/trigon/hardware/phoenix6/Phoenix6SignalThread.java +++ b/src/main/java/lib/hardware/phoenix6/Phoenix6SignalThread.java @@ -11,14 +11,14 @@ // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the // GNU General Public License for more details. -package trigon.hardware.phoenix6; +package lib.hardware.phoenix6; import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.StatusCode; import edu.wpi.first.wpilibj.RobotController; import edu.wpi.first.wpilibj.Timer; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.SignalThreadBase; +import lib.hardware.RobotHardwareStats; +import lib.hardware.SignalThreadBase; import java.util.ArrayList; import java.util.List; diff --git a/src/main/java/trigon/hardware/phoenix6/cancoder/CANcoderEncoder.java b/src/main/java/lib/hardware/phoenix6/cancoder/CANcoderEncoder.java similarity index 88% rename from src/main/java/trigon/hardware/phoenix6/cancoder/CANcoderEncoder.java rename to src/main/java/lib/hardware/phoenix6/cancoder/CANcoderEncoder.java index 61ebe5b..65a2409 100644 --- a/src/main/java/trigon/hardware/phoenix6/cancoder/CANcoderEncoder.java +++ b/src/main/java/lib/hardware/phoenix6/cancoder/CANcoderEncoder.java @@ -1,18 +1,16 @@ -package trigon.hardware.phoenix6.cancoder; +package lib.hardware.phoenix6.cancoder; import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.configs.CANcoderConfiguration; import com.ctre.phoenix6.hardware.CANcoder; import org.littletonrobotics.junction.Logger; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.phoenix6.Phoenix6Inputs; -import trigon.hardware.phoenix6.cancoder.CANcoderIO; -import trigon.hardware.phoenix6.cancoder.CANcoderSignal; -import trigon.hardware.phoenix6.cancoder.io.RealCANcoderIO; -import trigon.hardware.phoenix6.cancoder.io.SimulationCANcoderIO; -import trigon.hardware.phoenix6.talonfx.TalonFXMotor; -import trigon.hardware.phoenix6.talonfx.TalonFXSignal; +import lib.hardware.RobotHardwareStats; +import lib.hardware.phoenix6.Phoenix6Inputs; +import lib.hardware.phoenix6.cancoder.io.RealCANcoderIO; +import lib.hardware.phoenix6.cancoder.io.SimulationCANcoderIO; +import lib.hardware.phoenix6.talonfx.TalonFXMotor; +import lib.hardware.phoenix6.talonfx.TalonFXSignal; import java.util.function.DoubleSupplier; @@ -132,7 +130,7 @@ public void applySimulationConfiguration(CANcoderConfiguration simulationConfigu * @param signal the type of signal to get * @return the signal */ - public double getSignal(trigon.hardware.phoenix6.cancoder.CANcoderSignal signal) { + public double getSignal(CANcoderSignal signal) { return encoderInputs.getSignal(signal.name); } @@ -143,7 +141,7 @@ public double getSignal(trigon.hardware.phoenix6.cancoder.CANcoderSignal signal) * @param signal the type of signal to get * @return the threaded signal */ - public double[] getThreadedSignal(trigon.hardware.phoenix6.cancoder.CANcoderSignal signal) { + public double[] getThreadedSignal(CANcoderSignal signal) { return encoderInputs.getThreadedSignal(signal.name); } @@ -153,7 +151,7 @@ public double[] getThreadedSignal(trigon.hardware.phoenix6.cancoder.CANcoderSign * @param signal the signal to register * @param updateFrequencyHertz the frequency at which the signal will be updated */ - public void registerSignal(trigon.hardware.phoenix6.cancoder.CANcoderSignal signal, double updateFrequencyHertz) { + public void registerSignal(CANcoderSignal signal, double updateFrequencyHertz) { encoderInputs.registerSignal(encoderSignalToStatusSignal(signal), updateFrequencyHertz); } @@ -164,7 +162,7 @@ public void registerSignal(trigon.hardware.phoenix6.cancoder.CANcoderSignal sign * @param signal the signal to register * @param updateFrequencyHertz the frequency at which the signal will be updated */ - public void registerThreadedSignal(trigon.hardware.phoenix6.cancoder.CANcoderSignal signal, double updateFrequencyHertz) { + public void registerThreadedSignal(CANcoderSignal signal, double updateFrequencyHertz) { encoderInputs.registerThreadedSignal(encoderSignalToStatusSignal(signal), updateFrequencyHertz); } diff --git a/src/main/java/trigon/hardware/phoenix6/cancoder/CANcoderIO.java b/src/main/java/lib/hardware/phoenix6/cancoder/CANcoderIO.java similarity index 93% rename from src/main/java/trigon/hardware/phoenix6/cancoder/CANcoderIO.java rename to src/main/java/lib/hardware/phoenix6/cancoder/CANcoderIO.java index a6ca8fc..f44af54 100644 --- a/src/main/java/trigon/hardware/phoenix6/cancoder/CANcoderIO.java +++ b/src/main/java/lib/hardware/phoenix6/cancoder/CANcoderIO.java @@ -1,4 +1,4 @@ -package trigon.hardware.phoenix6.cancoder; +package lib.hardware.phoenix6.cancoder; import com.ctre.phoenix6.configs.CANcoderConfiguration; import com.ctre.phoenix6.hardware.CANcoder; diff --git a/src/main/java/trigon/hardware/phoenix6/cancoder/CANcoderSignal.java b/src/main/java/lib/hardware/phoenix6/cancoder/CANcoderSignal.java similarity index 87% rename from src/main/java/trigon/hardware/phoenix6/cancoder/CANcoderSignal.java rename to src/main/java/lib/hardware/phoenix6/cancoder/CANcoderSignal.java index 5165fe5..3fbdabd 100644 --- a/src/main/java/trigon/hardware/phoenix6/cancoder/CANcoderSignal.java +++ b/src/main/java/lib/hardware/phoenix6/cancoder/CANcoderSignal.java @@ -1,8 +1,8 @@ -package trigon.hardware.phoenix6.cancoder; +package lib.hardware.phoenix6.cancoder; import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.hardware.CANcoder; -import trigon.utilities.Conversions; +import lib.utilities.Conversions; import java.util.function.Function; diff --git a/src/main/java/trigon/hardware/phoenix6/cancoder/io/RealCANcoderIO.java b/src/main/java/lib/hardware/phoenix6/cancoder/io/RealCANcoderIO.java similarity index 88% rename from src/main/java/trigon/hardware/phoenix6/cancoder/io/RealCANcoderIO.java rename to src/main/java/lib/hardware/phoenix6/cancoder/io/RealCANcoderIO.java index 02cbce8..f197d8c 100644 --- a/src/main/java/trigon/hardware/phoenix6/cancoder/io/RealCANcoderIO.java +++ b/src/main/java/lib/hardware/phoenix6/cancoder/io/RealCANcoderIO.java @@ -1,8 +1,8 @@ -package trigon.hardware.phoenix6.cancoder.io; +package lib.hardware.phoenix6.cancoder.io; import com.ctre.phoenix6.configs.CANcoderConfiguration; import com.ctre.phoenix6.hardware.CANcoder; -import trigon.hardware.phoenix6.cancoder.CANcoderIO; +import lib.hardware.phoenix6.cancoder.CANcoderIO; public class RealCANcoderIO extends CANcoderIO { private final CANcoder cancoder; diff --git a/src/main/java/trigon/hardware/phoenix6/cancoder/io/SimulationCANcoderIO.java b/src/main/java/lib/hardware/phoenix6/cancoder/io/SimulationCANcoderIO.java similarity index 96% rename from src/main/java/trigon/hardware/phoenix6/cancoder/io/SimulationCANcoderIO.java rename to src/main/java/lib/hardware/phoenix6/cancoder/io/SimulationCANcoderIO.java index ef33e25..1d03908 100644 --- a/src/main/java/trigon/hardware/phoenix6/cancoder/io/SimulationCANcoderIO.java +++ b/src/main/java/lib/hardware/phoenix6/cancoder/io/SimulationCANcoderIO.java @@ -1,10 +1,10 @@ -package trigon.hardware.phoenix6.cancoder.io; +package lib.hardware.phoenix6.cancoder.io; import com.ctre.phoenix6.configs.CANcoderConfiguration; import com.ctre.phoenix6.hardware.CANcoder; import com.ctre.phoenix6.signals.SensorDirectionValue; import com.ctre.phoenix6.sim.CANcoderSimState; -import trigon.hardware.phoenix6.cancoder.CANcoderIO; +import lib.hardware.phoenix6.cancoder.CANcoderIO; import java.util.function.DoubleSupplier; diff --git a/src/main/java/trigon/hardware/phoenix6/pigeon2/Pigeon2Gyro.java b/src/main/java/lib/hardware/phoenix6/pigeon2/Pigeon2Gyro.java similarity index 80% rename from src/main/java/trigon/hardware/phoenix6/pigeon2/Pigeon2Gyro.java rename to src/main/java/lib/hardware/phoenix6/pigeon2/Pigeon2Gyro.java index 3dd3a89..2c266cd 100644 --- a/src/main/java/trigon/hardware/phoenix6/pigeon2/Pigeon2Gyro.java +++ b/src/main/java/lib/hardware/phoenix6/pigeon2/Pigeon2Gyro.java @@ -1,4 +1,4 @@ -package trigon.hardware.phoenix6.pigeon2; +package lib.hardware.phoenix6.pigeon2; import com.ctre.phoenix6.BaseStatusSignal; @@ -6,12 +6,10 @@ import com.ctre.phoenix6.hardware.Pigeon2; import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.Logger; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.phoenix6.Phoenix6Inputs; -import trigon.hardware.phoenix6.pigeon2.Pigeon2IO; -import trigon.hardware.phoenix6.pigeon2.Pigeon2Signal; -import trigon.hardware.phoenix6.pigeon2.io.RealPigeon2IO; -import trigon.hardware.phoenix6.pigeon2.io.SimulationPigeon2IO; +import lib.hardware.RobotHardwareStats; +import lib.hardware.phoenix6.Phoenix6Inputs; +import lib.hardware.phoenix6.pigeon2.io.RealPigeon2IO; +import lib.hardware.phoenix6.pigeon2.io.SimulationPigeon2IO; import java.util.function.DoubleSupplier; @@ -20,7 +18,7 @@ */ public class Pigeon2Gyro { private final String gyroName; - private final trigon.hardware.phoenix6.pigeon2.Pigeon2IO gyroIO; + private final Pigeon2IO gyroIO; private final Phoenix6Inputs gyroInputs; private final int id; @@ -96,19 +94,19 @@ public void setYaw(Rotation2d currentYaw) { gyroIO.setYaw(currentYaw); } - public double getSignal(trigon.hardware.phoenix6.pigeon2.Pigeon2Signal signal) { + public double getSignal(Pigeon2Signal signal) { return gyroInputs.getSignal(signal.name); } - public double[] getThreadedSignal(trigon.hardware.phoenix6.pigeon2.Pigeon2Signal signal) { + public double[] getThreadedSignal(Pigeon2Signal signal) { return gyroInputs.getThreadedSignal(signal.name); } - public void registerSignal(trigon.hardware.phoenix6.pigeon2.Pigeon2Signal signal, double updateFrequencyHertz) { + public void registerSignal(Pigeon2Signal signal, double updateFrequencyHertz) { gyroInputs.registerSignal(pigeon2SignalToStatusSignal(signal), updateFrequencyHertz); } - public void registerThreadedSignal(trigon.hardware.phoenix6.pigeon2.Pigeon2Signal signal, double updateFrequencyHertz) { + public void registerThreadedSignal(Pigeon2Signal signal, double updateFrequencyHertz) { gyroInputs.registerThreadedSignal(pigeon2SignalToStatusSignal(signal), updateFrequencyHertz); } @@ -120,7 +118,7 @@ private BaseStatusSignal pigeon2SignalToStatusSignal(Pigeon2Signal signal) { return signal.signalFunction.apply(pigeon2); } - private trigon.hardware.phoenix6.pigeon2.Pigeon2IO generateIO(int id, String canbus) { + private Pigeon2IO generateIO(int id, String canbus) { if (RobotHardwareStats.isReplay()) return new Pigeon2IO(); if (RobotHardwareStats.isSimulation()) diff --git a/src/main/java/trigon/hardware/phoenix6/pigeon2/Pigeon2IO.java b/src/main/java/lib/hardware/phoenix6/pigeon2/Pigeon2IO.java similarity index 93% rename from src/main/java/trigon/hardware/phoenix6/pigeon2/Pigeon2IO.java rename to src/main/java/lib/hardware/phoenix6/pigeon2/Pigeon2IO.java index 757af18..83660df 100644 --- a/src/main/java/trigon/hardware/phoenix6/pigeon2/Pigeon2IO.java +++ b/src/main/java/lib/hardware/phoenix6/pigeon2/Pigeon2IO.java @@ -1,4 +1,4 @@ -package trigon.hardware.phoenix6.pigeon2; +package lib.hardware.phoenix6.pigeon2; import com.ctre.phoenix6.configs.Pigeon2Configuration; import com.ctre.phoenix6.hardware.Pigeon2; diff --git a/src/main/java/trigon/hardware/phoenix6/pigeon2/Pigeon2Signal.java b/src/main/java/lib/hardware/phoenix6/pigeon2/Pigeon2Signal.java similarity index 90% rename from src/main/java/trigon/hardware/phoenix6/pigeon2/Pigeon2Signal.java rename to src/main/java/lib/hardware/phoenix6/pigeon2/Pigeon2Signal.java index 6509ea6..854a852 100644 --- a/src/main/java/trigon/hardware/phoenix6/pigeon2/Pigeon2Signal.java +++ b/src/main/java/lib/hardware/phoenix6/pigeon2/Pigeon2Signal.java @@ -1,9 +1,9 @@ -package trigon.hardware.phoenix6.pigeon2; +package lib.hardware.phoenix6.pigeon2; import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.hardware.Pigeon2; import com.ctre.phoenix6.hardware.core.CorePigeon2; -import trigon.utilities.Conversions; +import lib.utilities.Conversions; import java.util.function.Function; diff --git a/src/main/java/trigon/hardware/phoenix6/pigeon2/io/RealPigeon2IO.java b/src/main/java/lib/hardware/phoenix6/pigeon2/io/RealPigeon2IO.java similarity index 89% rename from src/main/java/trigon/hardware/phoenix6/pigeon2/io/RealPigeon2IO.java rename to src/main/java/lib/hardware/phoenix6/pigeon2/io/RealPigeon2IO.java index e88fe89..ba902d4 100644 --- a/src/main/java/trigon/hardware/phoenix6/pigeon2/io/RealPigeon2IO.java +++ b/src/main/java/lib/hardware/phoenix6/pigeon2/io/RealPigeon2IO.java @@ -1,9 +1,9 @@ -package trigon.hardware.phoenix6.pigeon2.io; +package lib.hardware.phoenix6.pigeon2.io; import com.ctre.phoenix6.configs.Pigeon2Configuration; import com.ctre.phoenix6.hardware.Pigeon2; import edu.wpi.first.math.geometry.Rotation2d; -import trigon.hardware.phoenix6.pigeon2.Pigeon2IO; +import lib.hardware.phoenix6.pigeon2.Pigeon2IO; public class RealPigeon2IO extends Pigeon2IO { private final Pigeon2 pigeon2; diff --git a/src/main/java/trigon/hardware/phoenix6/pigeon2/io/SimulationPigeon2IO.java b/src/main/java/lib/hardware/phoenix6/pigeon2/io/SimulationPigeon2IO.java similarity index 89% rename from src/main/java/trigon/hardware/phoenix6/pigeon2/io/SimulationPigeon2IO.java rename to src/main/java/lib/hardware/phoenix6/pigeon2/io/SimulationPigeon2IO.java index 73a8579..8d857af 100644 --- a/src/main/java/trigon/hardware/phoenix6/pigeon2/io/SimulationPigeon2IO.java +++ b/src/main/java/lib/hardware/phoenix6/pigeon2/io/SimulationPigeon2IO.java @@ -1,12 +1,12 @@ -package trigon.hardware.phoenix6.pigeon2.io; +package lib.hardware.phoenix6.pigeon2.io; import com.ctre.phoenix6.configs.Pigeon2Configuration; import com.ctre.phoenix6.hardware.Pigeon2; import com.ctre.phoenix6.sim.Pigeon2SimState; import edu.wpi.first.math.geometry.Rotation2d; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.phoenix6.pigeon2.Pigeon2IO; -import trigon.hardware.simulation.GyroSimulation; +import lib.hardware.RobotHardwareStats; +import lib.hardware.phoenix6.pigeon2.Pigeon2IO; +import lib.hardware.simulation.GyroSimulation; import java.util.function.DoubleSupplier; diff --git a/src/main/java/trigon/hardware/phoenix6/talonfx/TalonFXIO.java b/src/main/java/lib/hardware/phoenix6/talonfx/TalonFXIO.java similarity index 87% rename from src/main/java/trigon/hardware/phoenix6/talonfx/TalonFXIO.java rename to src/main/java/lib/hardware/phoenix6/talonfx/TalonFXIO.java index d511f00..a1c42be 100644 --- a/src/main/java/trigon/hardware/phoenix6/talonfx/TalonFXIO.java +++ b/src/main/java/lib/hardware/phoenix6/talonfx/TalonFXIO.java @@ -1,9 +1,9 @@ -package trigon.hardware.phoenix6.talonfx; +package lib.hardware.phoenix6.talonfx; import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.ControlRequest; import com.ctre.phoenix6.hardware.TalonFX; -import trigon.hardware.simulation.MotorPhysicsSimulation; +import lib.hardware.simulation.MotorPhysicsSimulation; public class TalonFXIO { protected void updateMotor() { diff --git a/src/main/java/trigon/hardware/phoenix6/talonfx/TalonFXMotor.java b/src/main/java/lib/hardware/phoenix6/talonfx/TalonFXMotor.java similarity index 94% rename from src/main/java/trigon/hardware/phoenix6/talonfx/TalonFXMotor.java rename to src/main/java/lib/hardware/phoenix6/talonfx/TalonFXMotor.java index c85afef..74b7120 100644 --- a/src/main/java/trigon/hardware/phoenix6/talonfx/TalonFXMotor.java +++ b/src/main/java/lib/hardware/phoenix6/talonfx/TalonFXMotor.java @@ -1,17 +1,15 @@ -package trigon.hardware.phoenix6.talonfx; +package lib.hardware.phoenix6.talonfx; import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.ControlRequest; import com.ctre.phoenix6.hardware.TalonFX; import org.littletonrobotics.junction.Logger; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.phoenix6.Phoenix6Inputs; -import trigon.hardware.phoenix6.talonfx.TalonFXIO; -import trigon.hardware.phoenix6.talonfx.TalonFXSignal; -import trigon.hardware.phoenix6.talonfx.io.RealTalonFXIO; -import trigon.hardware.phoenix6.talonfx.io.SimulationTalonFXIO; -import trigon.hardware.simulation.MotorPhysicsSimulation; +import lib.hardware.RobotHardwareStats; +import lib.hardware.phoenix6.Phoenix6Inputs; +import lib.hardware.phoenix6.talonfx.io.RealTalonFXIO; +import lib.hardware.phoenix6.talonfx.io.SimulationTalonFXIO; +import lib.hardware.simulation.MotorPhysicsSimulation; /** * A class that represents a TalonFX motor controller. diff --git a/src/main/java/trigon/hardware/phoenix6/talonfx/TalonFXSignal.java b/src/main/java/lib/hardware/phoenix6/talonfx/TalonFXSignal.java similarity index 92% rename from src/main/java/trigon/hardware/phoenix6/talonfx/TalonFXSignal.java rename to src/main/java/lib/hardware/phoenix6/talonfx/TalonFXSignal.java index 56d88de..beea072 100644 --- a/src/main/java/trigon/hardware/phoenix6/talonfx/TalonFXSignal.java +++ b/src/main/java/lib/hardware/phoenix6/talonfx/TalonFXSignal.java @@ -1,8 +1,8 @@ -package trigon.hardware.phoenix6.talonfx; +package lib.hardware.phoenix6.talonfx; import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.hardware.TalonFX; -import trigon.utilities.Conversions; +import lib.utilities.Conversions; import java.util.function.Function; diff --git a/src/main/java/trigon/hardware/phoenix6/talonfx/io/RealTalonFXIO.java b/src/main/java/lib/hardware/phoenix6/talonfx/io/RealTalonFXIO.java similarity index 92% rename from src/main/java/trigon/hardware/phoenix6/talonfx/io/RealTalonFXIO.java rename to src/main/java/lib/hardware/phoenix6/talonfx/io/RealTalonFXIO.java index ba4785e..73d9929 100644 --- a/src/main/java/trigon/hardware/phoenix6/talonfx/io/RealTalonFXIO.java +++ b/src/main/java/lib/hardware/phoenix6/talonfx/io/RealTalonFXIO.java @@ -1,10 +1,10 @@ -package trigon.hardware.phoenix6.talonfx.io; +package lib.hardware.phoenix6.talonfx.io; import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.ControlRequest; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.NeutralModeValue; -import trigon.hardware.phoenix6.talonfx.TalonFXIO; +import lib.hardware.phoenix6.talonfx.TalonFXIO; public class RealTalonFXIO extends TalonFXIO { private final TalonFX talonFX; diff --git a/src/main/java/trigon/hardware/phoenix6/talonfx/io/SimulationTalonFXIO.java b/src/main/java/lib/hardware/phoenix6/talonfx/io/SimulationTalonFXIO.java similarity index 94% rename from src/main/java/trigon/hardware/phoenix6/talonfx/io/SimulationTalonFXIO.java rename to src/main/java/lib/hardware/phoenix6/talonfx/io/SimulationTalonFXIO.java index ef1d66a..9f0c885 100644 --- a/src/main/java/trigon/hardware/phoenix6/talonfx/io/SimulationTalonFXIO.java +++ b/src/main/java/lib/hardware/phoenix6/talonfx/io/SimulationTalonFXIO.java @@ -1,4 +1,4 @@ -package trigon.hardware.phoenix6.talonfx.io; +package lib.hardware.phoenix6.talonfx.io; import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.ControlRequest; @@ -6,9 +6,9 @@ import com.ctre.phoenix6.signals.FeedbackSensorSourceValue; import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.sim.TalonFXSimState; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.phoenix6.talonfx.TalonFXIO; -import trigon.hardware.simulation.MotorPhysicsSimulation; +import lib.hardware.RobotHardwareStats; +import lib.hardware.phoenix6.talonfx.TalonFXIO; +import lib.hardware.simulation.MotorPhysicsSimulation; public class SimulationTalonFXIO extends TalonFXIO { private final TalonFX talonFX; diff --git a/src/main/java/trigon/hardware/rev/spark/SparkIO.java b/src/main/java/lib/hardware/rev/spark/SparkIO.java similarity index 90% rename from src/main/java/trigon/hardware/rev/spark/SparkIO.java rename to src/main/java/lib/hardware/rev/spark/SparkIO.java index ff52faa..a45f057 100644 --- a/src/main/java/trigon/hardware/rev/spark/SparkIO.java +++ b/src/main/java/lib/hardware/rev/spark/SparkIO.java @@ -1,11 +1,11 @@ -package trigon.hardware.rev.spark; +package lib.hardware.rev.spark; import com.revrobotics.spark.ClosedLoopSlot; import com.revrobotics.spark.SparkBase; import com.revrobotics.spark.SparkClosedLoopController; import com.revrobotics.spark.config.SparkBaseConfig; -import trigon.hardware.rev.sparkencoder.SparkEncoder; -import trigon.hardware.simulation.MotorPhysicsSimulation; +import lib.hardware.rev.sparkencoder.SparkEncoder; +import lib.hardware.simulation.MotorPhysicsSimulation; public class SparkIO { public void setReference(double value, SparkBase.ControlType ctrl) { diff --git a/src/main/java/trigon/hardware/rev/spark/SparkInputs.java b/src/main/java/lib/hardware/rev/spark/SparkInputs.java similarity index 86% rename from src/main/java/trigon/hardware/rev/spark/SparkInputs.java rename to src/main/java/lib/hardware/rev/spark/SparkInputs.java index f49bf63..dba00d5 100644 --- a/src/main/java/trigon/hardware/rev/spark/SparkInputs.java +++ b/src/main/java/lib/hardware/rev/spark/SparkInputs.java @@ -1,11 +1,9 @@ -package trigon.hardware.rev.spark; +package lib.hardware.rev.spark; import org.littletonrobotics.junction.LogTable; -import trigon.hardware.InputsBase; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.SignalThreadBase; -import trigon.hardware.rev.spark.SparkSignalThread; -import trigon.hardware.rev.spark.SparkStatusSignal; +import lib.hardware.InputsBase; +import lib.hardware.RobotHardwareStats; +import lib.hardware.SignalThreadBase; import java.util.HashMap; import java.util.Map; @@ -13,7 +11,7 @@ public class SparkInputs extends InputsBase { private final HashMap> signalToThreadedQueue = new HashMap<>(); - private final trigon.hardware.rev.spark.SparkSignalThread signalThread = SparkSignalThread.getInstance(); + private final SparkSignalThread signalThread = SparkSignalThread.getInstance(); private SparkStatusSignal[] signals = new SparkStatusSignal[0]; /** diff --git a/src/main/java/trigon/hardware/rev/spark/SparkMotor.java b/src/main/java/lib/hardware/rev/spark/SparkMotor.java similarity index 89% rename from src/main/java/trigon/hardware/rev/spark/SparkMotor.java rename to src/main/java/lib/hardware/rev/spark/SparkMotor.java index 2e70537..b996a12 100644 --- a/src/main/java/trigon/hardware/rev/spark/SparkMotor.java +++ b/src/main/java/lib/hardware/rev/spark/SparkMotor.java @@ -1,27 +1,22 @@ -package trigon.hardware.rev.spark; +package lib.hardware.rev.spark; import com.revrobotics.spark.ClosedLoopSlot; import com.revrobotics.spark.SparkBase; import com.revrobotics.spark.SparkClosedLoopController; import com.revrobotics.spark.config.SparkBaseConfig; import org.littletonrobotics.junction.Logger; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.rev.spark.SparkIO; -import trigon.hardware.rev.spark.SparkInputs; -import trigon.hardware.rev.spark.SparkSignal; -import trigon.hardware.rev.spark.SparkStatusSignal; -import trigon.hardware.rev.spark.SparkType; -import trigon.hardware.rev.spark.io.RealSparkIO; -import trigon.hardware.rev.spark.io.SimulationSparkIO; -import trigon.hardware.simulation.MotorPhysicsSimulation; +import lib.hardware.RobotHardwareStats; +import lib.hardware.rev.spark.io.RealSparkIO; +import lib.hardware.rev.spark.io.SimulationSparkIO; +import lib.hardware.simulation.MotorPhysicsSimulation; /** * A class the represents a Spark motor. Used to control and read data from a Spark motor. */ public class SparkMotor { private final String motorName; - private final trigon.hardware.rev.spark.SparkIO motorIO; - private final trigon.hardware.rev.spark.SparkInputs motorInputs; + private final SparkIO motorIO; + private final SparkInputs motorInputs; private final int id; /** @@ -56,8 +51,8 @@ public int getID() { * * @param signal the signal to be registered */ - public void registerThreadedSignal(trigon.hardware.rev.spark.SparkSignal signal) { - final trigon.hardware.rev.spark.SparkStatusSignal statusSignal = signal.getStatusSignal(motorIO.getMotor(), motorIO.getEncoder()); + public void registerThreadedSignal(SparkSignal signal) { + final SparkStatusSignal statusSignal = signal.getStatusSignal(motorIO.getMotor(), motorIO.getEncoder()); motorInputs.registerThreadedSignal(statusSignal); } @@ -66,7 +61,7 @@ public void registerThreadedSignal(trigon.hardware.rev.spark.SparkSignal signal) * * @param signal the signal to be read */ - public void registerSignal(trigon.hardware.rev.spark.SparkSignal signal) { + public void registerSignal(SparkSignal signal) { final SparkStatusSignal statusSignal = signal.getStatusSignal(motorIO.getMotor(), motorIO.getEncoder()); motorInputs.registerSignal(statusSignal); } @@ -77,7 +72,7 @@ public void registerSignal(trigon.hardware.rev.spark.SparkSignal signal) { * @param signal the signal to get * @return the signal */ - public double getSignal(trigon.hardware.rev.spark.SparkSignal signal) { + public double getSignal(SparkSignal signal) { return motorInputs.getSignal(signal.name); } @@ -236,7 +231,7 @@ public void setPhysicsSimulation(MotorPhysicsSimulation physicsSimulation, boole motorIO.setPhysicsSimulation(physicsSimulation, isUsingAbsoluteEncoder); } - private trigon.hardware.rev.spark.SparkIO createSparkIO(int id, SparkType sparkType) { + private SparkIO createSparkIO(int id, SparkType sparkType) { if (RobotHardwareStats.isReplay()) return new SparkIO(); if (RobotHardwareStats.isSimulation()) diff --git a/src/main/java/trigon/hardware/rev/spark/SparkSignal.java b/src/main/java/lib/hardware/rev/spark/SparkSignal.java similarity index 85% rename from src/main/java/trigon/hardware/rev/spark/SparkSignal.java rename to src/main/java/lib/hardware/rev/spark/SparkSignal.java index 1d64c5e..7ab2d36 100644 --- a/src/main/java/trigon/hardware/rev/spark/SparkSignal.java +++ b/src/main/java/lib/hardware/rev/spark/SparkSignal.java @@ -1,10 +1,9 @@ -package trigon.hardware.rev.spark; +package lib.hardware.rev.spark; import com.revrobotics.spark.SparkBase; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.rev.spark.SparkStatusSignal; -import trigon.hardware.rev.sparkencoder.SparkEncoder; -import trigon.utilities.Conversions; +import lib.hardware.RobotHardwareStats; +import lib.hardware.rev.sparkencoder.SparkEncoder; +import lib.utilities.Conversions; import java.util.function.Function; diff --git a/src/main/java/trigon/hardware/rev/spark/SparkSignalThread.java b/src/main/java/lib/hardware/rev/spark/SparkSignalThread.java similarity index 97% rename from src/main/java/trigon/hardware/rev/spark/SparkSignalThread.java rename to src/main/java/lib/hardware/rev/spark/SparkSignalThread.java index 8065dee..c44b9d8 100644 --- a/src/main/java/trigon/hardware/rev/spark/SparkSignalThread.java +++ b/src/main/java/lib/hardware/rev/spark/SparkSignalThread.java @@ -11,11 +11,11 @@ // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the // GNU General Public License for more details. -package trigon.hardware.rev.spark; +package lib.hardware.rev.spark; import edu.wpi.first.wpilibj.Notifier; import org.littletonrobotics.junction.Logger; -import trigon.hardware.SignalThreadBase; +import lib.hardware.SignalThreadBase; import java.util.ArrayList; import java.util.List; diff --git a/src/main/java/trigon/hardware/rev/spark/SparkStatusSignal.java b/src/main/java/lib/hardware/rev/spark/SparkStatusSignal.java similarity index 86% rename from src/main/java/trigon/hardware/rev/spark/SparkStatusSignal.java rename to src/main/java/lib/hardware/rev/spark/SparkStatusSignal.java index 02abaf6..e4768c2 100644 --- a/src/main/java/trigon/hardware/rev/spark/SparkStatusSignal.java +++ b/src/main/java/lib/hardware/rev/spark/SparkStatusSignal.java @@ -1,6 +1,4 @@ -package trigon.hardware.rev.spark; - -import trigon.hardware.rev.spark.SparkSignal; +package lib.hardware.rev.spark; import java.util.function.DoubleSupplier; diff --git a/src/main/java/trigon/hardware/rev/spark/SparkType.java b/src/main/java/lib/hardware/rev/spark/SparkType.java similarity index 94% rename from src/main/java/trigon/hardware/rev/spark/SparkType.java rename to src/main/java/lib/hardware/rev/spark/SparkType.java index 9657205..a4b78ea 100644 --- a/src/main/java/trigon/hardware/rev/spark/SparkType.java +++ b/src/main/java/lib/hardware/rev/spark/SparkType.java @@ -1,4 +1,4 @@ -package trigon.hardware.rev.spark; +package lib.hardware.rev.spark; import com.revrobotics.spark.SparkBase; import com.revrobotics.spark.SparkFlex; diff --git a/src/main/java/trigon/hardware/rev/spark/io/RealSparkIO.java b/src/main/java/lib/hardware/rev/spark/io/RealSparkIO.java similarity index 94% rename from src/main/java/trigon/hardware/rev/spark/io/RealSparkIO.java rename to src/main/java/lib/hardware/rev/spark/io/RealSparkIO.java index 81e52f1..5558acf 100644 --- a/src/main/java/trigon/hardware/rev/spark/io/RealSparkIO.java +++ b/src/main/java/lib/hardware/rev/spark/io/RealSparkIO.java @@ -1,13 +1,13 @@ -package trigon.hardware.rev.spark.io; +package lib.hardware.rev.spark.io; import com.revrobotics.spark.ClosedLoopSlot; import com.revrobotics.spark.SparkBase; import com.revrobotics.spark.SparkClosedLoopController; import com.revrobotics.spark.config.SparkBaseConfig; import com.revrobotics.spark.config.SparkMaxConfig; -import trigon.hardware.rev.spark.SparkIO; -import trigon.hardware.rev.spark.SparkType; -import trigon.hardware.rev.sparkencoder.SparkEncoder; +import lib.hardware.rev.spark.SparkIO; +import lib.hardware.rev.spark.SparkType; +import lib.hardware.rev.sparkencoder.SparkEncoder; public class RealSparkIO extends SparkIO { private final SparkBase motor; diff --git a/src/main/java/trigon/hardware/rev/spark/io/SimulationSparkIO.java b/src/main/java/lib/hardware/rev/spark/io/SimulationSparkIO.java similarity index 95% rename from src/main/java/trigon/hardware/rev/spark/io/SimulationSparkIO.java rename to src/main/java/lib/hardware/rev/spark/io/SimulationSparkIO.java index 2aef27f..a348906 100644 --- a/src/main/java/trigon/hardware/rev/spark/io/SimulationSparkIO.java +++ b/src/main/java/lib/hardware/rev/spark/io/SimulationSparkIO.java @@ -1,15 +1,15 @@ -package trigon.hardware.rev.spark.io; +package lib.hardware.rev.spark.io; import com.revrobotics.sim.SparkAbsoluteEncoderSim; import com.revrobotics.spark.*; import com.revrobotics.spark.config.SparkBaseConfig; import com.revrobotics.spark.config.SparkMaxConfig; import edu.wpi.first.math.system.plant.DCMotor; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.rev.spark.SparkIO; -import trigon.hardware.rev.sparkencoder.SparkEncoder; -import trigon.hardware.simulation.MotorPhysicsSimulation; -import trigon.utilities.Conversions; +import lib.hardware.RobotHardwareStats; +import lib.hardware.rev.spark.SparkIO; +import lib.hardware.rev.sparkencoder.SparkEncoder; +import lib.hardware.simulation.MotorPhysicsSimulation; +import lib.utilities.Conversions; public class SimulationSparkIO extends SparkIO { private final SparkMax motor; diff --git a/src/main/java/trigon/hardware/rev/sparkencoder/AbsoluteSparkEncoder.java b/src/main/java/lib/hardware/rev/sparkencoder/AbsoluteSparkEncoder.java similarity index 86% rename from src/main/java/trigon/hardware/rev/sparkencoder/AbsoluteSparkEncoder.java rename to src/main/java/lib/hardware/rev/sparkencoder/AbsoluteSparkEncoder.java index 72aa83c..34f2f02 100644 --- a/src/main/java/trigon/hardware/rev/sparkencoder/AbsoluteSparkEncoder.java +++ b/src/main/java/lib/hardware/rev/sparkencoder/AbsoluteSparkEncoder.java @@ -1,7 +1,6 @@ -package trigon.hardware.rev.sparkencoder; +package lib.hardware.rev.sparkencoder; import com.revrobotics.spark.SparkAbsoluteEncoder; -import trigon.hardware.rev.sparkencoder.SparkEncoder; /** * A class that represents an absolute encoder on a Spark MAX motor controller. diff --git a/src/main/java/trigon/hardware/rev/sparkencoder/RelativeSparkEncoder.java b/src/main/java/lib/hardware/rev/sparkencoder/RelativeSparkEncoder.java similarity index 86% rename from src/main/java/trigon/hardware/rev/sparkencoder/RelativeSparkEncoder.java rename to src/main/java/lib/hardware/rev/sparkencoder/RelativeSparkEncoder.java index e2a216c..03e5fd0 100644 --- a/src/main/java/trigon/hardware/rev/sparkencoder/RelativeSparkEncoder.java +++ b/src/main/java/lib/hardware/rev/sparkencoder/RelativeSparkEncoder.java @@ -1,7 +1,6 @@ -package trigon.hardware.rev.sparkencoder; +package lib.hardware.rev.sparkencoder; import com.revrobotics.RelativeEncoder; -import trigon.hardware.rev.sparkencoder.SparkEncoder; /** * A class that represents a relative encoder on a Spark MAX motor controller. diff --git a/src/main/java/trigon/hardware/rev/sparkencoder/SparkEncoder.java b/src/main/java/lib/hardware/rev/sparkencoder/SparkEncoder.java similarity index 89% rename from src/main/java/trigon/hardware/rev/sparkencoder/SparkEncoder.java rename to src/main/java/lib/hardware/rev/sparkencoder/SparkEncoder.java index 7015c3a..ed6ca1b 100644 --- a/src/main/java/trigon/hardware/rev/sparkencoder/SparkEncoder.java +++ b/src/main/java/lib/hardware/rev/sparkencoder/SparkEncoder.java @@ -1,9 +1,7 @@ -package trigon.hardware.rev.sparkencoder; +package lib.hardware.rev.sparkencoder; import com.revrobotics.spark.SparkAbsoluteEncoder; import com.revrobotics.spark.SparkBase; -import trigon.hardware.rev.sparkencoder.AbsoluteSparkEncoder; -import trigon.hardware.rev.sparkencoder.RelativeSparkEncoder; public abstract class SparkEncoder { /** diff --git a/src/main/java/trigon/hardware/simulation/ElevatorSimulation.java b/src/main/java/lib/hardware/simulation/ElevatorSimulation.java similarity index 94% rename from src/main/java/trigon/hardware/simulation/ElevatorSimulation.java rename to src/main/java/lib/hardware/simulation/ElevatorSimulation.java index 58a7f6b..c14bcc8 100644 --- a/src/main/java/trigon/hardware/simulation/ElevatorSimulation.java +++ b/src/main/java/lib/hardware/simulation/ElevatorSimulation.java @@ -1,10 +1,9 @@ -package trigon.hardware.simulation; +package lib.hardware.simulation; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.wpilibj.simulation.ElevatorSim; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.simulation.MotorPhysicsSimulation; -import trigon.utilities.Conversions; +import lib.hardware.RobotHardwareStats; +import lib.utilities.Conversions; /** * A class that represents a simulation of an elevator mechanism. diff --git a/src/main/java/trigon/hardware/simulation/GyroSimulation.java b/src/main/java/lib/hardware/simulation/GyroSimulation.java similarity index 96% rename from src/main/java/trigon/hardware/simulation/GyroSimulation.java rename to src/main/java/lib/hardware/simulation/GyroSimulation.java index b0afef3..d0cb03c 100644 --- a/src/main/java/trigon/hardware/simulation/GyroSimulation.java +++ b/src/main/java/lib/hardware/simulation/GyroSimulation.java @@ -1,4 +1,4 @@ -package trigon.hardware.simulation; +package lib.hardware.simulation; import edu.wpi.first.math.geometry.Rotation2d; diff --git a/src/main/java/trigon/hardware/simulation/MotorPhysicsSimulation.java b/src/main/java/lib/hardware/simulation/MotorPhysicsSimulation.java similarity index 95% rename from src/main/java/trigon/hardware/simulation/MotorPhysicsSimulation.java rename to src/main/java/lib/hardware/simulation/MotorPhysicsSimulation.java index 0b36067..bf40929 100644 --- a/src/main/java/trigon/hardware/simulation/MotorPhysicsSimulation.java +++ b/src/main/java/lib/hardware/simulation/MotorPhysicsSimulation.java @@ -1,4 +1,4 @@ -package trigon.hardware.simulation; +package lib.hardware.simulation; /** * An abstract class to simulate the physics of a motor. diff --git a/src/main/java/trigon/hardware/simulation/SimpleMotorSimulation.java b/src/main/java/lib/hardware/simulation/SimpleMotorSimulation.java similarity index 94% rename from src/main/java/trigon/hardware/simulation/SimpleMotorSimulation.java rename to src/main/java/lib/hardware/simulation/SimpleMotorSimulation.java index 33fe7bc..a46b70f 100644 --- a/src/main/java/trigon/hardware/simulation/SimpleMotorSimulation.java +++ b/src/main/java/lib/hardware/simulation/SimpleMotorSimulation.java @@ -1,11 +1,10 @@ -package trigon.hardware.simulation; +package lib.hardware.simulation; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.system.plant.LinearSystemId; import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.simulation.DCMotorSim; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.simulation.MotorPhysicsSimulation; +import lib.hardware.RobotHardwareStats; /** * A class that represents a simulation of a simple motor mechanism, such as flywheel and turret mechanisms. diff --git a/src/main/java/trigon/hardware/simulation/SingleJointedArmSimulation.java b/src/main/java/lib/hardware/simulation/SingleJointedArmSimulation.java similarity index 94% rename from src/main/java/trigon/hardware/simulation/SingleJointedArmSimulation.java rename to src/main/java/lib/hardware/simulation/SingleJointedArmSimulation.java index 402876d..6003f14 100644 --- a/src/main/java/trigon/hardware/simulation/SingleJointedArmSimulation.java +++ b/src/main/java/lib/hardware/simulation/SingleJointedArmSimulation.java @@ -1,11 +1,10 @@ -package trigon.hardware.simulation; +package lib.hardware.simulation; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; -import trigon.hardware.RobotHardwareStats; -import trigon.hardware.simulation.MotorPhysicsSimulation; +import lib.hardware.RobotHardwareStats; /** * A class that represents a simulation of a single jointed arm mechanism. diff --git a/src/main/java/trigon/utilities/Conversions.java b/src/main/java/lib/utilities/Conversions.java similarity index 99% rename from src/main/java/trigon/utilities/Conversions.java rename to src/main/java/lib/utilities/Conversions.java index 6c707a9..f75ab06 100644 --- a/src/main/java/trigon/utilities/Conversions.java +++ b/src/main/java/lib/utilities/Conversions.java @@ -1,4 +1,4 @@ -package trigon.utilities; +package lib.utilities; import edu.wpi.first.math.trajectory.TrapezoidProfile; diff --git a/src/main/java/trigon/utilities/FilesHandler.java b/src/main/java/lib/utilities/FilesHandler.java similarity index 99% rename from src/main/java/trigon/utilities/FilesHandler.java rename to src/main/java/lib/utilities/FilesHandler.java index 156dfcd..c6ef44d 100644 --- a/src/main/java/trigon/utilities/FilesHandler.java +++ b/src/main/java/lib/utilities/FilesHandler.java @@ -1,4 +1,4 @@ -package trigon.utilities; +package lib.utilities; import edu.wpi.first.wpilibj.Filesystem; diff --git a/src/main/java/trigon/utilities/JsonHandler.java b/src/main/java/lib/utilities/JsonHandler.java similarity index 96% rename from src/main/java/trigon/utilities/JsonHandler.java rename to src/main/java/lib/utilities/JsonHandler.java index 3921577..ec20aa5 100644 --- a/src/main/java/trigon/utilities/JsonHandler.java +++ b/src/main/java/lib/utilities/JsonHandler.java @@ -1,8 +1,7 @@ -package trigon.utilities; +package lib.utilities; import com.google.gson.Gson; import com.google.gson.GsonBuilder; -import trigon.utilities.FilesHandler; import java.io.IOException; diff --git a/src/main/java/trigon/utilities/LimelightHelpers.java b/src/main/java/lib/utilities/LimelightHelpers.java similarity index 99% rename from src/main/java/trigon/utilities/LimelightHelpers.java rename to src/main/java/lib/utilities/LimelightHelpers.java index c8fc659..bf23fca 100644 --- a/src/main/java/trigon/utilities/LimelightHelpers.java +++ b/src/main/java/lib/utilities/LimelightHelpers.java @@ -1,6 +1,6 @@ //LimelightHelpers v1.10 (REQUIRES LLOS 2024.9.1 OR LATER) -package trigon.utilities; +package lib.utilities; import com.fasterxml.jackson.annotation.JsonFormat; import com.fasterxml.jackson.annotation.JsonFormat.Shape; diff --git a/src/main/java/trigon/utilities/LocalADStarAK.java b/src/main/java/lib/utilities/LocalADStarAK.java similarity index 99% rename from src/main/java/trigon/utilities/LocalADStarAK.java rename to src/main/java/lib/utilities/LocalADStarAK.java index 0e7ad01..1fa1edc 100644 --- a/src/main/java/trigon/utilities/LocalADStarAK.java +++ b/src/main/java/lib/utilities/LocalADStarAK.java @@ -1,4 +1,4 @@ -package trigon.utilities; +package lib.utilities; import com.pathplanner.lib.path.GoalEndState; import com.pathplanner.lib.path.PathConstraints; diff --git a/src/main/java/trigon/utilities/QuickSortHandler.java b/src/main/java/lib/utilities/QuickSortHandler.java similarity index 99% rename from src/main/java/trigon/utilities/QuickSortHandler.java rename to src/main/java/lib/utilities/QuickSortHandler.java index b70f89e..1224bff 100644 --- a/src/main/java/trigon/utilities/QuickSortHandler.java +++ b/src/main/java/lib/utilities/QuickSortHandler.java @@ -1,4 +1,4 @@ -package trigon.utilities; +package lib.utilities; import java.util.function.ToDoubleFunction; diff --git a/src/main/java/trigon/utilities/RGBArrayUtils.java b/src/main/java/lib/utilities/RGBArrayUtils.java similarity index 99% rename from src/main/java/trigon/utilities/RGBArrayUtils.java rename to src/main/java/lib/utilities/RGBArrayUtils.java index 50b8068..56a2d1e 100644 --- a/src/main/java/trigon/utilities/RGBArrayUtils.java +++ b/src/main/java/lib/utilities/RGBArrayUtils.java @@ -1,4 +1,4 @@ -package trigon.utilities; +package lib.utilities; import javax.imageio.ImageIO; import java.awt.*; diff --git a/src/main/java/trigon/utilities/flippable/Flippable.java b/src/main/java/lib/utilities/flippable/Flippable.java similarity index 98% rename from src/main/java/trigon/utilities/flippable/Flippable.java rename to src/main/java/lib/utilities/flippable/Flippable.java index 95b044b..d649f4a 100644 --- a/src/main/java/trigon/utilities/flippable/Flippable.java +++ b/src/main/java/lib/utilities/flippable/Flippable.java @@ -1,4 +1,4 @@ -package trigon.utilities.flippable; +package lib.utilities.flippable; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.Timer; diff --git a/src/main/java/trigon/utilities/flippable/FlippablePose2d.java b/src/main/java/lib/utilities/flippable/FlippablePose2d.java similarity index 91% rename from src/main/java/trigon/utilities/flippable/FlippablePose2d.java rename to src/main/java/lib/utilities/flippable/FlippablePose2d.java index 18b4f5e..a838102 100644 --- a/src/main/java/trigon/utilities/flippable/FlippablePose2d.java +++ b/src/main/java/lib/utilities/flippable/FlippablePose2d.java @@ -1,11 +1,9 @@ -package trigon.utilities.flippable; +package lib.utilities.flippable; import com.pathplanner.lib.util.FlippingUtil; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Translation2d; -import trigon.utilities.flippable.Flippable; -import trigon.utilities.flippable.FlippableRotation2d; /** * A class that represents a {@link Pose2d} that can be flipped when the robot is on the red alliance. @@ -49,7 +47,7 @@ public FlippablePose2d(Pose2d nonFlippedPose, boolean shouldFlipWhenRedAlliance) * * @return the rotation value of the pose */ - public trigon.utilities.flippable.FlippableRotation2d getRotation() { + public FlippableRotation2d getRotation() { return new FlippableRotation2d(nonFlippedObject.getRotation(), shouldFlipWhenRedAlliance); } diff --git a/src/main/java/trigon/utilities/flippable/FlippablePose3d.java b/src/main/java/lib/utilities/flippable/FlippablePose3d.java similarity index 96% rename from src/main/java/trigon/utilities/flippable/FlippablePose3d.java rename to src/main/java/lib/utilities/flippable/FlippablePose3d.java index e857651..0ac5b46 100644 --- a/src/main/java/trigon/utilities/flippable/FlippablePose3d.java +++ b/src/main/java/lib/utilities/flippable/FlippablePose3d.java @@ -1,11 +1,10 @@ -package trigon.utilities.flippable; +package lib.utilities.flippable; import com.pathplanner.lib.util.FlippingUtil; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Translation3d; -import trigon.utilities.flippable.Flippable; /** * A class that represents a {@link Pose3d} that can be flipped when the robot is on the red alliance. diff --git a/src/main/java/trigon/utilities/flippable/FlippableRotation2d.java b/src/main/java/lib/utilities/flippable/FlippableRotation2d.java similarity index 97% rename from src/main/java/trigon/utilities/flippable/FlippableRotation2d.java rename to src/main/java/lib/utilities/flippable/FlippableRotation2d.java index d143b2c..07b1193 100644 --- a/src/main/java/trigon/utilities/flippable/FlippableRotation2d.java +++ b/src/main/java/lib/utilities/flippable/FlippableRotation2d.java @@ -1,8 +1,7 @@ -package trigon.utilities.flippable; +package lib.utilities.flippable; import com.pathplanner.lib.util.FlippingUtil; import edu.wpi.first.math.geometry.Rotation2d; -import trigon.utilities.flippable.Flippable; /** * A class that represents a {@link Rotation2d} that can be flipped when the robot is on the red alliance. diff --git a/src/main/java/trigon/utilities/flippable/FlippableTranslation2d.java b/src/main/java/lib/utilities/flippable/FlippableTranslation2d.java similarity index 94% rename from src/main/java/trigon/utilities/flippable/FlippableTranslation2d.java rename to src/main/java/lib/utilities/flippable/FlippableTranslation2d.java index fd5f90f..bd69aae 100644 --- a/src/main/java/trigon/utilities/flippable/FlippableTranslation2d.java +++ b/src/main/java/lib/utilities/flippable/FlippableTranslation2d.java @@ -1,8 +1,7 @@ -package trigon.utilities.flippable; +package lib.utilities.flippable; import com.pathplanner.lib.util.FlippingUtil; import edu.wpi.first.math.geometry.Translation2d; -import trigon.utilities.flippable.Flippable; /** * A class that represents a {@link Translation2d} that can be flipped when the robot is on the red alliance. diff --git a/src/main/java/trigon/utilities/flippable/FlippableTranslation3d.java b/src/main/java/lib/utilities/flippable/FlippableTranslation3d.java similarity index 96% rename from src/main/java/trigon/utilities/flippable/FlippableTranslation3d.java rename to src/main/java/lib/utilities/flippable/FlippableTranslation3d.java index 6d28eaf..cf421cf 100644 --- a/src/main/java/trigon/utilities/flippable/FlippableTranslation3d.java +++ b/src/main/java/lib/utilities/flippable/FlippableTranslation3d.java @@ -1,9 +1,8 @@ -package trigon.utilities.flippable; +package lib.utilities.flippable; import com.pathplanner.lib.util.FlippingUtil; import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.math.geometry.Translation3d; -import trigon.utilities.flippable.Flippable; /** * A class that represents a {@link Translation3d} that can be flipped when the robot is on the red alliance. diff --git a/src/main/java/trigon/utilities/mechanisms/ArmElevatorMechanism2d.java b/src/main/java/lib/utilities/mechanisms/ArmElevatorMechanism2d.java similarity index 98% rename from src/main/java/trigon/utilities/mechanisms/ArmElevatorMechanism2d.java rename to src/main/java/lib/utilities/mechanisms/ArmElevatorMechanism2d.java index f2dbc89..859a315 100644 --- a/src/main/java/trigon/utilities/mechanisms/ArmElevatorMechanism2d.java +++ b/src/main/java/lib/utilities/mechanisms/ArmElevatorMechanism2d.java @@ -1,4 +1,4 @@ -package trigon.utilities.mechanisms; +package lib.utilities.mechanisms; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.util.Color; @@ -7,7 +7,6 @@ import org.littletonrobotics.junction.mechanism.LoggedMechanism2d; import org.littletonrobotics.junction.mechanism.LoggedMechanismLigament2d; import org.littletonrobotics.junction.mechanism.LoggedMechanismRoot2d; -import trigon.utilities.mechanisms.MechanismConstants; /** * A Mechanism2d object to display the current angle and target angle, and the current position and target position of an arm elevator. diff --git a/src/main/java/trigon/utilities/mechanisms/DoubleJointedArmMechanism2d.java b/src/main/java/lib/utilities/mechanisms/DoubleJointedArmMechanism2d.java similarity index 87% rename from src/main/java/trigon/utilities/mechanisms/DoubleJointedArmMechanism2d.java rename to src/main/java/lib/utilities/mechanisms/DoubleJointedArmMechanism2d.java index 7037056..dacb816 100644 --- a/src/main/java/trigon/utilities/mechanisms/DoubleJointedArmMechanism2d.java +++ b/src/main/java/lib/utilities/mechanisms/DoubleJointedArmMechanism2d.java @@ -1,4 +1,4 @@ -package trigon.utilities.mechanisms; +package lib.utilities.mechanisms; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.util.Color; @@ -7,7 +7,6 @@ import org.littletonrobotics.junction.mechanism.LoggedMechanism2d; import org.littletonrobotics.junction.mechanism.LoggedMechanismLigament2d; import org.littletonrobotics.junction.mechanism.LoggedMechanismRoot2d; -import trigon.utilities.mechanisms.MechanismConstants; /** * A Mechanism2d object to display the current angle and the target angle of a double-jointed arm. @@ -28,7 +27,7 @@ public class DoubleJointedArmMechanism2d { * @param mechanismColor the color of the mechanism */ public DoubleJointedArmMechanism2d(String key, Color mechanismColor) { - this(key, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_LENGTH, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_LENGTH, mechanismColor); + this(key, MechanismConstants.MECHANISM_LINE_LENGTH, MechanismConstants.MECHANISM_LINE_LENGTH, mechanismColor); } /** @@ -41,14 +40,14 @@ public DoubleJointedArmMechanism2d(String key, Color mechanismColor) { */ public DoubleJointedArmMechanism2d(String name, double firstJointLength, double secondJointLength, Color mechanismColor) { this.key = "Mechanisms/" + name; - final double mechanismMiddle = trigon.utilities.mechanisms.MechanismConstants.LIGAMENT_END_TO_EDGE_RATIO * (firstJointLength + secondJointLength); + final double mechanismMiddle = MechanismConstants.LIGAMENT_END_TO_EDGE_RATIO * (firstJointLength + secondJointLength); this.mechanism = new LoggedMechanism2d(2 * mechanismMiddle, 2 * mechanismMiddle); final LoggedMechanismRoot2d root = mechanism.getRoot("Root", mechanismMiddle, mechanismMiddle); - this.currentPositionFirstLigament = root.append(new LoggedMechanismLigament2d("ZCurrentPositionFirstLigament", firstJointLength, 0, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_WIDTH, new Color8Bit(mechanismColor))); - this.currentPositionSecondLigament = currentPositionFirstLigament.append(new LoggedMechanismLigament2d("ZCurrentPositionSecondLigament", secondJointLength, 0, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_WIDTH, new Color8Bit(mechanismColor))); - this.targetPositionFirstLigament = root.append(new LoggedMechanismLigament2d("TargetPositionFirstLigament", firstJointLength, 0, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_WIDTH, trigon.utilities.mechanisms.MechanismConstants.GRAY)); - this.targetPositionSecondLigament = targetPositionFirstLigament.append(new LoggedMechanismLigament2d("TargetPositionSecondLigament", secondJointLength, 0, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_WIDTH, MechanismConstants.GRAY)); + this.currentPositionFirstLigament = root.append(new LoggedMechanismLigament2d("ZCurrentPositionFirstLigament", firstJointLength, 0, MechanismConstants.MECHANISM_LINE_WIDTH, new Color8Bit(mechanismColor))); + this.currentPositionSecondLigament = currentPositionFirstLigament.append(new LoggedMechanismLigament2d("ZCurrentPositionSecondLigament", secondJointLength, 0, MechanismConstants.MECHANISM_LINE_WIDTH, new Color8Bit(mechanismColor))); + this.targetPositionFirstLigament = root.append(new LoggedMechanismLigament2d("TargetPositionFirstLigament", firstJointLength, 0, MechanismConstants.MECHANISM_LINE_WIDTH, MechanismConstants.GRAY)); + this.targetPositionSecondLigament = targetPositionFirstLigament.append(new LoggedMechanismLigament2d("TargetPositionSecondLigament", secondJointLength, 0, MechanismConstants.MECHANISM_LINE_WIDTH, MechanismConstants.GRAY)); } /** diff --git a/src/main/java/trigon/utilities/mechanisms/ElevatorMechanism2d.java b/src/main/java/lib/utilities/mechanisms/ElevatorMechanism2d.java similarity index 97% rename from src/main/java/trigon/utilities/mechanisms/ElevatorMechanism2d.java rename to src/main/java/lib/utilities/mechanisms/ElevatorMechanism2d.java index 19c6180..9c995e9 100644 --- a/src/main/java/trigon/utilities/mechanisms/ElevatorMechanism2d.java +++ b/src/main/java/lib/utilities/mechanisms/ElevatorMechanism2d.java @@ -1,4 +1,4 @@ -package trigon.utilities.mechanisms; +package lib.utilities.mechanisms; import edu.wpi.first.wpilibj.util.Color; import edu.wpi.first.wpilibj.util.Color8Bit; @@ -6,7 +6,6 @@ import org.littletonrobotics.junction.mechanism.LoggedMechanism2d; import org.littletonrobotics.junction.mechanism.LoggedMechanismLigament2d; import org.littletonrobotics.junction.mechanism.LoggedMechanismRoot2d; -import trigon.utilities.mechanisms.MechanismConstants; /** * A Mechanism2d object to display the current position and target position of an elevator. diff --git a/src/main/java/trigon/utilities/mechanisms/MechanismConstants.java b/src/main/java/lib/utilities/mechanisms/MechanismConstants.java similarity index 96% rename from src/main/java/trigon/utilities/mechanisms/MechanismConstants.java rename to src/main/java/lib/utilities/mechanisms/MechanismConstants.java index 728b4e4..6b32ae6 100644 --- a/src/main/java/trigon/utilities/mechanisms/MechanismConstants.java +++ b/src/main/java/lib/utilities/mechanisms/MechanismConstants.java @@ -1,4 +1,4 @@ -package trigon.utilities.mechanisms; +package lib.utilities.mechanisms; import edu.wpi.first.wpilibj.util.Color; import edu.wpi.first.wpilibj.util.Color8Bit; diff --git a/src/main/java/trigon/utilities/mechanisms/SingleJointedArmMechanism2d.java b/src/main/java/lib/utilities/mechanisms/SingleJointedArmMechanism2d.java similarity index 81% rename from src/main/java/trigon/utilities/mechanisms/SingleJointedArmMechanism2d.java rename to src/main/java/lib/utilities/mechanisms/SingleJointedArmMechanism2d.java index 38effe5..082ad7d 100644 --- a/src/main/java/trigon/utilities/mechanisms/SingleJointedArmMechanism2d.java +++ b/src/main/java/lib/utilities/mechanisms/SingleJointedArmMechanism2d.java @@ -1,4 +1,4 @@ -package trigon.utilities.mechanisms; +package lib.utilities.mechanisms; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.util.Color; @@ -7,7 +7,6 @@ import org.littletonrobotics.junction.mechanism.LoggedMechanism2d; import org.littletonrobotics.junction.mechanism.LoggedMechanismLigament2d; import org.littletonrobotics.junction.mechanism.LoggedMechanismRoot2d; -import trigon.utilities.mechanisms.MechanismConstants; /** * A Mechanism2d object to display the current angle and the target angle of a single jointed arm. @@ -26,7 +25,7 @@ public class SingleJointedArmMechanism2d { * @param mechanismColor the color of the mechanism */ public SingleJointedArmMechanism2d(String key, Color mechanismColor) { - this(key, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_LENGTH, mechanismColor); + this(key, MechanismConstants.MECHANISM_LINE_LENGTH, mechanismColor); } /** @@ -38,11 +37,11 @@ public SingleJointedArmMechanism2d(String key, Color mechanismColor) { */ public SingleJointedArmMechanism2d(String name, double armLength, Color mechanismColor) { this.key = "Mechanisms/" + name; - final double mechanismMiddle = trigon.utilities.mechanisms.MechanismConstants.LIGAMENT_END_TO_EDGE_RATIO * armLength; + final double mechanismMiddle = MechanismConstants.LIGAMENT_END_TO_EDGE_RATIO * armLength; this.mechanism = new LoggedMechanism2d(2 * mechanismMiddle, 2 * mechanismMiddle); final LoggedMechanismRoot2d root = mechanism.getRoot("Root", mechanismMiddle, mechanismMiddle); - this.currentPositionLigament = root.append(new LoggedMechanismLigament2d("ZCurrentPositionLigament", armLength, 0, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_WIDTH, new Color8Bit(mechanismColor))); - this.targetPositionLigament = root.append(new LoggedMechanismLigament2d("TargetPositionLigament", armLength, 0, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_WIDTH, MechanismConstants.GRAY)); + this.currentPositionLigament = root.append(new LoggedMechanismLigament2d("ZCurrentPositionLigament", armLength, 0, MechanismConstants.MECHANISM_LINE_WIDTH, new Color8Bit(mechanismColor))); + this.targetPositionLigament = root.append(new LoggedMechanismLigament2d("TargetPositionLigament", armLength, 0, MechanismConstants.MECHANISM_LINE_WIDTH, MechanismConstants.GRAY)); } /** diff --git a/src/main/java/trigon/utilities/mechanisms/SpeedMechanism2d.java b/src/main/java/lib/utilities/mechanisms/SpeedMechanism2d.java similarity index 66% rename from src/main/java/trigon/utilities/mechanisms/SpeedMechanism2d.java rename to src/main/java/lib/utilities/mechanisms/SpeedMechanism2d.java index 9fd24e0..81d7e22 100644 --- a/src/main/java/trigon/utilities/mechanisms/SpeedMechanism2d.java +++ b/src/main/java/lib/utilities/mechanisms/SpeedMechanism2d.java @@ -1,11 +1,10 @@ -package trigon.utilities.mechanisms; +package lib.utilities.mechanisms; import edu.wpi.first.wpilibj.util.Color8Bit; import org.littletonrobotics.junction.Logger; import org.littletonrobotics.junction.mechanism.LoggedMechanism2d; import org.littletonrobotics.junction.mechanism.LoggedMechanismLigament2d; import org.littletonrobotics.junction.mechanism.LoggedMechanismRoot2d; -import trigon.utilities.mechanisms.MechanismConstants; /** * A Mechanism2d object to display the current velocity and target velocity of a mechanism. @@ -43,13 +42,13 @@ public SpeedMechanism2d(String name, double maximumDisplayableVelocity, double d this.key = "Mechanisms/" + name; this.mechanism = new LoggedMechanism2d(2 * maximumDisplayableVelocity, 2 * maximumDisplayableVelocity); final LoggedMechanismRoot2d root = mechanism.getRoot("Root", maximumDisplayableVelocity, maximumDisplayableVelocity); - this.currentVelocityLigament = root.append(new LoggedMechanismLigament2d("ZCurrentVelocityLigament", 0, 0, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_WIDTH, trigon.utilities.mechanisms.MechanismConstants.BLUE)); - this.currentVelocityTopArrowLigament = currentVelocityLigament.append(new LoggedMechanismLigament2d("ZCurrentVelocityTopArrowLigament", trigon.utilities.mechanisms.MechanismConstants.ARROW_LENGTH_SCALE * maximumDisplayableVelocity, trigon.utilities.mechanisms.MechanismConstants.ZERO_TOP_ANGLE, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_WIDTH, trigon.utilities.mechanisms.MechanismConstants.BLUE)); - this.currentVelocityBottomArrowLigament = currentVelocityLigament.append(new LoggedMechanismLigament2d("ZCurrentVelocityBottomArrowLigament", trigon.utilities.mechanisms.MechanismConstants.ARROW_LENGTH_SCALE * maximumDisplayableVelocity, trigon.utilities.mechanisms.MechanismConstants.ZERO_BOTTOM_ANGLE, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_WIDTH, trigon.utilities.mechanisms.MechanismConstants.BLUE)); + this.currentVelocityLigament = root.append(new LoggedMechanismLigament2d("ZCurrentVelocityLigament", 0, 0, MechanismConstants.MECHANISM_LINE_WIDTH, MechanismConstants.BLUE)); + this.currentVelocityTopArrowLigament = currentVelocityLigament.append(new LoggedMechanismLigament2d("ZCurrentVelocityTopArrowLigament", MechanismConstants.ARROW_LENGTH_SCALE * maximumDisplayableVelocity, MechanismConstants.ZERO_TOP_ANGLE, MechanismConstants.MECHANISM_LINE_WIDTH, MechanismConstants.BLUE)); + this.currentVelocityBottomArrowLigament = currentVelocityLigament.append(new LoggedMechanismLigament2d("ZCurrentVelocityBottomArrowLigament", MechanismConstants.ARROW_LENGTH_SCALE * maximumDisplayableVelocity, MechanismConstants.ZERO_BOTTOM_ANGLE, MechanismConstants.MECHANISM_LINE_WIDTH, MechanismConstants.BLUE)); - this.targetVelocityLigament = root.append(new LoggedMechanismLigament2d("TargetVelocityLigament", 0, 0, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_WIDTH, trigon.utilities.mechanisms.MechanismConstants.GRAY)); - this.targetVelocityTopArrowLigament = targetVelocityLigament.append(new LoggedMechanismLigament2d("TargetVelocityTopArrowLigament", trigon.utilities.mechanisms.MechanismConstants.ARROW_LENGTH_SCALE * maximumDisplayableVelocity, trigon.utilities.mechanisms.MechanismConstants.ZERO_TOP_ANGLE, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_WIDTH, trigon.utilities.mechanisms.MechanismConstants.GRAY)); - this.targetVelocityBottomArrowLigament = targetVelocityLigament.append(new LoggedMechanismLigament2d("TargetVelocityBottomArrowLigament", trigon.utilities.mechanisms.MechanismConstants.ARROW_LENGTH_SCALE * maximumDisplayableVelocity, trigon.utilities.mechanisms.MechanismConstants.ZERO_BOTTOM_ANGLE, trigon.utilities.mechanisms.MechanismConstants.MECHANISM_LINE_WIDTH, trigon.utilities.mechanisms.MechanismConstants.GRAY)); + this.targetVelocityLigament = root.append(new LoggedMechanismLigament2d("TargetVelocityLigament", 0, 0, MechanismConstants.MECHANISM_LINE_WIDTH, MechanismConstants.GRAY)); + this.targetVelocityTopArrowLigament = targetVelocityLigament.append(new LoggedMechanismLigament2d("TargetVelocityTopArrowLigament", MechanismConstants.ARROW_LENGTH_SCALE * maximumDisplayableVelocity, MechanismConstants.ZERO_TOP_ANGLE, MechanismConstants.MECHANISM_LINE_WIDTH, MechanismConstants.GRAY)); + this.targetVelocityBottomArrowLigament = targetVelocityLigament.append(new LoggedMechanismLigament2d("TargetVelocityBottomArrowLigament", MechanismConstants.ARROW_LENGTH_SCALE * maximumDisplayableVelocity, MechanismConstants.ZERO_BOTTOM_ANGLE, MechanismConstants.MECHANISM_LINE_WIDTH, MechanismConstants.GRAY)); } /** @@ -109,21 +108,21 @@ private void setCurrentLigamentColor(Color8Bit color) { private Color8Bit velocityToColor(double velocity) { if (velocity > deadband) - return trigon.utilities.mechanisms.MechanismConstants.GREEN; + return MechanismConstants.GREEN; else if (velocity < -deadband) - return trigon.utilities.mechanisms.MechanismConstants.RED; - return trigon.utilities.mechanisms.MechanismConstants.BLUE; + return MechanismConstants.RED; + return MechanismConstants.BLUE; } private void setArrowAngle(double velocity, LoggedMechanismLigament2d topLigament, LoggedMechanismLigament2d bottomLigament) { if (velocity > deadband) { - topLigament.setAngle(trigon.utilities.mechanisms.MechanismConstants.POSITIVE_TOP_ANGLE); - bottomLigament.setAngle(trigon.utilities.mechanisms.MechanismConstants.POSITIVE_BOTTOM_ANGLE); + topLigament.setAngle(MechanismConstants.POSITIVE_TOP_ANGLE); + bottomLigament.setAngle(MechanismConstants.POSITIVE_BOTTOM_ANGLE); } else if (velocity < -deadband) { - topLigament.setAngle(trigon.utilities.mechanisms.MechanismConstants.NEGATIVE_TOP_ANGLE); - bottomLigament.setAngle(trigon.utilities.mechanisms.MechanismConstants.NEGATIVE_BOTTOM_ANGLE); + topLigament.setAngle(MechanismConstants.NEGATIVE_TOP_ANGLE); + bottomLigament.setAngle(MechanismConstants.NEGATIVE_BOTTOM_ANGLE); } else { - topLigament.setAngle(trigon.utilities.mechanisms.MechanismConstants.ZERO_TOP_ANGLE); + topLigament.setAngle(MechanismConstants.ZERO_TOP_ANGLE); bottomLigament.setAngle(MechanismConstants.ZERO_BOTTOM_ANGLE); } }