-
Notifications
You must be signed in to change notification settings - Fork 2
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
1 changed file
with
62 additions
and
0 deletions.
There are no files selected for viewing
62 changes: 62 additions & 0 deletions
62
src/test/java/subsystem_tests/drive_subsystem_tests/DriveWithGyroTests.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,62 @@ | ||
package subsystem_tests.drive_subsystem_tests; | ||
|
||
import static org.junit.jupiter.api.Assertions.assertEquals; | ||
|
||
import edu.wpi.first.hal.simulation.SimDeviceDataJNI; | ||
import edu.wpi.first.math.geometry.Rotation2d; | ||
import edu.wpi.first.wpilibj.Timer; | ||
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.NavXSim; | ||
|
||
class DriveWithGyroTests extends DriveSubsystemTestBase { | ||
|
||
@BeforeEach | ||
public void setUp() { | ||
super.setUp(); | ||
} | ||
|
||
@AfterEach | ||
public void tearDown() { | ||
super.tearDown(); | ||
} | ||
|
||
@Test | ||
void printAllSimNames() { | ||
for (int i = 1; i <= 16; i++) { | ||
var deviceName = SimDeviceDataJNI.getSimDeviceName(i); | ||
System.out.println(deviceName); | ||
} | ||
} | ||
|
||
@Test | ||
void testDriveForwardWithAngleFieldRelative() { | ||
Timer.delay(0.02); // let the navX thread update | ||
NavXSim.setConnected(true); | ||
NavXSim.setAngle(90); | ||
Timer.delay(0.1); // wait 20ms for the navX Thread to update | ||
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(90), state.angle); | ||
} | ||
} | ||
|
||
@Test | ||
void testDriveSidewaysWithAngleFieldRelative() { | ||
Timer.delay(0.02); // wait 20ms for the navX Thread to update | ||
NavXSim.setConnected(true); | ||
NavXSim.setAngle(45); | ||
Timer.delay(0.1); // wait 20ms for the navX Thread to update | ||
driveSubsystem.drive(0, 0.5, 0, true, false); | ||
|
||
for (var state : driveSubsystem.getModuleDesiredStates()) { | ||
assertEquals(DriveConstants.kMaxSpeedMetersPerSecond * 0.5, state.speedMetersPerSecond, 0.01); | ||
// 90 + 45 degrees | ||
assertEquals(Rotation2d.fromDegrees(90 + 45), state.angle); | ||
} | ||
} | ||
} |