From bd72299b2d94e90fa3c1db26badfbc9700912f6f Mon Sep 17 00:00:00 2001 From: Kaya <95276965+kytpbs@users.noreply.github.com> Date: Mon, 27 May 2024 23:48:06 +0300 Subject: [PATCH] =?UTF-8?q?Revert=20"[=E2=80=BC=EF=B8=8FBreaking]=20Update?= =?UTF-8?q?=20to=20LogitechController=20Instead"?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit This reverts commit 79383ceee012592fdabf725c2d394ddb4c49bf25. --- src/main/java/frc/robot/RobotContainer.java | 3 +- .../robot/subsystems/LogitechController.java | 20 ---- .../drive_subsystem_tests/DriveTests.java | 92 ------------------- 3 files changed, 1 insertion(+), 114 deletions(-) delete mode 100644 src/main/java/frc/robot/subsystems/LogitechController.java delete mode 100644 src/test/java/subsystem_tests/drive_subsystem_tests/DriveTests.java diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 87ff99c..5298771 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -31,13 +31,12 @@ import frc.robot.subsystems.IntakeSubsystem; import frc.robot.subsystems.LEDSubsystem; import frc.robot.subsystems.LEDSystem; -import frc.robot.subsystems.LogitechController; import frc.robot.subsystems.PhotonCameraSystem; import frc.robot.subsystems.ShooterSubsystem; import org.littletonrobotics.urcl.URCL; public class RobotContainer { - private final XboxController controller = new LogitechController(0); + private final XboxController controller = new XboxController(0); private final SendableChooser autoChooser; diff --git a/src/main/java/frc/robot/subsystems/LogitechController.java b/src/main/java/frc/robot/subsystems/LogitechController.java deleted file mode 100644 index 43a55a0..0000000 --- a/src/main/java/frc/robot/subsystems/LogitechController.java +++ /dev/null @@ -1,20 +0,0 @@ -package frc.robot.subsystems; - -import edu.wpi.first.wpilibj.XboxController; - -public class LogitechController extends XboxController { - public LogitechController(int port) { - super(port); - } - - /** - * Get the Y axis value of left side of the controller. - * - * @apiNote inverts axis value - * @return The axis value. - */ - @Override - public double getLeftY() { - return -super.getLeftY(); - } -} diff --git a/src/test/java/subsystem_tests/drive_subsystem_tests/DriveTests.java b/src/test/java/subsystem_tests/drive_subsystem_tests/DriveTests.java deleted file mode 100644 index 9350dce..0000000 --- a/src/test/java/subsystem_tests/drive_subsystem_tests/DriveTests.java +++ /dev/null @@ -1,92 +0,0 @@ -package subsystem_tests.drive_subsystem_tests; - -import static org.junit.jupiter.api.Assertions.assertEquals; - -import edu.wpi.first.math.geometry.Rotation2d; -import frc.robot.Constants.DriveConstants; -import org.junit.jupiter.api.AfterEach; -import org.junit.jupiter.api.BeforeEach; -import org.junit.jupiter.api.Test; -import subsystem_tests.drive_subsystem_tests.utils.DriveTestUtils; - -class DriveTests extends DriveSubsystemTestBase { - @BeforeEach - public void setUp() { - super.setUp(); - } - - @AfterEach - public void tearDown() { - super.tearDown(); - } - - @Test - void testRotation() { - driveSubsystem.drive(0, 0, 0.5, false, false); - - var shouldBe = DriveTestUtils.driveToChassisSpeeds(0, 0, 0.5); - var currentlyIs = DriveTestUtils.getDesiredChassisSpeeds(driveSubsystem); - - DriveTestUtils.checkIfEqual(shouldBe, currentlyIs); - } - - @Test - void testDriveForwardRobotRelative() { - driveSubsystem.drive(0.5, 0, 0, false, false); - - var shouldBe = DriveTestUtils.driveToChassisSpeeds(0.5, 0, 0); - var currentlyIs = DriveTestUtils.getDesiredChassisSpeeds(driveSubsystem); - - DriveTestUtils.checkIfEqual(shouldBe, currentlyIs); - } - - @Test - void testDriveSidewaysRobotRelative() { - driveSubsystem.drive(0, 0.5, 0, false, false); - - var shouldBe = DriveTestUtils.driveToChassisSpeeds(0, 0.5, 0); - var currentlyIs = DriveTestUtils.getDesiredChassisSpeeds(driveSubsystem); - - DriveTestUtils.checkIfEqual(shouldBe, currentlyIs); - } - - @Test - void testRotateRobotRelative() { - driveSubsystem.drive(0, 0, 0.5, false, false); - - var shouldBe = DriveTestUtils.driveToChassisSpeeds(0, 0, 0.5); - var currentlyIs = DriveTestUtils.getDesiredChassisSpeeds(driveSubsystem); - - DriveTestUtils.checkIfEqual(shouldBe, currentlyIs); - } - - @Test - void testDriveForwardFieldRelative() { - driveSubsystem.drive(0.5, 0, 0, true, false); - - for (var state : driveSubsystem.getModuleDesiredStates()) { - assertEquals(DriveConstants.kMaxSpeedMetersPerSecond * 0.5, state.speedMetersPerSecond, 0.01); - assertEquals(Rotation2d.fromDegrees(0), state.angle); - } - } - - @Test - void testDriveSidewaysFieldRelative() { - driveSubsystem.drive(0, 0.5, 0, true, false); - - for (var state : driveSubsystem.getModuleDesiredStates()) { - assertEquals(DriveConstants.kMaxSpeedMetersPerSecond * 0.5, state.speedMetersPerSecond, 0.01); - assertEquals(Rotation2d.fromDegrees(90), state.angle); - } - } - - @Test - void testDriveDiagonalFieldRelative() { - driveSubsystem.drive(1, 1, 0, true, false); - - for (var state : driveSubsystem.getModuleDesiredStates()) { - assertEquals(DriveConstants.kMaxSpeedMetersPerSecond, state.speedMetersPerSecond, 0.01); - assertEquals(Rotation2d.fromDegrees(45), state.angle); - } - } -}