Skip to content

Commit

Permalink
Fix unit tests
Browse files Browse the repository at this point in the history
  • Loading branch information
viggy96 committed Jan 14, 2024
1 parent 0883828 commit 8dd5753
Showing 1 changed file with 8 additions and 8 deletions.
16 changes: 8 additions & 8 deletions src/test/java/frc/robot/subsystems/DriveSubsystemTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -368,14 +368,14 @@ public void tractionControl() {
m_driveSubsystem.driveCommand(() -> +1.0, () -> 0.0, () -> 0.0).execute();

// Verify that motors are being driven with expected values
verify(m_lFrontDriveMotor, times(1)).set(AdditionalMatchers.eq(+0.28, DELTA), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_lFrontRotateMotor, times(1)).set(AdditionalMatchers.eq(+Math.PI / 2, DELTA), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_rFrontDriveMotor, times(1)).set(AdditionalMatchers.eq(-0.28, DELTA), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_rFrontRotateMotor, times(1)).set(AdditionalMatchers.eq(0.0, DELTA), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_lRearDriveMotor, times(1)).set(AdditionalMatchers.eq(+0.28, DELTA), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_lRearRotateMotor, times(1)).set(AdditionalMatchers.eq(0.0, DELTA), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_rRearDriveMotor, times(1)).set(AdditionalMatchers.eq(-0.28, DELTA), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_rRearRotateMotor, times(1)).set(AdditionalMatchers.eq(+Math.PI / 2, DELTA), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_lFrontDriveMotor, times(1)).set(AdditionalMatchers.eq(0.0, DELTA), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_lFrontRotateMotor, times(1)).set(AdditionalMatchers.eq(+Math.PI / 4, DELTA), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_rFrontDriveMotor, times(1)).set(AdditionalMatchers.eq(0.0, DELTA), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_rFrontRotateMotor, times(1)).set(AdditionalMatchers.eq(+Math.PI / 4, DELTA), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_lRearDriveMotor, times(1)).set(AdditionalMatchers.eq(0.0, DELTA), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_lRearRotateMotor, times(1)).set(AdditionalMatchers.eq(+Math.PI / 4, DELTA), ArgumentMatchers.eq(ControlType.kPosition));
verify(m_rRearDriveMotor, times(1)).set(AdditionalMatchers.eq(0.0, DELTA), ArgumentMatchers.eq(ControlType.kVelocity));
verify(m_rRearRotateMotor, times(1)).set(AdditionalMatchers.eq(+Math.PI / 4, DELTA), ArgumentMatchers.eq(ControlType.kPosition));
}

@Test
Expand Down

0 comments on commit 8dd5753

Please sign in to comment.