Skip to content

Commit

Permalink
Fix unit tests
Browse files Browse the repository at this point in the history
  • Loading branch information
viggy96 committed Aug 2, 2024
1 parent edb1b2a commit 65dd13e
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 8 deletions.
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -57,10 +57,12 @@ public class RobotContainer {
DRIVE_SUBSYSTEM::getPose,
() -> speakerSupplier()
);

private static final IntakeSubsystem INTAKE_SUBSYSTEM = new IntakeSubsystem(
IntakeSubsystem.initializeHardware(),
Constants.Intake.ROLLER_VELOCITY
);

private static final VisionSubsystem VISION_SUBSYSTEM = VisionSubsystem.getInstance();

private static final CommandXboxController PRIMARY_CONTROLLER = new CommandXboxController(Constants.HID.PRIMARY_CONTROLLER_PORT);
Expand Down
9 changes: 5 additions & 4 deletions src/test/java/frc/robot/commands/AntiTipCommandTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
import edu.wpi.first.wpilibj.simulation.DriverStationSim;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.AbsoluteValueMatcher;
import frc.robot.AngleMatcher;
import frc.robot.Constants;
import frc.robot.subsystems.drive.DriveSubsystem;

Expand Down Expand Up @@ -232,13 +233,13 @@ public void execute() {

// Verify motors are being driven with expected values
verify(m_lFrontDriveMotor, times(1)).set(doubleThat(m_matchLinearVelocity), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_lFrontRotateMotor, times(1)).set(doubleThat(new AbsoluteValueMatcher(Math.PI, DELTA)), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_lFrontRotateMotor, times(1)).set(doubleThat(new AngleMatcher(AngleMatcher.Units.RADIANS, Math.PI, DELTA)), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_rFrontDriveMotor, times(1)).set(doubleThat(m_matchLinearVelocity), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_rFrontRotateMotor, times(1)).set(doubleThat(new AbsoluteValueMatcher(Math.PI / 2, DELTA)), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_rFrontRotateMotor, times(1)).set(doubleThat(new AngleMatcher(AngleMatcher.Units.RADIANS, Math.PI / 2, DELTA)), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_lRearDriveMotor, times(1)).set(doubleThat(m_matchLinearVelocity), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_lRearRotateMotor, times(1)).set(doubleThat(new AbsoluteValueMatcher(Math.PI / 2, DELTA)), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_lRearRotateMotor, times(1)).set(doubleThat(new AngleMatcher(AngleMatcher.Units.RADIANS, Math.PI / 2, DELTA)), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_rRearDriveMotor, times(1)).set(doubleThat(m_matchLinearVelocity), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_rRearRotateMotor, times(1)).set(doubleThat(new AbsoluteValueMatcher(0.0, DELTA)), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_rRearRotateMotor, times(1)).set(doubleThat(new AngleMatcher(AngleMatcher.Units.RADIANS, 0.0, DELTA)), ArgumentMatchers.eq(ControlType.kPosition));
}

@Test
Expand Down
8 changes: 4 additions & 4 deletions src/test/java/frc/robot/subsystems/DriveSubsystemTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -452,13 +452,13 @@ public void tractionControl() {

// Verify that motors are being driven with expected values
verify(m_lFrontDriveMotor, times(1)).set(AdditionalMatchers.lt(m_driveSubsystem.DRIVE_MAX_LINEAR_SPEED.in(Units.MetersPerSecond) / 2), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_lFrontRotateMotor, times(1)).set(AdditionalMatchers.eq(+Math.PI / 2, DELTA), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_lFrontRotateMotor, times(1)).set(doubleThat(new AngleMatcher(AngleMatcher.Units.RADIANS, Math.PI / 2, DELTA)), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_rFrontDriveMotor, times(1)).set(AdditionalMatchers.lt(m_driveSubsystem.DRIVE_MAX_LINEAR_SPEED.in(Units.MetersPerSecond) / 2), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_rFrontRotateMotor, times(1)).set(AdditionalMatchers.eq(0.0, DELTA), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_rFrontRotateMotor, times(1)).set(doubleThat(new AngleMatcher(AngleMatcher.Units.RADIANS, 0.0, DELTA)), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_lRearDriveMotor, times(1)).set(AdditionalMatchers.lt(m_driveSubsystem.DRIVE_MAX_LINEAR_SPEED.in(Units.MetersPerSecond) / 2), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_lRearRotateMotor, times(1)).set(AdditionalMatchers.eq(0.0, DELTA), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_lRearRotateMotor, times(1)).set(doubleThat(new AngleMatcher(AngleMatcher.Units.RADIANS, 0.0, DELTA)), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_rRearDriveMotor, times(1)).set(AdditionalMatchers.lt(m_driveSubsystem.DRIVE_MAX_LINEAR_SPEED.in(Units.MetersPerSecond) / 2), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_rRearRotateMotor, times(1)).set(AdditionalMatchers.eq(+Math.PI / 2, DELTA), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_rRearRotateMotor, times(1)).set(doubleThat(new AngleMatcher(AngleMatcher.Units.RADIANS, Math.PI / 2, DELTA)), ArgumentMatchers.eq(ControlType.kPosition));
}

@Test
Expand Down

0 comments on commit 65dd13e

Please sign in to comment.