mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[hal,wpilib] Rename "Test" robot mode to "Utility" (#8782)
The "Utility" name better matches its intended generic use case and avoids overloaded terminology with unit testing (e.g. the need to name the opmode annotation `@TestOpMode`). The driver station will also be updated to reflect this change.
This commit is contained in:
@@ -91,23 +91,23 @@ public final class RobotState {
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets a value indicating whether the Driver Station requires the robot to be running in Test
|
||||
* Gets a value indicating whether the Driver Station requires the robot to be running in Utility
|
||||
* mode.
|
||||
*
|
||||
* @return True if test mode should be enabled, false otherwise.
|
||||
* @return True if utility mode should be enabled, false otherwise.
|
||||
*/
|
||||
public static boolean isTest() {
|
||||
return DriverStationBackend.isTest();
|
||||
public static boolean isUtility() {
|
||||
return DriverStationBackend.isUtility();
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets a value indicating whether the Driver Station requires the robot to be running in Test
|
||||
* Gets a value indicating whether the Driver Station requires the robot to be running in Utility
|
||||
* mode and enabled.
|
||||
*
|
||||
* @return True if test mode should be set and the robot should be enabled.
|
||||
* @return True if utility mode should be set and the robot should be enabled.
|
||||
*/
|
||||
public static boolean isTestEnabled() {
|
||||
return DriverStationBackend.isTestEnabled();
|
||||
public static boolean isUtilityEnabled() {
|
||||
return DriverStationBackend.isUtilityEnabled();
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -1167,30 +1167,30 @@ public final class DriverStationBackend {
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets a value indicating whether the Driver Station requires the robot to be running in Test
|
||||
* Gets a value indicating whether the Driver Station requires the robot to be running in Utility
|
||||
* mode.
|
||||
*
|
||||
* @return True if test mode should be enabled, false otherwise.
|
||||
* @return True if utility mode should be enabled, false otherwise.
|
||||
*/
|
||||
public static boolean isTest() {
|
||||
public static boolean isUtility() {
|
||||
m_cacheDataMutex.lock();
|
||||
try {
|
||||
return m_controlWord.isTest();
|
||||
return m_controlWord.isUtility();
|
||||
} finally {
|
||||
m_cacheDataMutex.unlock();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets a value indicating whether the Driver Station requires the robot to be running in Test
|
||||
* Gets a value indicating whether the Driver Station requires the robot to be running in Utility
|
||||
* mode and enabled.
|
||||
*
|
||||
* @return True if test mode should be set and the robot should be enabled.
|
||||
* @return True if utility mode should be set and the robot should be enabled.
|
||||
*/
|
||||
public static boolean isTestEnabled() {
|
||||
public static boolean isUtilityEnabled() {
|
||||
m_cacheDataMutex.lock();
|
||||
try {
|
||||
return m_controlWord.isTestEnabled();
|
||||
return m_controlWord.isUtilityEnabled();
|
||||
} finally {
|
||||
m_cacheDataMutex.unlock();
|
||||
}
|
||||
|
||||
@@ -33,7 +33,7 @@ import org.wpilib.system.Watchdog;
|
||||
* <li>disabledInit() -- called each and every time disabled is entered from another mode
|
||||
* <li>autonomousInit() -- called each and every time autonomous is entered from another mode
|
||||
* <li>teleopInit() -- called each and every time teleop is entered from another mode
|
||||
* <li>testInit() -- called each and every time test is entered from another mode
|
||||
* <li>utilityInit() -- called each and every time utility is entered from another mode
|
||||
* </ul>
|
||||
*
|
||||
* <p>periodic() functions -- each of these functions is called on an interval:
|
||||
@@ -43,7 +43,7 @@ import org.wpilib.system.Watchdog;
|
||||
* <li>disabledPeriodic()
|
||||
* <li>autonomousPeriodic()
|
||||
* <li>teleopPeriodic()
|
||||
* <li>testPeriodic()
|
||||
* <li>utilityPeriodic()
|
||||
* </ul>
|
||||
*
|
||||
* <p>exit() functions -- each of the following functions is called once when the appropriate mode
|
||||
@@ -53,7 +53,7 @@ import org.wpilib.system.Watchdog;
|
||||
* <li>disabledExit() -- called each and every time disabled is exited
|
||||
* <li>autonomousExit() -- called each and every time autonomous is exited
|
||||
* <li>teleopExit() -- called each and every time teleop is exited
|
||||
* <li>testExit() -- called each and every time test is exited
|
||||
* <li>utilityExit() -- called each and every time utility is exited
|
||||
* </ul>
|
||||
*/
|
||||
public abstract class IterativeRobotBase extends RobotBase {
|
||||
@@ -121,12 +121,12 @@ public abstract class IterativeRobotBase extends RobotBase {
|
||||
public void teleopInit() {}
|
||||
|
||||
/**
|
||||
* Initialization code for test mode should go here.
|
||||
* Initialization code for utility mode should go here.
|
||||
*
|
||||
* <p>Users should override this method for initialization code which will be called each time the
|
||||
* robot enters test mode.
|
||||
* robot enters utility mode.
|
||||
*/
|
||||
public void testInit() {}
|
||||
public void utilityInit() {}
|
||||
|
||||
/* ----------- Overridable periodic code ----------------- */
|
||||
|
||||
@@ -186,10 +186,10 @@ public abstract class IterativeRobotBase extends RobotBase {
|
||||
|
||||
private boolean m_tmpFirstRun = true;
|
||||
|
||||
/** Periodic code for test mode should go here. */
|
||||
public void testPeriodic() {
|
||||
/** Periodic code for utility mode should go here. */
|
||||
public void utilityPeriodic() {
|
||||
if (m_tmpFirstRun) {
|
||||
System.out.println("Default testPeriodic() method... Override me!");
|
||||
System.out.println("Default utilityPeriodic() method... Override me!");
|
||||
m_tmpFirstRun = false;
|
||||
}
|
||||
}
|
||||
@@ -219,12 +219,12 @@ public abstract class IterativeRobotBase extends RobotBase {
|
||||
public void teleopExit() {}
|
||||
|
||||
/**
|
||||
* Exit code for test mode should go here.
|
||||
* Exit code for utility mode should go here.
|
||||
*
|
||||
* <p>Users should override this method for code which will be called each time the robot exits
|
||||
* test mode.
|
||||
* utility mode.
|
||||
*/
|
||||
public void testExit() {}
|
||||
public void utilityExit() {}
|
||||
|
||||
/**
|
||||
* Gets time period between calls to Periodic() functions.
|
||||
@@ -258,7 +258,7 @@ public abstract class IterativeRobotBase extends RobotBase {
|
||||
case UNKNOWN -> disabledExit();
|
||||
case AUTONOMOUS -> autonomousExit();
|
||||
case TELEOPERATED -> teleopExit();
|
||||
case TEST -> testExit();
|
||||
case UTILITY -> utilityExit();
|
||||
default -> {
|
||||
// NOP
|
||||
}
|
||||
@@ -279,9 +279,9 @@ public abstract class IterativeRobotBase extends RobotBase {
|
||||
teleopInit();
|
||||
m_watchdog.addEpoch("teleopInit()");
|
||||
}
|
||||
case TEST -> {
|
||||
testInit();
|
||||
m_watchdog.addEpoch("testInit()");
|
||||
case UTILITY -> {
|
||||
utilityInit();
|
||||
m_watchdog.addEpoch("utilityInit()");
|
||||
}
|
||||
default -> {
|
||||
// NOP
|
||||
@@ -306,9 +306,9 @@ public abstract class IterativeRobotBase extends RobotBase {
|
||||
teleopPeriodic();
|
||||
m_watchdog.addEpoch("teleopPeriodic()");
|
||||
}
|
||||
case TEST -> {
|
||||
testPeriodic();
|
||||
m_watchdog.addEpoch("testPeriodic()");
|
||||
case UTILITY -> {
|
||||
utilityPeriodic();
|
||||
m_watchdog.addEpoch("utilityPeriodic()");
|
||||
}
|
||||
default -> {
|
||||
// NOP
|
||||
|
||||
@@ -37,7 +37,7 @@ import org.wpilib.opmode.Autonomous;
|
||||
import org.wpilib.opmode.OpMode;
|
||||
import org.wpilib.opmode.PeriodicOpMode;
|
||||
import org.wpilib.opmode.Teleop;
|
||||
import org.wpilib.opmode.TestOpMode;
|
||||
import org.wpilib.opmode.Utility;
|
||||
import org.wpilib.smartdashboard.SmartDashboard;
|
||||
import org.wpilib.system.RobotController;
|
||||
import org.wpilib.system.Watchdog;
|
||||
@@ -49,9 +49,9 @@ import org.wpilib.util.ConstructorMatch;
|
||||
*
|
||||
* <p>The OpModeRobot class is intended to be subclassed by a user creating a robot program.
|
||||
*
|
||||
* <p>Classes annotated with {@link Autonomous}, {@link Teleop}, and {@link TestOpMode} in the same
|
||||
* <p>Classes annotated with {@link Autonomous}, {@link Teleop}, and {@link Utility} in the same
|
||||
* package or subpackages as the user's subclass are automatically registered as autonomous, teleop,
|
||||
* and test opmodes respectively.
|
||||
* and utility opmodes respectively.
|
||||
*
|
||||
* <p>Opmodes are constructed when selected on the driver station. While selected and disabled,
|
||||
* {@link PeriodicOpMode#disabledPeriodic()} is called. When enabled, {@link PeriodicOpMode#start()}
|
||||
@@ -363,7 +363,7 @@ public abstract class OpModeRobot extends RobotBase {
|
||||
}
|
||||
|
||||
private void addAnnotatedOpModeImpl(
|
||||
Class<? extends OpMode> cls, Autonomous auto, Teleop teleop, TestOpMode test) {
|
||||
Class<? extends OpMode> cls, Autonomous auto, Teleop teleop, Utility utility) {
|
||||
checkOpModeClass(cls);
|
||||
|
||||
// add an opmode for each annotation
|
||||
@@ -387,24 +387,24 @@ public abstract class OpModeRobot extends RobotBase {
|
||||
teleop.textColor(),
|
||||
teleop.backgroundColor());
|
||||
}
|
||||
if (test != null) {
|
||||
if (utility != null) {
|
||||
addOpModeClassImpl(
|
||||
cls,
|
||||
RobotMode.TEST,
|
||||
test.name(),
|
||||
test.group(),
|
||||
test.description(),
|
||||
test.textColor(),
|
||||
test.backgroundColor());
|
||||
RobotMode.UTILITY,
|
||||
utility.name(),
|
||||
utility.group(),
|
||||
utility.description(),
|
||||
utility.textColor(),
|
||||
utility.backgroundColor());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Adds an opmode for an opmode class annotated with {@link Autonomous}, {@link Teleop}, or {@link
|
||||
* TestOpMode}. The class must be a public, non-abstract subclass of OpMode with a public
|
||||
* constructor that either takes no arguments or accepts a single argument assignable from this
|
||||
* robot class type (if multiple match, the most specific parameter type is used). It's necessary
|
||||
* to call publishOpModes() to make the added mode visible to the driver station.
|
||||
* Utility}. The class must be a public, non-abstract subclass of OpMode with a public constructor
|
||||
* that either takes no arguments or accepts a single argument assignable from this robot class
|
||||
* type (if multiple match, the most specific parameter type is used). It's necessary to call
|
||||
* publishOpModes() to make the added mode visible to the driver station.
|
||||
*
|
||||
* @param cls class to add
|
||||
* @throws IllegalArgumentException if class does not meet criteria
|
||||
@@ -412,12 +412,11 @@ public abstract class OpModeRobot extends RobotBase {
|
||||
public void addAnnotatedOpMode(Class<? extends OpMode> cls) {
|
||||
Autonomous auto = cls.getAnnotation(Autonomous.class);
|
||||
Teleop teleop = cls.getAnnotation(Teleop.class);
|
||||
TestOpMode test = cls.getAnnotation(TestOpMode.class);
|
||||
if (auto == null && teleop == null && test == null) {
|
||||
throw new IllegalArgumentException(
|
||||
"must be annotated with Autonomous, Teleop, or TestOpMode");
|
||||
Utility utility = cls.getAnnotation(Utility.class);
|
||||
if (auto == null && teleop == null && utility == null) {
|
||||
throw new IllegalArgumentException("must be annotated with Autonomous, Teleop, or Utility");
|
||||
}
|
||||
addAnnotatedOpModeImpl(cls, auto, teleop, test);
|
||||
addAnnotatedOpModeImpl(cls, auto, teleop, utility);
|
||||
}
|
||||
|
||||
private void addAnnotatedOpModeClass(String name) {
|
||||
@@ -431,12 +430,12 @@ public abstract class OpModeRobot extends RobotBase {
|
||||
}
|
||||
Autonomous auto = cls.getAnnotation(Autonomous.class);
|
||||
Teleop teleop = cls.getAnnotation(Teleop.class);
|
||||
TestOpMode test = cls.getAnnotation(TestOpMode.class);
|
||||
if (auto == null && teleop == null && test == null) {
|
||||
Utility utility = cls.getAnnotation(Utility.class);
|
||||
if (auto == null && teleop == null && utility == null) {
|
||||
return;
|
||||
}
|
||||
try {
|
||||
addAnnotatedOpModeImpl(cls, auto, teleop, test);
|
||||
addAnnotatedOpModeImpl(cls, auto, teleop, utility);
|
||||
} catch (IllegalArgumentException e) {
|
||||
reportAddOpModeError(cls, e.getMessage());
|
||||
}
|
||||
@@ -459,7 +458,7 @@ public abstract class OpModeRobot extends RobotBase {
|
||||
|
||||
/**
|
||||
* Scans for classes in the specified package and all nested packages that are annotated with
|
||||
* {@link Autonomous}, {@link Teleop}, or {@link TestOpMode} and registers them. It's necessary to
|
||||
* {@link Autonomous}, {@link Teleop}, or {@link Utility} and registers them. It's necessary to
|
||||
* call publishOpModes() to make the added modes visible to the driver station.
|
||||
*
|
||||
* @param pkg package to scan
|
||||
|
||||
@@ -217,21 +217,22 @@ public abstract class RobotBase implements AutoCloseable {
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine if the robot is currently in Test mode as determined by the Driver Station.
|
||||
* Determine if the robot is currently in Utility mode as determined by the Driver Station.
|
||||
*
|
||||
* @return True if the robot is currently operating in Test mode.
|
||||
* @return True if the robot is currently operating in Utility mode.
|
||||
*/
|
||||
public static boolean isTest() {
|
||||
return RobotState.isTest();
|
||||
public static boolean isUtility() {
|
||||
return RobotState.isUtility();
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine if the robot is current in Test mode and enabled as determined by the Driver Station.
|
||||
* Determine if the robot is current in Utility mode and enabled as determined by the Driver
|
||||
* Station.
|
||||
*
|
||||
* @return True if the robot is currently operating in Test mode while enabled.
|
||||
* @return True if the robot is currently operating in Utility mode while enabled.
|
||||
*/
|
||||
public static boolean isTestEnabled() {
|
||||
return RobotState.isTestEnabled();
|
||||
public static boolean isUtilityEnabled() {
|
||||
return RobotState.isUtilityEnabled();
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -134,7 +134,7 @@ public abstract class MotorSafety {
|
||||
stopTime = m_stopTime;
|
||||
}
|
||||
|
||||
if (!enabled || RobotState.isDisabled() || RobotState.isTest()) {
|
||||
if (!enabled || RobotState.isDisabled() || RobotState.isUtility()) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
@@ -10,14 +10,14 @@ import java.lang.annotation.Retention;
|
||||
import java.lang.annotation.RetentionPolicy;
|
||||
import java.lang.annotation.Target;
|
||||
|
||||
/** Annotation for automatic registration of test opmode classes. */
|
||||
/** Annotation for automatic registration of utility opmode classes. */
|
||||
@Retention(RetentionPolicy.RUNTIME)
|
||||
@Target(ElementType.TYPE)
|
||||
@Documented
|
||||
public @interface TestOpMode {
|
||||
public @interface Utility {
|
||||
/**
|
||||
* Name. This is shown as the selection name in the Driver Station, and must be unique across all
|
||||
* test opmodes in the project. If not specified, defaults to the name of the class.
|
||||
* utility opmodes in the project. If not specified, defaults to the name of the class.
|
||||
*
|
||||
* @return Name
|
||||
*/
|
||||
@@ -33,6 +33,6 @@ public final class MockHardwareExtension implements BeforeAllCallback {
|
||||
HAL.initialize(500, 0);
|
||||
DriverStationSim.setDsAttached(true);
|
||||
DriverStationSim.setEnabled(true);
|
||||
DriverStationSim.setRobotMode(RobotMode.TEST);
|
||||
DriverStationSim.setRobotMode(RobotMode.UTILITY);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -125,7 +125,7 @@ class OpModeRobotTest {
|
||||
Color.BLACK);
|
||||
addOpModeFactory(
|
||||
() -> new OneArgOpMode(this),
|
||||
RobotMode.TEST,
|
||||
RobotMode.UTILITY,
|
||||
"OneArgOpMode-Test",
|
||||
"Group",
|
||||
"Description",
|
||||
|
||||
@@ -23,19 +23,19 @@ class TimedRobotTest {
|
||||
public final AtomicInteger m_disabledInitCount = new AtomicInteger(0);
|
||||
public final AtomicInteger m_autonomousInitCount = new AtomicInteger(0);
|
||||
public final AtomicInteger m_teleopInitCount = new AtomicInteger(0);
|
||||
public final AtomicInteger m_testInitCount = new AtomicInteger(0);
|
||||
public final AtomicInteger m_utilityInitCount = new AtomicInteger(0);
|
||||
|
||||
public final AtomicInteger m_robotPeriodicCount = new AtomicInteger(0);
|
||||
public final AtomicInteger m_simulationPeriodicCount = new AtomicInteger(0);
|
||||
public final AtomicInteger m_disabledPeriodicCount = new AtomicInteger(0);
|
||||
public final AtomicInteger m_autonomousPeriodicCount = new AtomicInteger(0);
|
||||
public final AtomicInteger m_teleopPeriodicCount = new AtomicInteger(0);
|
||||
public final AtomicInteger m_testPeriodicCount = new AtomicInteger(0);
|
||||
public final AtomicInteger m_utilityPeriodicCount = new AtomicInteger(0);
|
||||
|
||||
public final AtomicInteger m_disabledExitCount = new AtomicInteger(0);
|
||||
public final AtomicInteger m_autonomousExitCount = new AtomicInteger(0);
|
||||
public final AtomicInteger m_teleopExitCount = new AtomicInteger(0);
|
||||
public final AtomicInteger m_testExitCount = new AtomicInteger(0);
|
||||
public final AtomicInteger m_utilityExitCount = new AtomicInteger(0);
|
||||
|
||||
MockRobot() {
|
||||
super(kPeriod);
|
||||
@@ -62,8 +62,8 @@ class TimedRobotTest {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void testInit() {
|
||||
m_testInitCount.addAndGet(1);
|
||||
public void utilityInit() {
|
||||
m_utilityInitCount.addAndGet(1);
|
||||
}
|
||||
|
||||
@Override
|
||||
@@ -92,8 +92,8 @@ class TimedRobotTest {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void testPeriodic() {
|
||||
m_testPeriodicCount.addAndGet(1);
|
||||
public void utilityPeriodic() {
|
||||
m_utilityPeriodicCount.addAndGet(1);
|
||||
}
|
||||
|
||||
@Override
|
||||
@@ -112,8 +112,8 @@ class TimedRobotTest {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void testExit() {
|
||||
m_testExitCount.addAndGet(1);
|
||||
public void utilityExit() {
|
||||
m_utilityExitCount.addAndGet(1);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -145,19 +145,19 @@ class TimedRobotTest {
|
||||
assertEquals(0, robot.m_disabledInitCount.get());
|
||||
assertEquals(0, robot.m_autonomousInitCount.get());
|
||||
assertEquals(0, robot.m_teleopInitCount.get());
|
||||
assertEquals(0, robot.m_testInitCount.get());
|
||||
assertEquals(0, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(0, robot.m_robotPeriodicCount.get());
|
||||
assertEquals(0, robot.m_simulationPeriodicCount.get());
|
||||
assertEquals(0, robot.m_disabledPeriodicCount.get());
|
||||
assertEquals(0, robot.m_autonomousPeriodicCount.get());
|
||||
assertEquals(0, robot.m_teleopPeriodicCount.get());
|
||||
assertEquals(0, robot.m_testPeriodicCount.get());
|
||||
assertEquals(0, robot.m_utilityPeriodicCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
SimHooks.stepTiming(kPeriod);
|
||||
|
||||
@@ -165,19 +165,19 @@ class TimedRobotTest {
|
||||
assertEquals(1, robot.m_disabledInitCount.get());
|
||||
assertEquals(0, robot.m_autonomousInitCount.get());
|
||||
assertEquals(0, robot.m_teleopInitCount.get());
|
||||
assertEquals(0, robot.m_testInitCount.get());
|
||||
assertEquals(0, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(1, robot.m_robotPeriodicCount.get());
|
||||
assertEquals(1, robot.m_simulationPeriodicCount.get());
|
||||
assertEquals(1, robot.m_disabledPeriodicCount.get());
|
||||
assertEquals(0, robot.m_autonomousPeriodicCount.get());
|
||||
assertEquals(0, robot.m_teleopPeriodicCount.get());
|
||||
assertEquals(0, robot.m_testPeriodicCount.get());
|
||||
assertEquals(0, robot.m_utilityPeriodicCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
SimHooks.stepTiming(kPeriod);
|
||||
|
||||
@@ -185,19 +185,19 @@ class TimedRobotTest {
|
||||
assertEquals(1, robot.m_disabledInitCount.get());
|
||||
assertEquals(0, robot.m_autonomousInitCount.get());
|
||||
assertEquals(0, robot.m_teleopInitCount.get());
|
||||
assertEquals(0, robot.m_testInitCount.get());
|
||||
assertEquals(0, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(2, robot.m_robotPeriodicCount.get());
|
||||
assertEquals(2, robot.m_simulationPeriodicCount.get());
|
||||
assertEquals(2, robot.m_disabledPeriodicCount.get());
|
||||
assertEquals(0, robot.m_autonomousPeriodicCount.get());
|
||||
assertEquals(0, robot.m_teleopPeriodicCount.get());
|
||||
assertEquals(0, robot.m_testPeriodicCount.get());
|
||||
assertEquals(0, robot.m_utilityPeriodicCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
robot.endCompetition();
|
||||
try {
|
||||
@@ -226,19 +226,19 @@ class TimedRobotTest {
|
||||
assertEquals(0, robot.m_disabledInitCount.get());
|
||||
assertEquals(0, robot.m_autonomousInitCount.get());
|
||||
assertEquals(0, robot.m_teleopInitCount.get());
|
||||
assertEquals(0, robot.m_testInitCount.get());
|
||||
assertEquals(0, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(0, robot.m_robotPeriodicCount.get());
|
||||
assertEquals(0, robot.m_simulationPeriodicCount.get());
|
||||
assertEquals(0, robot.m_disabledPeriodicCount.get());
|
||||
assertEquals(0, robot.m_autonomousPeriodicCount.get());
|
||||
assertEquals(0, robot.m_teleopPeriodicCount.get());
|
||||
assertEquals(0, robot.m_testPeriodicCount.get());
|
||||
assertEquals(0, robot.m_utilityPeriodicCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
SimHooks.stepTiming(kPeriod);
|
||||
|
||||
@@ -246,19 +246,19 @@ class TimedRobotTest {
|
||||
assertEquals(0, robot.m_disabledInitCount.get());
|
||||
assertEquals(1, robot.m_autonomousInitCount.get());
|
||||
assertEquals(0, robot.m_teleopInitCount.get());
|
||||
assertEquals(0, robot.m_testInitCount.get());
|
||||
assertEquals(0, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(1, robot.m_robotPeriodicCount.get());
|
||||
assertEquals(1, robot.m_simulationPeriodicCount.get());
|
||||
assertEquals(0, robot.m_disabledPeriodicCount.get());
|
||||
assertEquals(1, robot.m_autonomousPeriodicCount.get());
|
||||
assertEquals(0, robot.m_teleopPeriodicCount.get());
|
||||
assertEquals(0, robot.m_testPeriodicCount.get());
|
||||
assertEquals(0, robot.m_utilityPeriodicCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
SimHooks.stepTiming(kPeriod);
|
||||
|
||||
@@ -266,19 +266,19 @@ class TimedRobotTest {
|
||||
assertEquals(0, robot.m_disabledInitCount.get());
|
||||
assertEquals(1, robot.m_autonomousInitCount.get());
|
||||
assertEquals(0, robot.m_teleopInitCount.get());
|
||||
assertEquals(0, robot.m_testInitCount.get());
|
||||
assertEquals(0, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(2, robot.m_robotPeriodicCount.get());
|
||||
assertEquals(2, robot.m_simulationPeriodicCount.get());
|
||||
assertEquals(0, robot.m_disabledPeriodicCount.get());
|
||||
assertEquals(2, robot.m_autonomousPeriodicCount.get());
|
||||
assertEquals(0, robot.m_teleopPeriodicCount.get());
|
||||
assertEquals(0, robot.m_testPeriodicCount.get());
|
||||
assertEquals(0, robot.m_utilityPeriodicCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
robot.endCompetition();
|
||||
try {
|
||||
@@ -307,19 +307,19 @@ class TimedRobotTest {
|
||||
assertEquals(0, robot.m_disabledInitCount.get());
|
||||
assertEquals(0, robot.m_autonomousInitCount.get());
|
||||
assertEquals(0, robot.m_teleopInitCount.get());
|
||||
assertEquals(0, robot.m_testInitCount.get());
|
||||
assertEquals(0, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(0, robot.m_robotPeriodicCount.get());
|
||||
assertEquals(0, robot.m_simulationPeriodicCount.get());
|
||||
assertEquals(0, robot.m_disabledPeriodicCount.get());
|
||||
assertEquals(0, robot.m_autonomousPeriodicCount.get());
|
||||
assertEquals(0, robot.m_teleopPeriodicCount.get());
|
||||
assertEquals(0, robot.m_testPeriodicCount.get());
|
||||
assertEquals(0, robot.m_utilityPeriodicCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
SimHooks.stepTiming(kPeriod);
|
||||
|
||||
@@ -327,19 +327,19 @@ class TimedRobotTest {
|
||||
assertEquals(0, robot.m_disabledInitCount.get());
|
||||
assertEquals(0, robot.m_autonomousInitCount.get());
|
||||
assertEquals(1, robot.m_teleopInitCount.get());
|
||||
assertEquals(0, robot.m_testInitCount.get());
|
||||
assertEquals(0, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(1, robot.m_robotPeriodicCount.get());
|
||||
assertEquals(1, robot.m_simulationPeriodicCount.get());
|
||||
assertEquals(0, robot.m_disabledPeriodicCount.get());
|
||||
assertEquals(0, robot.m_autonomousPeriodicCount.get());
|
||||
assertEquals(1, robot.m_teleopPeriodicCount.get());
|
||||
assertEquals(0, robot.m_testPeriodicCount.get());
|
||||
assertEquals(0, robot.m_utilityPeriodicCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
SimHooks.stepTiming(kPeriod);
|
||||
|
||||
@@ -347,19 +347,19 @@ class TimedRobotTest {
|
||||
assertEquals(0, robot.m_disabledInitCount.get());
|
||||
assertEquals(0, robot.m_autonomousInitCount.get());
|
||||
assertEquals(1, robot.m_teleopInitCount.get());
|
||||
assertEquals(0, robot.m_testInitCount.get());
|
||||
assertEquals(0, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(2, robot.m_robotPeriodicCount.get());
|
||||
assertEquals(2, robot.m_simulationPeriodicCount.get());
|
||||
assertEquals(0, robot.m_disabledPeriodicCount.get());
|
||||
assertEquals(0, robot.m_autonomousPeriodicCount.get());
|
||||
assertEquals(2, robot.m_teleopPeriodicCount.get());
|
||||
assertEquals(0, robot.m_testPeriodicCount.get());
|
||||
assertEquals(0, robot.m_utilityPeriodicCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
robot.endCompetition();
|
||||
try {
|
||||
@@ -373,7 +373,7 @@ class TimedRobotTest {
|
||||
|
||||
@Test
|
||||
@ResourceLock("timing")
|
||||
void testModeTest() {
|
||||
void utilityModeTest() {
|
||||
MockRobot robot = new MockRobot();
|
||||
|
||||
Thread robotThread = new Thread(robot::startCompetition);
|
||||
@@ -381,26 +381,26 @@ class TimedRobotTest {
|
||||
SimHooks.waitForProgramStart();
|
||||
|
||||
DriverStationSim.setEnabled(true);
|
||||
DriverStationSim.setRobotMode(RobotMode.TEST);
|
||||
DriverStationSim.setRobotMode(RobotMode.UTILITY);
|
||||
DriverStationSim.notifyNewData();
|
||||
|
||||
assertEquals(1, robot.m_simulationInitCount.get());
|
||||
assertEquals(0, robot.m_disabledInitCount.get());
|
||||
assertEquals(0, robot.m_autonomousInitCount.get());
|
||||
assertEquals(0, robot.m_teleopInitCount.get());
|
||||
assertEquals(0, robot.m_testInitCount.get());
|
||||
assertEquals(0, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(0, robot.m_robotPeriodicCount.get());
|
||||
assertEquals(0, robot.m_simulationPeriodicCount.get());
|
||||
assertEquals(0, robot.m_disabledPeriodicCount.get());
|
||||
assertEquals(0, robot.m_autonomousPeriodicCount.get());
|
||||
assertEquals(0, robot.m_teleopPeriodicCount.get());
|
||||
assertEquals(0, robot.m_testPeriodicCount.get());
|
||||
assertEquals(0, robot.m_utilityPeriodicCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
SimHooks.stepTiming(kPeriod);
|
||||
|
||||
@@ -408,19 +408,19 @@ class TimedRobotTest {
|
||||
assertEquals(0, robot.m_disabledInitCount.get());
|
||||
assertEquals(0, robot.m_autonomousInitCount.get());
|
||||
assertEquals(0, robot.m_teleopInitCount.get());
|
||||
assertEquals(1, robot.m_testInitCount.get());
|
||||
assertEquals(1, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(1, robot.m_robotPeriodicCount.get());
|
||||
assertEquals(1, robot.m_simulationPeriodicCount.get());
|
||||
assertEquals(0, robot.m_disabledPeriodicCount.get());
|
||||
assertEquals(0, robot.m_autonomousPeriodicCount.get());
|
||||
assertEquals(0, robot.m_teleopPeriodicCount.get());
|
||||
assertEquals(1, robot.m_testPeriodicCount.get());
|
||||
assertEquals(1, robot.m_utilityPeriodicCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
SimHooks.stepTiming(kPeriod);
|
||||
|
||||
@@ -428,19 +428,19 @@ class TimedRobotTest {
|
||||
assertEquals(0, robot.m_disabledInitCount.get());
|
||||
assertEquals(0, robot.m_autonomousInitCount.get());
|
||||
assertEquals(0, robot.m_teleopInitCount.get());
|
||||
assertEquals(1, robot.m_testInitCount.get());
|
||||
assertEquals(1, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(2, robot.m_robotPeriodicCount.get());
|
||||
assertEquals(2, robot.m_simulationPeriodicCount.get());
|
||||
assertEquals(0, robot.m_disabledPeriodicCount.get());
|
||||
assertEquals(0, robot.m_autonomousPeriodicCount.get());
|
||||
assertEquals(0, robot.m_teleopPeriodicCount.get());
|
||||
assertEquals(2, robot.m_testPeriodicCount.get());
|
||||
assertEquals(2, robot.m_utilityPeriodicCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
DriverStationSim.setEnabled(false);
|
||||
DriverStationSim.notifyNewData();
|
||||
@@ -451,19 +451,19 @@ class TimedRobotTest {
|
||||
assertEquals(1, robot.m_disabledInitCount.get());
|
||||
assertEquals(0, robot.m_autonomousInitCount.get());
|
||||
assertEquals(0, robot.m_teleopInitCount.get());
|
||||
assertEquals(1, robot.m_testInitCount.get());
|
||||
assertEquals(1, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(3, robot.m_robotPeriodicCount.get());
|
||||
assertEquals(3, robot.m_simulationPeriodicCount.get());
|
||||
assertEquals(1, robot.m_disabledPeriodicCount.get());
|
||||
assertEquals(0, robot.m_autonomousPeriodicCount.get());
|
||||
assertEquals(0, robot.m_teleopPeriodicCount.get());
|
||||
assertEquals(2, robot.m_testPeriodicCount.get());
|
||||
assertEquals(2, robot.m_utilityPeriodicCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(1, robot.m_testExitCount.get());
|
||||
assertEquals(1, robot.m_utilityExitCount.get());
|
||||
|
||||
robot.endCompetition();
|
||||
try {
|
||||
@@ -491,24 +491,24 @@ class TimedRobotTest {
|
||||
assertEquals(0, robot.m_disabledInitCount.get());
|
||||
assertEquals(0, robot.m_autonomousInitCount.get());
|
||||
assertEquals(0, robot.m_teleopInitCount.get());
|
||||
assertEquals(0, robot.m_testInitCount.get());
|
||||
assertEquals(0, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
SimHooks.stepTiming(kPeriod);
|
||||
|
||||
assertEquals(1, robot.m_disabledInitCount.get());
|
||||
assertEquals(0, robot.m_autonomousInitCount.get());
|
||||
assertEquals(0, robot.m_teleopInitCount.get());
|
||||
assertEquals(0, robot.m_testInitCount.get());
|
||||
assertEquals(0, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(0, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
// Transition to autonomous
|
||||
DriverStationSim.setEnabled(true);
|
||||
@@ -520,12 +520,12 @@ class TimedRobotTest {
|
||||
assertEquals(1, robot.m_disabledInitCount.get());
|
||||
assertEquals(1, robot.m_autonomousInitCount.get());
|
||||
assertEquals(0, robot.m_teleopInitCount.get());
|
||||
assertEquals(0, robot.m_testInitCount.get());
|
||||
assertEquals(0, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(1, robot.m_disabledExitCount.get());
|
||||
assertEquals(0, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
// Transition to teleop
|
||||
DriverStationSim.setEnabled(true);
|
||||
@@ -537,16 +537,16 @@ class TimedRobotTest {
|
||||
assertEquals(1, robot.m_disabledInitCount.get());
|
||||
assertEquals(1, robot.m_autonomousInitCount.get());
|
||||
assertEquals(1, robot.m_teleopInitCount.get());
|
||||
assertEquals(0, robot.m_testInitCount.get());
|
||||
assertEquals(0, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(1, robot.m_disabledExitCount.get());
|
||||
assertEquals(1, robot.m_autonomousExitCount.get());
|
||||
assertEquals(0, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
// Transition to test
|
||||
// Transition to utility
|
||||
DriverStationSim.setEnabled(true);
|
||||
DriverStationSim.setRobotMode(RobotMode.TEST);
|
||||
DriverStationSim.setRobotMode(RobotMode.UTILITY);
|
||||
DriverStationSim.notifyNewData();
|
||||
|
||||
SimHooks.stepTiming(kPeriod);
|
||||
@@ -554,12 +554,12 @@ class TimedRobotTest {
|
||||
assertEquals(1, robot.m_disabledInitCount.get());
|
||||
assertEquals(1, robot.m_autonomousInitCount.get());
|
||||
assertEquals(1, robot.m_teleopInitCount.get());
|
||||
assertEquals(1, robot.m_testInitCount.get());
|
||||
assertEquals(1, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(1, robot.m_disabledExitCount.get());
|
||||
assertEquals(1, robot.m_autonomousExitCount.get());
|
||||
assertEquals(1, robot.m_teleopExitCount.get());
|
||||
assertEquals(0, robot.m_testExitCount.get());
|
||||
assertEquals(0, robot.m_utilityExitCount.get());
|
||||
|
||||
// Transition to disabled
|
||||
DriverStationSim.setEnabled(false);
|
||||
@@ -570,12 +570,12 @@ class TimedRobotTest {
|
||||
assertEquals(2, robot.m_disabledInitCount.get());
|
||||
assertEquals(1, robot.m_autonomousInitCount.get());
|
||||
assertEquals(1, robot.m_teleopInitCount.get());
|
||||
assertEquals(1, robot.m_testInitCount.get());
|
||||
assertEquals(1, robot.m_utilityInitCount.get());
|
||||
|
||||
assertEquals(1, robot.m_disabledExitCount.get());
|
||||
assertEquals(1, robot.m_autonomousExitCount.get());
|
||||
assertEquals(1, robot.m_teleopExitCount.get());
|
||||
assertEquals(1, robot.m_testExitCount.get());
|
||||
assertEquals(1, robot.m_utilityExitCount.get());
|
||||
|
||||
robot.endCompetition();
|
||||
try {
|
||||
|
||||
@@ -64,16 +64,16 @@ class DriverStationSimTest {
|
||||
HAL.initialize(500, 0);
|
||||
DriverStationSim.resetData();
|
||||
|
||||
assertFalse(RobotState.isTest());
|
||||
assertFalse(RobotState.isUtility());
|
||||
EnumCallback callback = new EnumCallback();
|
||||
try (CallbackStore cb = DriverStationSim.registerRobotModeCallback(callback, false)) {
|
||||
DriverStationSim.setRobotMode(RobotMode.TEST);
|
||||
DriverStationSim.setRobotMode(RobotMode.UTILITY);
|
||||
DriverStationSim.notifyNewData();
|
||||
assertEquals(RobotMode.TEST, DriverStationSim.getRobotMode());
|
||||
assertTrue(RobotState.isTest());
|
||||
assertEquals(RobotMode.TEST, RobotState.getRobotMode());
|
||||
assertEquals(RobotMode.UTILITY, DriverStationSim.getRobotMode());
|
||||
assertTrue(RobotState.isUtility());
|
||||
assertEquals(RobotMode.UTILITY, RobotState.getRobotMode());
|
||||
assertTrue(callback.wasTriggered());
|
||||
assertEquals(RobotMode.TEST.getValue(), callback.getSetValue());
|
||||
assertEquals(RobotMode.UTILITY.getValue(), callback.getSetValue());
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user