mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[examples] Add unit testing infrastructure (#4646)
This commit is contained in:
@@ -0,0 +1,70 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.unittest.subsystems;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.examples.unittest.Constants.IntakeConstants;
|
||||
import edu.wpi.first.wpilibj.simulation.DoubleSolenoidSim;
|
||||
import edu.wpi.first.wpilibj.simulation.PWMSim;
|
||||
import org.junit.jupiter.api.AfterEach;
|
||||
import org.junit.jupiter.api.BeforeEach;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class IntakeTest {
|
||||
static final double DELTA = 1e-2; // acceptable deviation range
|
||||
Intake m_intake;
|
||||
PWMSim m_simMotor;
|
||||
DoubleSolenoidSim m_simPiston;
|
||||
|
||||
@BeforeEach // this method will run before each test
|
||||
void setup() {
|
||||
assert HAL.initialize(500, 0); // initialize the HAL, crash if failed
|
||||
m_intake = new Intake(); // create our intake
|
||||
m_simMotor =
|
||||
new PWMSim(IntakeConstants.kMotorPort); // create our simulation PWM motor controller
|
||||
m_simPiston =
|
||||
new DoubleSolenoidSim(
|
||||
PneumaticsModuleType.CTREPCM,
|
||||
IntakeConstants.kPistonFwdChannel,
|
||||
IntakeConstants.kPistonRevChannel); // create our simulation solenoid
|
||||
}
|
||||
|
||||
@SuppressWarnings("PMD.SignatureDeclareThrowsException")
|
||||
@AfterEach // this method will run after each test
|
||||
void shutdown() throws Exception {
|
||||
m_intake.close(); // destroy our intake object
|
||||
}
|
||||
|
||||
@Test // marks this method as a test
|
||||
void doesntWorkWhenClosed() {
|
||||
m_intake.retract(); // close the intake
|
||||
m_intake.activate(0.5); // try to activate the motor
|
||||
assertEquals(
|
||||
0.0, m_simMotor.getSpeed(), DELTA); // make sure that the value set to the motor is 0
|
||||
}
|
||||
|
||||
@Test
|
||||
void worksWhenOpen() {
|
||||
m_intake.deploy();
|
||||
m_intake.activate(0.5);
|
||||
assertEquals(0.5, m_simMotor.getSpeed(), DELTA);
|
||||
}
|
||||
|
||||
@Test
|
||||
void retractTest() {
|
||||
m_intake.retract();
|
||||
assertEquals(DoubleSolenoid.Value.kReverse, m_simPiston.get());
|
||||
}
|
||||
|
||||
@Test
|
||||
void deployTest() {
|
||||
m_intake.deploy();
|
||||
assertEquals(DoubleSolenoid.Value.kForward, m_simPiston.get());
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user