From 4a600fdca86f51914f0d1d481e904a3e0164480c Mon Sep 17 00:00:00 2001 From: Kaya <95276965+kytpbs@users.noreply.github.com> Date: Sat, 2 Nov 2024 23:28:24 +0300 Subject: [PATCH] Fixed the tests by now simulating input from correct input We simulate the input from the logitech controller (all xInput controllers more exactly) since the Command expects this input instead (Added extra comments that explain that) --- .../frc/robot/commands/DriveCommands.java | 11 ++++++++ .../drive_tests/DefaultDriveCommandTest.java | 25 +++++++++---------- 2 files changed, 23 insertions(+), 13 deletions(-) diff --git a/src/main/java/frc/robot/commands/DriveCommands.java b/src/main/java/frc/robot/commands/DriveCommands.java index c492adc..2af3d81 100644 --- a/src/main/java/frc/robot/commands/DriveCommands.java +++ b/src/main/java/frc/robot/commands/DriveCommands.java @@ -9,6 +9,17 @@ import frc.robot.subsystems.DriveSubsystem; public class DriveCommands { + /** + * A command that handles all boost and deadband calculations for the drive command. It also + * handles the inversion of the controller, so be careful when using this command. + * + *

Warning: This command meant to be used with the Logitech controller only. + * Xbox/playstation controllers won't work due to forward and backward being inverted. + * + * @param driveSubsystem DriveSubsystem + * @param controller Logitech controller + * @return The command to drive the robot with the Logitech controller + */ public static Command driveWithController( DriveSubsystem driveSubsystem, XboxController controller) { return driveSubsystem.drive( diff --git a/src/test/java/command_tests/drive_tests/DefaultDriveCommandTest.java b/src/test/java/command_tests/drive_tests/DefaultDriveCommandTest.java index 53c4f04..5927361 100644 --- a/src/test/java/command_tests/drive_tests/DefaultDriveCommandTest.java +++ b/src/test/java/command_tests/drive_tests/DefaultDriveCommandTest.java @@ -7,7 +7,6 @@ import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.XboxController; -import edu.wpi.first.wpilibj.simulation.DriverStationSim; import edu.wpi.first.wpilibj.simulation.SimHooks; import edu.wpi.first.wpilibj.simulation.XboxControllerSim; import edu.wpi.first.wpilibj2.command.Command; @@ -38,9 +37,9 @@ public void setUp() { @AfterEach public void tearDown() { - driveSubsystem.close(); - resetController(); super.tearDown(); + resetController(); + driveSubsystem.close(); } /** Sets all axis to 0 */ @@ -56,9 +55,9 @@ void testDefaultDriveCommandForward() { assertTrue(commandScheduler.isScheduled(defaultDriveCommand)); - controllerSim.setLeftY(1); - DriverStationSim.notifyNewData(); - assertEquals(1, controller.getLeftY(), 0.001); + controllerSim.setLeftY(-1); // -1 because +y is inverted in the logitech controller + controllerSim.notifyNewData(); + assertEquals(-1, controller.getLeftY(), 0.001, "Signal notify broke, check controllerSim"); commandScheduler.run(); SimHooks.stepTiming(2); // ! This is for the rate limiter not to kick in commandScheduler.run(); @@ -80,8 +79,8 @@ void testDefaultDriveCommandSideways() { assertTrue(commandScheduler.isScheduled(defaultDriveCommand)); controllerSim.setLeftX(1); - DriverStationSim.notifyNewData(); - assertEquals(1, controller.getLeftX(), 0.001); + controllerSim.notifyNewData(); + assertEquals(1, controller.getLeftX(), 0.001, "Signal notify broke, check controllerSim"); commandScheduler.run(); SimHooks.stepTiming(2); // ! This is for the rate limiter not to kick in commandScheduler.run(); @@ -103,10 +102,10 @@ void testDefaultDriveCommandBoost() { assertTrue(commandScheduler.isScheduled(defaultDriveCommand)); - controllerSim.setLeftY(1); + controllerSim.setLeftY(-1); // -1 because +y is inverted in the logitech controller controllerSim.setRightTriggerAxis(1); - DriverStationSim.notifyNewData(); - assertEquals(1, controller.getLeftY(), 0.001); + controllerSim.notifyNewData(); + assertEquals(-1, controller.getLeftY(), 0.001, "Signal notify broke, check controllerSim"); commandScheduler.run(); SimHooks.stepTiming(2); // ! This is for the rate limiter not to kick in commandScheduler.run(); @@ -126,8 +125,8 @@ void testDefaultDriveCommandRotate() { controllerSim.setRightX(1); controllerSim.setRightTriggerAxis(0); - DriverStationSim.notifyNewData(); - assertEquals(1, controller.getRightX(), 0.001); + controllerSim.notifyNewData(); + assertEquals(1, controller.getRightX(), 0.001, "Signal notify broke, check controllerSim"); commandScheduler.run(); SimHooks.stepTiming(2); // ! This is for the rate limiter not to kick in commandScheduler.run();