From ab00aac960d05678337f4346600de61134211d8c Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Mon, 20 Apr 2026 20:29:25 -0700 Subject: [PATCH] [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. --- .../command2/button/RobotModeTriggers.java | 8 +- .../frc2/command/button/RobotModeTriggers.cpp | 4 +- .../commands2/button/RobotModeTriggers.hpp | 6 +- .../org/wpilib/MockHardwareExtension.java | 2 +- .../button/RobotModeTriggersTest.java | 6 +- .../command/button/RobotModeTriggersTest.cpp | 6 +- .../command3/button/RobotModeTriggers.java | 8 +- .../src/main/java/wpilib/robot/Robot.java | 4 +- developerRobot/src/main/native/cpp/Robot.cpp | 2 +- .../org/wpilib/hardware/hal/ControlWord.java | 16 +-- .../org/wpilib/hardware/hal/RobotMode.java | 6 +- .../hal/struct/ControlWordStruct.java | 2 +- hal/src/main/native/cpp/DashboardOpMode.cpp | 12 +- .../include/wpi/hal/DriverStationTypes.h | 2 +- .../include/wpi/hal/DriverStationTypes.hpp | 20 +-- .../python/semiwrap/DriverStationTypes.yml | 4 +- .../DriveDistanceOffboard/robot.py | 4 +- robotpyExamples/GettingStarted/robot.py | 8 +- robotpyExamples/HatchbotInlined/robot.py | 4 +- robotpyExamples/HatchbotTraditional/robot.py | 4 +- robotpyExamples/RapidReactCommandBot/robot.py | 8 +- robotpyExamples/RomiReference/robot.py | 4 +- robotpyExamples/SelectCommand/robot.py | 4 +- robotpyExamples/SysId/robot.py | 8 +- robotpyExamples/XrpReference/robot.py | 4 +- .../src/main/native/cpp/DSCommPacket.cpp | 2 +- .../src/main/native/cpp/DriverStationGui.cpp | 22 +-- .../cpp/framework/IterativeRobotBase.cpp | 22 +-- .../native/cpp/hardware/motor/MotorSafety.cpp | 2 +- wpilibc/src/main/native/cppcs/RobotBase.cpp | 8 +- .../include/wpi/driverstation/RobotState.hpp | 16 ++- .../internal/DriverStationBackend.hpp | 12 +- .../wpi/framework/IterativeRobotBase.hpp | 26 ++-- .../include/wpi/framework/OpModeRobot.hpp | 3 - .../include/wpi/framework/RobotBase.hpp | 14 +- .../python/semiwrap/DriverStationBackend.yml | 4 +- .../python/semiwrap/IterativeRobotBase.yml | 12 +- .../src/main/python/semiwrap/RobotBase.yml | 4 +- .../src/main/python/semiwrap/RobotState.yml | 4 +- .../src/test/native/cpp/OpModeRobotTest.cpp | 2 +- .../src/test/native/cpp/TimedRobotTest.cpp | 10 +- .../cpp/simulation/DriverStationSimTest.cpp | 12 +- wpilibc/src/test/python/test_opmode_robot.py | 4 +- .../DriveDistanceOffboard/cpp/Robot.cpp | 6 +- .../DriveDistanceOffboard/include/Robot.hpp | 2 +- .../cpp/examples/GettingStarted/cpp/Robot.cpp | 4 +- .../src/main/cpp/examples/HAL/c/Robot.c | 6 +- .../examples/HatchbotInlined/cpp/Robot.cpp | 6 +- .../HatchbotInlined/include/Robot.hpp | 2 +- .../HatchbotTraditional/cpp/Robot.cpp | 6 +- .../HatchbotTraditional/include/Robot.hpp | 2 +- .../RapidReactCommandBot/cpp/Robot.cpp | 6 +- .../RapidReactCommandBot/include/Robot.hpp | 4 +- .../cpp/examples/RomiReference/cpp/Robot.cpp | 6 +- .../examples/RomiReference/include/Robot.hpp | 2 +- .../cpp/examples/SysIdRoutine/cpp/Robot.cpp | 6 +- .../examples/SysIdRoutine/include/Robot.hpp | 6 +- .../cpp/examples/XRPReference/cpp/Robot.cpp | 6 +- .../examples/XRPReference/include/Robot.hpp | 2 +- .../main/cpp/examples/Xrptimed/cpp/Robot.cpp | 2 +- .../cpp/snippets/SelectCommand/cpp/Robot.cpp | 4 +- .../snippets/SelectCommand/include/Robot.hpp | 2 +- .../cpp/templates/commandv2/cpp/Robot.cpp | 6 +- .../cpp/templates/commandv2/include/Robot.hpp | 2 +- .../templates/commandv2skeleton/cpp/Robot.cpp | 6 +- .../commandv2skeleton/include/Robot.hpp | 6 +- .../templates/robotbaseskeleton/cpp/Robot.cpp | 10 +- .../robotbaseskeleton/include/Robot.hpp | 2 +- .../main/cpp/templates/timed/cpp/Robot.cpp | 6 +- .../cpp/templates/timed/include/Robot.hpp | 4 +- .../cpp/templates/timedskeleton/cpp/Robot.cpp | 4 +- .../templates/timedskeleton/include/Robot.hpp | 4 +- .../cpp/templates/timeslice/cpp/Robot.cpp | 4 +- .../cpp/templates/timeslice/include/Robot.hpp | 4 +- .../templates/timesliceskeleton/cpp/Robot.cpp | 4 +- .../timesliceskeleton/include/Robot.hpp | 4 +- .../org/wpilib/driverstation/RobotState.java | 16 +-- .../internal/DriverStationBackend.java | 16 +-- .../wpilib/framework/IterativeRobotBase.java | 38 +++--- .../org/wpilib/framework/OpModeRobot.java | 47 ++++--- .../java/org/wpilib/framework/RobotBase.java | 17 +-- .../wpilib/hardware/motor/MotorSafety.java | 2 +- .../opmode/{TestOpMode.java => Utility.java} | 6 +- .../org/wpilib/MockHardwareExtension.java | 2 +- .../org/wpilib/framework/OpModeRobotTest.java | 2 +- .../org/wpilib/framework/TimedRobotTest.java | 128 +++++++++--------- .../simulation/DriverStationSimTest.java | 12 +- .../examples/drivedistanceoffboard/Robot.java | 8 +- .../wpilib/examples/gettingstarted/Robot.java | 8 +- .../examples/hatchbotinlined/Robot.java | 8 +- .../examples/hatchbottraditional/Robot.java | 10 +- .../examples/rapidreactcommandbot/Robot.java | 8 +- .../wpilib/examples/romireference/Robot.java | 8 +- .../wpilib/examples/sysidroutine/Robot.java | 8 +- .../wpilib/examples/xrpreference/Robot.java | 8 +- .../org/wpilib/examples/xrptimed/Robot.java | 8 +- .../wpilib/snippets/selectcommand/Robot.java | 10 +- .../org/wpilib/templates/commandv2/Robot.java | 10 +- .../templates/commandv2skeleton/Robot.java | 6 +- .../educational/EducationalRobot.java | 10 +- .../templates/robotbaseskeleton/Robot.java | 10 +- .../wpilib/templates/romicommandv2/Robot.java | 10 +- .../romieducational/EducationalRobot.java | 10 +- .../org/wpilib/templates/romitimed/Robot.java | 10 +- .../org/wpilib/templates/timed/Robot.java | 10 +- .../wpilib/templates/timedskeleton/Robot.java | 4 +- .../org/wpilib/templates/timeslice/Robot.java | 10 +- .../templates/timesliceskeleton/Robot.java | 4 +- .../wpilib/templates/xrpcommandv2/Robot.java | 10 +- .../xrpeducational/EducationalRobot.java | 10 +- .../org/wpilib/templates/xrptimed/Robot.java | 10 +- 111 files changed, 487 insertions(+), 488 deletions(-) rename wpilibj/src/main/java/org/wpilib/opmode/{TestOpMode.java => Utility.java} (87%) diff --git a/commandsv2/src/main/java/org/wpilib/command2/button/RobotModeTriggers.java b/commandsv2/src/main/java/org/wpilib/command2/button/RobotModeTriggers.java index f21adf62b1..4afe51e55a 100644 --- a/commandsv2/src/main/java/org/wpilib/command2/button/RobotModeTriggers.java +++ b/commandsv2/src/main/java/org/wpilib/command2/button/RobotModeTriggers.java @@ -42,11 +42,11 @@ public final class RobotModeTriggers { } /** - * Returns a trigger that is true when the robot is enabled in test mode. + * Returns a trigger that is true when the robot is enabled in utility mode. * - * @return A trigger that is true when the robot is enabled in test mode. + * @return A trigger that is true when the robot is enabled in utility mode. */ - public static Trigger test() { - return new Trigger(RobotState::isTestEnabled); + public static Trigger utility() { + return new Trigger(RobotState::isUtilityEnabled); } } diff --git a/commandsv2/src/main/native/cpp/frc2/command/button/RobotModeTriggers.cpp b/commandsv2/src/main/native/cpp/frc2/command/button/RobotModeTriggers.cpp index ff58cecda2..70ac221424 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/button/RobotModeTriggers.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/button/RobotModeTriggers.cpp @@ -20,6 +20,6 @@ Trigger RobotModeTriggers::Disabled() { return Trigger{&wpi::RobotState::IsDisabled}; } -Trigger RobotModeTriggers::Test() { - return Trigger{&wpi::RobotState::IsTestEnabled}; +Trigger RobotModeTriggers::Utility() { + return Trigger{&wpi::RobotState::IsUtilityEnabled}; } diff --git a/commandsv2/src/main/native/include/wpi/commands2/button/RobotModeTriggers.hpp b/commandsv2/src/main/native/include/wpi/commands2/button/RobotModeTriggers.hpp index 6171640a4d..66150d64d5 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/button/RobotModeTriggers.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/button/RobotModeTriggers.hpp @@ -40,11 +40,11 @@ class RobotModeTriggers { static Trigger Disabled(); /** - * Returns a trigger that is true when the robot is enabled in test mode. + * Returns a trigger that is true when the robot is enabled in utility mode. * - * @return A trigger that is true when the robot is enabled in test mode. + * @return A trigger that is true when the robot is enabled in utility mode. */ - static Trigger Test(); + static Trigger Utility(); }; } // namespace wpi::cmd diff --git a/commandsv2/src/test/java/org/wpilib/MockHardwareExtension.java b/commandsv2/src/test/java/org/wpilib/MockHardwareExtension.java index 0918f18729..f3df07106c 100644 --- a/commandsv2/src/test/java/org/wpilib/MockHardwareExtension.java +++ b/commandsv2/src/test/java/org/wpilib/MockHardwareExtension.java @@ -33,7 +33,7 @@ public final class MockHardwareExtension implements BeforeAllCallback { HAL.initialize(500, 0); DriverStationSim.setDsAttached(true); DriverStationSim.setEnabled(true); - DriverStationSim.setRobotMode(RobotMode.TEST); + DriverStationSim.setRobotMode(RobotMode.UTILITY); DriverStationSim.notifyNewData(); } } diff --git a/commandsv2/src/test/java/org/wpilib/command2/button/RobotModeTriggersTest.java b/commandsv2/src/test/java/org/wpilib/command2/button/RobotModeTriggersTest.java index faa0909548..48714454fb 100644 --- a/commandsv2/src/test/java/org/wpilib/command2/button/RobotModeTriggersTest.java +++ b/commandsv2/src/test/java/org/wpilib/command2/button/RobotModeTriggersTest.java @@ -33,12 +33,12 @@ class RobotModeTriggersTest extends CommandTestBase { } @Test - void testModeTest() { + void utilityTest() { DriverStationSim.resetData(); - DriverStationSim.setRobotMode(RobotMode.TEST); + DriverStationSim.setRobotMode(RobotMode.UTILITY); DriverStationSim.setEnabled(true); DriverStationSim.notifyNewData(); - Trigger test = RobotModeTriggers.test(); + Trigger test = RobotModeTriggers.utility(); assertTrue(test.getAsBoolean()); } diff --git a/commandsv2/src/test/native/cpp/wpi/command/button/RobotModeTriggersTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/button/RobotModeTriggersTest.cpp index f97f0e8090..6ff1740a10 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/button/RobotModeTriggersTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/button/RobotModeTriggersTest.cpp @@ -40,11 +40,11 @@ TEST(RobotModeTriggersTest, Disabled) { EXPECT_TRUE(disabled.Get()); } -TEST(RobotModeTriggersTest, TestMode) { +TEST(RobotModeTriggersTest, UtilityMode) { DriverStationSim::ResetData(); - DriverStationSim::SetRobotMode(HAL_ROBOT_MODE_TEST); + DriverStationSim::SetRobotMode(HAL_ROBOT_MODE_UTILITY); DriverStationSim::SetEnabled(true); DriverStationSim::NotifyNewData(); - Trigger test = RobotModeTriggers::Test(); + Trigger test = RobotModeTriggers::Utility(); EXPECT_TRUE(test.Get()); } diff --git a/commandsv3/src/main/java/org/wpilib/command3/button/RobotModeTriggers.java b/commandsv3/src/main/java/org/wpilib/command3/button/RobotModeTriggers.java index cbb513161e..366c2f9657 100644 --- a/commandsv3/src/main/java/org/wpilib/command3/button/RobotModeTriggers.java +++ b/commandsv3/src/main/java/org/wpilib/command3/button/RobotModeTriggers.java @@ -43,11 +43,11 @@ public final class RobotModeTriggers { } /** - * Returns a trigger that is true when the robot is enabled in test mode. + * Returns a trigger that is true when the robot is enabled in utility mode. * - * @return A trigger that is true when the robot is enabled in test mode. + * @return A trigger that is true when the robot is enabled in utility mode. */ - public static Trigger test() { - return new Trigger(RobotState::isTestEnabled); + public static Trigger utility() { + return new Trigger(RobotState::isUtilityEnabled); } } diff --git a/developerRobot/src/main/java/wpilib/robot/Robot.java b/developerRobot/src/main/java/wpilib/robot/Robot.java index bfdfd31c3d..30a91404d2 100644 --- a/developerRobot/src/main/java/wpilib/robot/Robot.java +++ b/developerRobot/src/main/java/wpilib/robot/Robot.java @@ -29,9 +29,9 @@ public class Robot extends TimedRobot { @Override public void teleopPeriodic() {} - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} /** This function is called periodically during all modes. */ @Override diff --git a/developerRobot/src/main/native/cpp/Robot.cpp b/developerRobot/src/main/native/cpp/Robot.cpp index b8d328bfb7..07ebdfeea9 100644 --- a/developerRobot/src/main/native/cpp/Robot.cpp +++ b/developerRobot/src/main/native/cpp/Robot.cpp @@ -35,7 +35,7 @@ class Robot : public wpi::TimedRobot { /** * This function is called periodically during test mode */ - void TestPeriodic() override {} + void UtilityPeriodic() override {} /** * This function is called periodically during all modes diff --git a/hal/src/main/java/org/wpilib/hardware/hal/ControlWord.java b/hal/src/main/java/org/wpilib/hardware/hal/ControlWord.java index 4fac7e18c0..7df1579035 100644 --- a/hal/src/main/java/org/wpilib/hardware/hal/ControlWord.java +++ b/hal/src/main/java/org/wpilib/hardware/hal/ControlWord.java @@ -181,23 +181,23 @@ public class ControlWord { } /** - * 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 boolean isTest() { - return getRobotMode() == RobotMode.TEST; + public boolean isUtility() { + return getRobotMode() == RobotMode.UTILITY; } /** - * 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 boolean isTestEnabled() { - return isTest() && isEnabled() && isDSAttached(); + public boolean isUtilityEnabled() { + return isUtility() && isEnabled() && isDSAttached(); } /** diff --git a/hal/src/main/java/org/wpilib/hardware/hal/RobotMode.java b/hal/src/main/java/org/wpilib/hardware/hal/RobotMode.java index 02b3e5713d..4644b44ab7 100644 --- a/hal/src/main/java/org/wpilib/hardware/hal/RobotMode.java +++ b/hal/src/main/java/org/wpilib/hardware/hal/RobotMode.java @@ -12,8 +12,8 @@ public enum RobotMode { AUTONOMOUS(1), /** Teleoperated. */ TELEOPERATED(2), - /** Test. */ - TEST(3); + /** Utility. */ + UTILITY(3); private final int value; @@ -35,7 +35,7 @@ public enum RobotMode { return switch (value) { case 1 -> AUTONOMOUS; case 2 -> TELEOPERATED; - case 3 -> TEST; + case 3 -> UTILITY; default -> UNKNOWN; }; } diff --git a/hal/src/main/java/org/wpilib/hardware/hal/struct/ControlWordStruct.java b/hal/src/main/java/org/wpilib/hardware/hal/struct/ControlWordStruct.java index 93eb797640..cd27644704 100644 --- a/hal/src/main/java/org/wpilib/hardware/hal/struct/ControlWordStruct.java +++ b/hal/src/main/java/org/wpilib/hardware/hal/struct/ControlWordStruct.java @@ -27,7 +27,7 @@ public class ControlWordStruct implements Struct { @Override public String getSchema() { return "uint64 opModeHash:56;" - + "enum{unknown=0,autonomous=1,teleoperated=2,test=3} uint64 robotMode:2;" + + "enum{unknown=0,autonomous=1,teleoperated=2,utility=3} uint64 robotMode:2;" + "bool enabled:1;bool eStop:1;bool fmsAttached:1;bool dsAttached:1;"; } diff --git a/hal/src/main/native/cpp/DashboardOpMode.cpp b/hal/src/main/native/cpp/DashboardOpMode.cpp index 556aa7f2fd..093e2ae95a 100644 --- a/hal/src/main/native/cpp/DashboardOpMode.cpp +++ b/hal/src/main/native/cpp/DashboardOpMode.cpp @@ -99,13 +99,13 @@ struct DashboardOpModeInstance { void Start(nt::NetworkTableInstance inst) { autoOpModes.Start(inst, "/SmartDashboard/Auto OpMode"); teleopOpModes.Start(inst, "/SmartDashboard/Teleop OpMode"); - testOpModes.Start(inst, "/SmartDashboard/Test OpMode"); + utilityOpModes.Start(inst, "/SmartDashboard/Utility OpMode"); } util::mutex mutex; DashboardOpModeSender autoOpModes; DashboardOpModeSender teleopOpModes; - DashboardOpModeSender testOpModes; + DashboardOpModeSender utilityOpModes; }; } // namespace @@ -122,7 +122,7 @@ void hal::SetDashboardOpModeOptions(std::span options) { std::scoped_lock lock{gInstance->mutex}; gInstance->autoOpModes.SetOptions(options, HAL_ROBOT_MODE_AUTONOMOUS); gInstance->teleopOpModes.SetOptions(options, HAL_ROBOT_MODE_TELEOPERATED); - gInstance->testOpModes.SetOptions(options, HAL_ROBOT_MODE_TEST); + gInstance->utilityOpModes.SetOptions(options, HAL_ROBOT_MODE_UTILITY); } void hal::StartDashboardOpMode() { @@ -141,7 +141,7 @@ void hal::EnableDashboardOpMode() { std::scoped_lock lock{gInstance->mutex}; gInstance->autoOpModes.Enable(); gInstance->teleopOpModes.Enable(); - gInstance->testOpModes.Enable(); + gInstance->utilityOpModes.Enable(); } int64_t hal::GetDashboardSelectedOpMode(HAL_RobotMode robotMode) { @@ -154,8 +154,8 @@ int64_t hal::GetDashboardSelectedOpMode(HAL_RobotMode robotMode) { return gInstance->autoOpModes.GetSelected(); case HAL_ROBOT_MODE_TELEOPERATED: return gInstance->teleopOpModes.GetSelected(); - case HAL_ROBOT_MODE_TEST: - return gInstance->testOpModes.GetSelected(); + case HAL_ROBOT_MODE_UTILITY: + return gInstance->utilityOpModes.GetSelected(); default: return 0; } diff --git a/hal/src/main/native/include/wpi/hal/DriverStationTypes.h b/hal/src/main/native/include/wpi/hal/DriverStationTypes.h index b403cf95e1..bdb991d935 100644 --- a/hal/src/main/native/include/wpi/hal/DriverStationTypes.h +++ b/hal/src/main/native/include/wpi/hal/DriverStationTypes.h @@ -56,7 +56,7 @@ HAL_ENUM(HAL_RobotMode) { HAL_ROBOT_MODE_UNKNOWN = 0, HAL_ROBOT_MODE_AUTONOMOUS, HAL_ROBOT_MODE_TELEOPERATED, - HAL_ROBOT_MODE_TEST, + HAL_ROBOT_MODE_UTILITY, }; /** diff --git a/hal/src/main/native/include/wpi/hal/DriverStationTypes.hpp b/hal/src/main/native/include/wpi/hal/DriverStationTypes.hpp index 49a5f43e47..e874e6222b 100644 --- a/hal/src/main/native/include/wpi/hal/DriverStationTypes.hpp +++ b/hal/src/main/native/include/wpi/hal/DriverStationTypes.hpp @@ -19,8 +19,8 @@ enum class RobotMode { AUTONOMOUS = HAL_ROBOT_MODE_AUTONOMOUS, /// Teleoperated. TELEOPERATED = HAL_ROBOT_MODE_TELEOPERATED, - /// Test. - TEST = HAL_ROBOT_MODE_TEST + /// Utility. + UTILITY = HAL_ROBOT_MODE_UTILITY }; /** @@ -174,20 +174,20 @@ class ControlWord { } /** - * Check if the DS is commanding test mode. + * Check if the DS is commanding utility mode. * - * @return True if the robot is being commanded to be in test mode + * @return True if the robot is being commanded to be in utility mode */ - bool IsTest() const { return GetRobotMode() == RobotMode::TEST; } + bool IsUtility() const { return GetRobotMode() == RobotMode::UTILITY; } /** - * Check if the DS is commanding test mode and if it has enabled the robot. + * Check if the DS is commanding utility mode and if it has enabled the robot. * - * @return True if the robot is being commanded to be in test mode and + * @return True if the robot is being commanded to be in utility mode and * enabled. */ - bool IsTestEnabled() const { - return IsTest() && IsEnabled() && IsDSAttached(); + bool IsUtilityEnabled() const { + return IsUtility() && IsEnabled() && IsDSAttached(); } /** @@ -217,7 +217,7 @@ struct wpi::util::Struct { static constexpr size_t GetSize() { return 8; } static constexpr std::string_view GetSchema() { return "uint64 opModeHash:56;" - "enum{unknown=0,autonomous=1,teleoperated=2,test=3}" + "enum{unknown=0,autonomous=1,teleoperated=2,utility=3}" "uint64 robotMode:2;" "bool enabled:1;bool eStop:1;bool fmsAttached:1;bool dsAttached:1;"; } diff --git a/hal/src/main/python/semiwrap/DriverStationTypes.yml b/hal/src/main/python/semiwrap/DriverStationTypes.yml index c1a145e952..ef4d35f41f 100644 --- a/hal/src/main/python/semiwrap/DriverStationTypes.yml +++ b/hal/src/main/python/semiwrap/DriverStationTypes.yml @@ -29,6 +29,6 @@ classes: IsAutonomousEnabled: IsTeleop: IsTeleopEnabled: - IsTest: - IsTestEnabled: + IsUtility: + IsUtilityEnabled: GetValue: diff --git a/robotpyExamples/DriveDistanceOffboard/robot.py b/robotpyExamples/DriveDistanceOffboard/robot.py index f221c8fc52..07423e3cf1 100644 --- a/robotpyExamples/DriveDistanceOffboard/robot.py +++ b/robotpyExamples/DriveDistanceOffboard/robot.py @@ -69,6 +69,6 @@ class MyRobot(commands2.TimedCommandRobot): def teleopPeriodic(self) -> None: """This function is called periodically during operator control""" - def testInit(self) -> None: - # Cancels all running commands at the start of test mode + def utilityInit(self) -> None: + # Cancels all running commands at the start of utility mode commands2.CommandScheduler.getInstance().cancelAll() diff --git a/robotpyExamples/GettingStarted/robot.py b/robotpyExamples/GettingStarted/robot.py index 7d0d0ea379..1b624d15aa 100755 --- a/robotpyExamples/GettingStarted/robot.py +++ b/robotpyExamples/GettingStarted/robot.py @@ -49,8 +49,8 @@ class MyRobot(wpilib.TimedRobot): -self.controller.getLeftY(), -self.controller.getRightX() ) - def testInit(self): - """This function is called once each time the robot enters test mode.""" + def utilityInit(self): + """This function is called once each time the robot enters utility mode.""" - def testPeriodic(self): - """This function is called periodically during test mode.""" + def utilityPeriodic(self): + """This function is called periodically during utility mode.""" diff --git a/robotpyExamples/HatchbotInlined/robot.py b/robotpyExamples/HatchbotInlined/robot.py index bbb9f5b3df..1525bc33f8 100644 --- a/robotpyExamples/HatchbotInlined/robot.py +++ b/robotpyExamples/HatchbotInlined/robot.py @@ -66,6 +66,6 @@ class MyRobot(commands2.TimedCommandRobot): def teleopPeriodic(self) -> None: """This function is called periodically during operator control""" - def testInit(self) -> None: - # Cancels all running commands at the start of test mode + def utilityInit(self) -> None: + # Cancels all running commands at the start of utility mode commands2.CommandScheduler.getInstance().cancelAll() diff --git a/robotpyExamples/HatchbotTraditional/robot.py b/robotpyExamples/HatchbotTraditional/robot.py index bbb9f5b3df..1525bc33f8 100644 --- a/robotpyExamples/HatchbotTraditional/robot.py +++ b/robotpyExamples/HatchbotTraditional/robot.py @@ -66,6 +66,6 @@ class MyRobot(commands2.TimedCommandRobot): def teleopPeriodic(self) -> None: """This function is called periodically during operator control""" - def testInit(self) -> None: - # Cancels all running commands at the start of test mode + def utilityInit(self) -> None: + # Cancels all running commands at the start of utility mode commands2.CommandScheduler.getInstance().cancelAll() diff --git a/robotpyExamples/RapidReactCommandBot/robot.py b/robotpyExamples/RapidReactCommandBot/robot.py index 06377ebe15..4aa0f4f18c 100644 --- a/robotpyExamples/RapidReactCommandBot/robot.py +++ b/robotpyExamples/RapidReactCommandBot/robot.py @@ -61,10 +61,10 @@ class MyRobot(commands2.TimedCommandRobot): """This function is called periodically during operator control.""" pass - def testInit(self) -> None: - # Cancels all running commands at the start of test mode. + def utilityInit(self) -> None: + # Cancels all running commands at the start of utility mode. commands2.CommandScheduler.getInstance().cancelAll() - def testPeriodic(self) -> None: - """This function is called periodically during test mode.""" + def utilityPeriodic(self) -> None: + """This function is called periodically during utility mode.""" pass diff --git a/robotpyExamples/RomiReference/robot.py b/robotpyExamples/RomiReference/robot.py index dcc48e1b9a..cb436c5ba0 100644 --- a/robotpyExamples/RomiReference/robot.py +++ b/robotpyExamples/RomiReference/robot.py @@ -92,6 +92,6 @@ class MyRobot(commands2.TimedCommandRobot): def teleopPeriodic(self) -> None: """This function is called periodically during operator control""" - def testInit(self) -> None: - # Cancels all running commands at the start of test mode + def utilityInit(self) -> None: + # Cancels all running commands at the start of utility mode commands2.CommandScheduler.getInstance().cancelAll() diff --git a/robotpyExamples/SelectCommand/robot.py b/robotpyExamples/SelectCommand/robot.py index b65fda8cfd..bbd5460a2c 100644 --- a/robotpyExamples/SelectCommand/robot.py +++ b/robotpyExamples/SelectCommand/robot.py @@ -62,6 +62,6 @@ class MyRobot(commands2.TimedCommandRobot): """This function is called periodically during operator control""" pass - def testInit(self) -> None: - # Cancels all running commands at the start of test mode + def utilityInit(self) -> None: + # Cancels all running commands at the start of utility mode commands2.CommandScheduler.getInstance().cancelAll() diff --git a/robotpyExamples/SysId/robot.py b/robotpyExamples/SysId/robot.py index 9ec1204917..84dde3b57b 100644 --- a/robotpyExamples/SysId/robot.py +++ b/robotpyExamples/SysId/robot.py @@ -57,10 +57,10 @@ class MyRobot(TimedCommandRobot): """This function is called periodically during operator control.""" pass - def testInit(self) -> None: - # Cancels all running commands at the start of test mode. + def utilityInit(self) -> None: + # Cancels all running commands at the start of utility mode. CommandScheduler.getInstance().cancelAll() - def testPeriodic(self) -> None: - """This function is called periodically during test mode.""" + def utilityPeriodic(self) -> None: + """This function is called periodically during utility mode.""" pass diff --git a/robotpyExamples/XrpReference/robot.py b/robotpyExamples/XrpReference/robot.py index 6827d86b4d..e6aa0fcb73 100644 --- a/robotpyExamples/XrpReference/robot.py +++ b/robotpyExamples/XrpReference/robot.py @@ -92,6 +92,6 @@ class MyRobot(commands2.TimedCommandRobot): def teleopPeriodic(self) -> None: """This function is called periodically during operator control""" - def testInit(self) -> None: - # Cancels all running commands at the start of test mode + def utilityInit(self) -> None: + # Cancels all running commands at the start of utility mode commands2.CommandScheduler.getInstance().cancelAll() diff --git a/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp b/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp index d83cc6eb6f..042e1c1129 100644 --- a/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp +++ b/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp @@ -56,7 +56,7 @@ void DSCommPacket::SetControl(uint8_t control, uint8_t request) { if ((control & kAutonomous) != 0) { robotMode = HAL_ROBOT_MODE_AUTONOMOUS; } else if ((control & kTest) != 0) { - robotMode = HAL_ROBOT_MODE_TEST; + robotMode = HAL_ROBOT_MODE_UTILITY; } else { robotMode = HAL_ROBOT_MODE_TELEOPERATED; } diff --git a/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp b/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp index dfea6cdbbd..7a67cb0193 100644 --- a/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp @@ -309,7 +309,7 @@ struct OpModes { static wpi::util::mutex gOpModeOptionsMutex; static OpModes gAutoOpModes; static OpModes gTeleopOpModes; -static OpModes gTestOpModes; +static OpModes gUtilityOpModes; static void UpdateOpModes(const char* name, void* param, const HAL_OpModeOption* opmodes, int32_t count) { @@ -318,8 +318,8 @@ static void UpdateOpModes(const char* name, void* param, gAutoOpModes.groups.clear(); gTeleopOpModes.ids.clear(); gTeleopOpModes.groups.clear(); - gTestOpModes.ids.clear(); - gTestOpModes.groups.clear(); + gUtilityOpModes.ids.clear(); + gUtilityOpModes.groups.clear(); for (auto&& o : std::span{opmodes, opmodes + count}) { OpModes* vec; switch (HAL_OpMode_GetRobotMode(o.id)) { @@ -329,8 +329,8 @@ static void UpdateOpModes(const char* name, void* param, case HAL_ROBOT_MODE_TELEOPERATED: vec = &gTeleopOpModes; break; - case HAL_ROBOT_MODE_TEST: - vec = &gTestOpModes; + case HAL_ROBOT_MODE_UTILITY: + vec = &gUtilityOpModes; break; default: continue; @@ -341,7 +341,7 @@ static void UpdateOpModes(const char* name, void* param, std::string{wpi::util::to_string_view(&o.description)}, o.textColor, o.backgroundColor}); } - for (auto&& vec : {&gAutoOpModes, &gTeleopOpModes, &gTestOpModes}) { + for (auto&& vec : {&gAutoOpModes, &gTeleopOpModes, &gUtilityOpModes}) { for (auto&& [group, options] : vec->groups) { std::sort(options.begin(), options.end(), [](const OpModeOption& a, const OpModeOption& b) { @@ -1181,9 +1181,9 @@ static void DriverStationExecute() { isAttached && robotMode == HAL_ROBOT_MODE_TELEOPERATED)) { DriverStationSetRobotMode(HAL_ROBOT_MODE_TELEOPERATED); } - if (ImGui::Selectable("Test", - isAttached && robotMode == HAL_ROBOT_MODE_TEST)) { - DriverStationSetRobotMode(HAL_ROBOT_MODE_TEST); + if (ImGui::Selectable("Utility", + isAttached && robotMode == HAL_ROBOT_MODE_UTILITY)) { + DriverStationSetRobotMode(HAL_ROBOT_MODE_UTILITY); } // OpMode bool canEnable = isAttached && started; @@ -1200,8 +1200,8 @@ static void DriverStationExecute() { case HAL_ROBOT_MODE_TELEOPERATED: modes = &gTeleopOpModes; break; - case HAL_ROBOT_MODE_TEST: - modes = &gTestOpModes; + case HAL_ROBOT_MODE_UTILITY: + modes = &gUtilityOpModes; break; default: modes = nullptr; diff --git a/wpilibc/src/main/native/cpp/framework/IterativeRobotBase.cpp b/wpilibc/src/main/native/cpp/framework/IterativeRobotBase.cpp index d6efcbf073..47572256ed 100644 --- a/wpilibc/src/main/native/cpp/framework/IterativeRobotBase.cpp +++ b/wpilibc/src/main/native/cpp/framework/IterativeRobotBase.cpp @@ -29,7 +29,7 @@ void IterativeRobotBase::AutonomousInit() {} void IterativeRobotBase::TeleopInit() {} -void IterativeRobotBase::TestInit() {} +void IterativeRobotBase::UtilityInit() {} void IterativeRobotBase::RobotPeriodic() { static bool firstRun = true; @@ -71,7 +71,7 @@ void IterativeRobotBase::TeleopPeriodic() { } } -void IterativeRobotBase::TestPeriodic() { +void IterativeRobotBase::UtilityPeriodic() { static bool firstRun = true; if (firstRun) { wpi::util::print("Default {}() method... Override me!\n", __FUNCTION__); @@ -85,7 +85,7 @@ void IterativeRobotBase::AutonomousExit() {} void IterativeRobotBase::TeleopExit() {} -void IterativeRobotBase::TestExit() {} +void IterativeRobotBase::UtilityExit() {} wpi::units::second_t IterativeRobotBase::GetPeriod() const { return m_period; @@ -114,8 +114,8 @@ void IterativeRobotBase::LoopFunc() { AutonomousExit(); } else if (m_lastMode == static_cast(RobotMode::TELEOPERATED)) { TeleopExit(); - } else if (m_lastMode == static_cast(RobotMode::TEST)) { - TestExit(); + } else if (m_lastMode == static_cast(RobotMode::UTILITY)) { + UtilityExit(); } // Call current mode's entry function @@ -128,9 +128,9 @@ void IterativeRobotBase::LoopFunc() { } else if (mode == RobotMode::TELEOPERATED) { TeleopInit(); m_watchdog.AddEpoch("TeleopInit()"); - } else if (mode == RobotMode::TEST) { - TestInit(); - m_watchdog.AddEpoch("TestInit()"); + } else if (mode == RobotMode::UTILITY) { + UtilityInit(); + m_watchdog.AddEpoch("UtilityInit()"); } m_lastMode = static_cast(mode); @@ -147,9 +147,9 @@ void IterativeRobotBase::LoopFunc() { } else if (mode == RobotMode::TELEOPERATED) { TeleopPeriodic(); m_watchdog.AddEpoch("TeleopPeriodic()"); - } else if (mode == RobotMode::TEST) { - TestPeriodic(); - m_watchdog.AddEpoch("TestPeriodic()"); + } else if (mode == RobotMode::UTILITY) { + UtilityPeriodic(); + m_watchdog.AddEpoch("UtilityPeriodic()"); } RobotPeriodic(); diff --git a/wpilibc/src/main/native/cpp/hardware/motor/MotorSafety.cpp b/wpilibc/src/main/native/cpp/hardware/motor/MotorSafety.cpp index 2461a1ad7f..e5e5ba60df 100644 --- a/wpilibc/src/main/native/cpp/hardware/motor/MotorSafety.cpp +++ b/wpilibc/src/main/native/cpp/hardware/motor/MotorSafety.cpp @@ -153,7 +153,7 @@ void MotorSafety::Check() { stopTime = m_stopTime; } - if (!enabled || RobotState::IsDisabled() || RobotState::IsTest()) { + if (!enabled || RobotState::IsDisabled() || RobotState::IsUtility()) { return; } diff --git a/wpilibc/src/main/native/cppcs/RobotBase.cpp b/wpilibc/src/main/native/cppcs/RobotBase.cpp index be8057a952..13faf3d50f 100644 --- a/wpilibc/src/main/native/cppcs/RobotBase.cpp +++ b/wpilibc/src/main/native/cppcs/RobotBase.cpp @@ -158,12 +158,12 @@ bool RobotBase::IsTeleopEnabled() { return RobotState::IsTeleopEnabled(); } -bool RobotBase::IsTest() { - return RobotState::IsTest(); +bool RobotBase::IsUtility() { + return RobotState::IsUtility(); } -bool RobotBase::IsTestEnabled() { - return RobotState::IsTestEnabled(); +bool RobotBase::IsUtilityEnabled() { + return RobotState::IsUtilityEnabled(); } int64_t RobotBase::GetOpModeId() { diff --git a/wpilibc/src/main/native/include/wpi/driverstation/RobotState.hpp b/wpilibc/src/main/native/include/wpi/driverstation/RobotState.hpp index d50e13b414..5b7d9acd38 100644 --- a/wpilibc/src/main/native/include/wpi/driverstation/RobotState.hpp +++ b/wpilibc/src/main/native/include/wpi/driverstation/RobotState.hpp @@ -99,20 +99,22 @@ class RobotState final { } /** - * Check if the DS is commanding test mode. + * Check if the DS is commanding utility mode. * - * @return True if the robot is being commanded to be in test mode + * @return True if the robot is being commanded to be in utility mode */ - static bool IsTest() { return wpi::internal::DriverStationBackend::IsTest(); } + static bool IsUtility() { + return wpi::internal::DriverStationBackend::IsUtility(); + } /** - * Check if the DS is commanding Test mode and if it has enabled the robot. + * Check if the DS is commanding Utility mode and if it has enabled the robot. * - * @return True if the robot is being commanded to be in Test mode and + * @return True if the robot is being commanded to be in Utility mode and * enabled. */ - static bool IsTestEnabled() { - return wpi::internal::DriverStationBackend::IsTestEnabled(); + static bool IsUtilityEnabled() { + return wpi::internal::DriverStationBackend::IsUtilityEnabled(); } /** diff --git a/wpilibc/src/main/native/include/wpi/driverstation/internal/DriverStationBackend.hpp b/wpilibc/src/main/native/include/wpi/driverstation/internal/DriverStationBackend.hpp index 2f44ce0471..3f96fc1476 100644 --- a/wpilibc/src/main/native/include/wpi/driverstation/internal/DriverStationBackend.hpp +++ b/wpilibc/src/main/native/include/wpi/driverstation/internal/DriverStationBackend.hpp @@ -303,19 +303,19 @@ class DriverStationBackend final { static bool IsTeleopEnabled() { return GetControlWord().IsTeleopEnabled(); } /** - * Check if the DS is commanding test mode. + * Check if the DS is commanding utility mode. * - * @return True if the robot is being commanded to be in test mode + * @return True if the robot is being commanded to be in utility mode */ - static bool IsTest() { return GetControlWord().IsTest(); } + static bool IsUtility() { return GetControlWord().IsUtility(); } /** - * Check if the DS is commanding Test mode and if it has enabled the robot. + * Check if the DS is commanding Utility mode and if it has enabled the robot. * - * @return True if the robot is being commanded to be in Test mode and + * @return True if the robot is being commanded to be in Utility mode and * enabled. */ - static bool IsTestEnabled() { return GetControlWord().IsTestEnabled(); } + static bool IsUtilityEnabled() { return GetControlWord().IsUtilityEnabled(); } /** * Adds an operating mode option. It's necessary to call PublishOpModes() to diff --git a/wpilibc/src/main/native/include/wpi/framework/IterativeRobotBase.hpp b/wpilibc/src/main/native/include/wpi/framework/IterativeRobotBase.hpp index 09fe232ac2..69e5e00b94 100644 --- a/wpilibc/src/main/native/include/wpi/framework/IterativeRobotBase.hpp +++ b/wpilibc/src/main/native/include/wpi/framework/IterativeRobotBase.hpp @@ -32,8 +32,8 @@ namespace wpi { * 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 * * Periodic() functions -- each of these functions is called on an interval: * @@ -41,7 +41,7 @@ namespace wpi { * \li DisabledPeriodic() * \li AutonomousPeriodic() * \li TeleopPeriodic() - * \li TestPeriodic() + * \li UtilityPeriodic() * * Exit() functions -- each of the following functions is called once when the * appropriate mode is exited: @@ -49,7 +49,7 @@ namespace wpi { * \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 */ class IterativeRobotBase : public RobotBase { public: @@ -97,12 +97,12 @@ class IterativeRobotBase : public RobotBase { virtual void TeleopInit(); /** - * Initialization code for test mode should go here. + * Initialization code for utility mode should go here. * * Users should override this method for initialization code which will be - * called each time the robot enters test mode. + * called each time the robot enters utility mode. */ - virtual void TestInit(); + virtual void UtilityInit(); /** * Periodic code for all modes should go here. @@ -147,13 +147,13 @@ class IterativeRobotBase : public RobotBase { virtual void TeleopPeriodic(); /** - * Periodic code for test mode should go here. + * Periodic code for utility mode should go here. * * Users should override this method for code which will be called each time a - * new packet is received from the driver station and the robot is in test + * new packet is received from the driver station and the robot is in utility * mode. */ - virtual void TestPeriodic(); + virtual void UtilityPeriodic(); /** * Exit code for disabled mode should go here. @@ -180,12 +180,12 @@ class IterativeRobotBase : public RobotBase { virtual void TeleopExit(); /** - * Exit code for test mode should go here. + * Exit code for utility mode should go here. * * Users should override this method for code which will be called each time - * the robot exits test mode. + * the robot exits utility mode. */ - virtual void TestExit(); + virtual void UtilityExit(); /** * Gets time period between calls to Periodic() functions. diff --git a/wpilibc/src/main/native/include/wpi/framework/OpModeRobot.hpp b/wpilibc/src/main/native/include/wpi/framework/OpModeRobot.hpp index c817cd8d76..de1df00e0a 100644 --- a/wpilibc/src/main/native/include/wpi/framework/OpModeRobot.hpp +++ b/wpilibc/src/main/native/include/wpi/framework/OpModeRobot.hpp @@ -13,14 +13,11 @@ #include "wpi/driverstation/Alert.hpp" #include "wpi/framework/RobotBase.hpp" #include "wpi/hal/DriverStationTypes.hpp" -#include "wpi/hal/Notifier.h" #include "wpi/internal/PeriodicPriorityQueue.hpp" #include "wpi/opmode/OpMode.hpp" #include "wpi/system/Watchdog.hpp" #include "wpi/units/time.hpp" #include "wpi/util/DenseMap.hpp" -#include "wpi/util/SafeThread.hpp" -#include "wpi/util/Synchronization.hpp" #include "wpi/util/mutex.hpp" namespace wpi::util { diff --git a/wpilibc/src/main/native/include/wpi/framework/RobotBase.hpp b/wpilibc/src/main/native/include/wpi/framework/RobotBase.hpp index 767f2cd98d..7ae472681a 100644 --- a/wpilibc/src/main/native/include/wpi/framework/RobotBase.hpp +++ b/wpilibc/src/main/native/include/wpi/framework/RobotBase.hpp @@ -191,20 +191,20 @@ class RobotBase { static bool IsTeleopEnabled(); /** - * Determine if the robot is currently in Test mode. + * Determine if the robot is currently in Utility mode. * - * @return True if the robot is currently running in Test mode as determined - * by the Driver Station. + * @return True if the robot is currently running in Utility mode as + * determined by the Driver Station. */ - static bool IsTest(); + static bool IsUtility(); /** - * Determine if the robot is current in Test mode and enabled. + * Determine if the robot is currently in Utility mode and enabled. * - * @return True if the robot is currently operating in Test mode while + * @return True if the robot is currently operating in Utility mode while * enabled as determined by the Driver Station. */ - static bool IsTestEnabled(); + static bool IsUtilityEnabled(); /** * Gets the currently selected operating mode of the driver station. Note this diff --git a/wpilibc/src/main/python/semiwrap/DriverStationBackend.yml b/wpilibc/src/main/python/semiwrap/DriverStationBackend.yml index 246adacdad..ee022b9fd6 100644 --- a/wpilibc/src/main/python/semiwrap/DriverStationBackend.yml +++ b/wpilibc/src/main/python/semiwrap/DriverStationBackend.yml @@ -36,8 +36,8 @@ classes: IsAutonomousEnabled: IsTeleop: IsTeleopEnabled: - IsTest: - IsTestEnabled: + IsUtility: + IsUtilityEnabled: AddOpMode: overloads: RobotMode, std::string_view, std::string_view, std::string_view, const wpi::util::Color&, const wpi::util::Color&: diff --git a/wpilibc/src/main/python/semiwrap/IterativeRobotBase.yml b/wpilibc/src/main/python/semiwrap/IterativeRobotBase.yml index b0803dd501..bb68d7e31b 100644 --- a/wpilibc/src/main/python/semiwrap/IterativeRobotBase.yml +++ b/wpilibc/src/main/python/semiwrap/IterativeRobotBase.yml @@ -5,12 +5,12 @@ classes: DisabledInit: AutonomousInit: TeleopInit: - TestInit: + UtilityInit: RobotPeriodic: DisabledPeriodic: AutonomousPeriodic: TeleopPeriodic: - TestPeriodic: + UtilityPeriodic: IterativeRobotBase: overloads: double: @@ -22,7 +22,7 @@ classes: DisabledExit: AutonomousExit: TeleopExit: - TestExit: + UtilityExit: GetPeriod: PrintWatchdogEpochs: doc: | @@ -44,7 +44,7 @@ classes: - DisabledInit() -- called each and every time disabled is entered from another mode - AutonomousInit() -- called each and every time autonomous is entered from another mode - TeleopInit() -- called each and every time teleop is entered from another mode - - TestInit() -- called each and every time test is entered from another mode + - UtilityInit() -- called each and every time utility is entered from another mode Periodic() functions -- each of these functions is called on an interval: @@ -52,7 +52,7 @@ classes: - DisabledPeriodic() - AutonomousPeriodic() - TeleopPeriodic() - - TestPeriodic() + - UtilityPeriodic() Exit() functions -- each of the following functions is called once when the appropriate mode is exited: @@ -60,4 +60,4 @@ classes: - DisabledExit() -- called each and every time disabled is exited - AutonomousExit() -- called each and every time autonomous is exited - TeleopExit() -- called each and every time teleop is exited - - TestExit() -- called each and every time test is exited + - UtilityExit() -- called each and every time utility is exited diff --git a/wpilibc/src/main/python/semiwrap/RobotBase.yml b/wpilibc/src/main/python/semiwrap/RobotBase.yml index 95ca956b99..203e2f8f78 100644 --- a/wpilibc/src/main/python/semiwrap/RobotBase.yml +++ b/wpilibc/src/main/python/semiwrap/RobotBase.yml @@ -25,8 +25,8 @@ classes: IsAutonomousEnabled: IsTeleop: IsTeleopEnabled: - IsTest: - IsTestEnabled: + IsUtility: + IsUtilityEnabled: GetThreadId: ignore: true StartCompetition: diff --git a/wpilibc/src/main/python/semiwrap/RobotState.yml b/wpilibc/src/main/python/semiwrap/RobotState.yml index 3c07a64f28..a199b76f55 100644 --- a/wpilibc/src/main/python/semiwrap/RobotState.yml +++ b/wpilibc/src/main/python/semiwrap/RobotState.yml @@ -12,8 +12,8 @@ classes: IsAutonomousEnabled: IsTeleop: IsTeleopEnabled: - IsTest: - IsTestEnabled: + IsUtility: + IsUtilityEnabled: AddOpMode: overloads: RobotMode, std::string_view, std::string_view, std::string_view, const wpi::util::Color&, const wpi::util::Color&: diff --git a/wpilibc/src/test/native/cpp/OpModeRobotTest.cpp b/wpilibc/src/test/native/cpp/OpModeRobotTest.cpp index 72a4f7e05b..3dd9bc441f 100644 --- a/wpilibc/src/test/native/cpp/OpModeRobotTest.cpp +++ b/wpilibc/src/test/native/cpp/OpModeRobotTest.cpp @@ -78,7 +78,7 @@ TEST_F(OpModeRobotTest, AddOpMode) { AddOpMode(wpi::RobotMode::AUTONOMOUS, "NoArgOpMode-Auto", "Group", "Description", wpi::util::Color::WHITE, wpi::util::Color::BLACK); - AddOpMode(wpi::RobotMode::TEST, "OneArgOpMode-Test", + AddOpMode(wpi::RobotMode::UTILITY, "OneArgOpMode-Test", "Group", "Description", wpi::util::Color::WHITE, wpi::util::Color::BLACK); AddOpMode(wpi::RobotMode::TELEOPERATED, "NoArgOpMode"); diff --git a/wpilibc/src/test/native/cpp/TimedRobotTest.cpp b/wpilibc/src/test/native/cpp/TimedRobotTest.cpp index dc2f594f44..fb372dc660 100644 --- a/wpilibc/src/test/native/cpp/TimedRobotTest.cpp +++ b/wpilibc/src/test/native/cpp/TimedRobotTest.cpp @@ -60,7 +60,7 @@ class MockRobot : public TimedRobot { void TeleopInit() override { m_teleopInitCount++; } - void TestInit() override { m_testInitCount++; } + void UtilityInit() override { m_testInitCount++; } void RobotPeriodic() override { m_robotPeriodicCount++; } @@ -72,7 +72,7 @@ class MockRobot : public TimedRobot { void TeleopPeriodic() override { m_teleopPeriodicCount++; } - void TestPeriodic() override { m_testPeriodicCount++; } + void UtilityPeriodic() override { m_testPeriodicCount++; } void DisabledExit() override { m_disabledExitCount++; } @@ -80,7 +80,7 @@ class MockRobot : public TimedRobot { void TeleopExit() override { m_teleopExitCount++; } - void TestExit() override { m_testExitCount++; } + void UtilityExit() override { m_testExitCount++; } }; } // namespace @@ -305,7 +305,7 @@ TEST_F(TimedRobotTest, TestMode) { wpi::sim::WaitForProgramStart(); wpi::sim::DriverStationSim::SetEnabled(true); - wpi::sim::DriverStationSim::SetRobotMode(HAL_ROBOT_MODE_TEST); + wpi::sim::DriverStationSim::SetRobotMode(HAL_ROBOT_MODE_UTILITY); wpi::sim::DriverStationSim::NotifyNewData(); EXPECT_EQ(1u, robot.m_simulationInitCount); @@ -460,7 +460,7 @@ TEST_F(TimedRobotTest, ModeChange) { // Transition to test wpi::sim::DriverStationSim::SetEnabled(true); - wpi::sim::DriverStationSim::SetRobotMode(HAL_ROBOT_MODE_TEST); + wpi::sim::DriverStationSim::SetRobotMode(HAL_ROBOT_MODE_UTILITY); wpi::sim::DriverStationSim::NotifyNewData(); wpi::sim::StepTiming(kPeriod); diff --git a/wpilibc/src/test/native/cpp/simulation/DriverStationSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/DriverStationSimTest.cpp index 5cf7b892ce..65ee41125c 100644 --- a/wpilibc/src/test/native/cpp/simulation/DriverStationSimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/DriverStationSimTest.cpp @@ -54,17 +54,17 @@ TEST(DriverStationTest, Mode) { HAL_Initialize(500, 0); DriverStationSim::ResetData(); - EXPECT_FALSE(RobotState::IsTest()); + EXPECT_FALSE(RobotState::IsUtility()); EnumCallback callback; auto cb = DriverStationSim::RegisterRobotModeCallback(callback.GetCallback(), false); - DriverStationSim::SetRobotMode(HAL_ROBOT_MODE_TEST); + DriverStationSim::SetRobotMode(HAL_ROBOT_MODE_UTILITY); DriverStationSim::NotifyNewData(); - EXPECT_EQ(DriverStationSim::GetRobotMode(), HAL_ROBOT_MODE_TEST); - EXPECT_TRUE(RobotState::IsTest()); - EXPECT_EQ(RobotState::GetRobotMode(), RobotMode::TEST); + EXPECT_EQ(DriverStationSim::GetRobotMode(), HAL_ROBOT_MODE_UTILITY); + EXPECT_TRUE(RobotState::IsUtility()); + EXPECT_EQ(RobotState::GetRobotMode(), RobotMode::UTILITY); EXPECT_TRUE(callback.WasTriggered()); - EXPECT_EQ(callback.GetLastValue(), HAL_ROBOT_MODE_TEST); + EXPECT_EQ(callback.GetLastValue(), HAL_ROBOT_MODE_UTILITY); } TEST(DriverStationTest, Estop) { diff --git a/wpilibc/src/test/python/test_opmode_robot.py b/wpilibc/src/test/python/test_opmode_robot.py index 7586b5c98f..db3debbf76 100644 --- a/wpilibc/src/test/python/test_opmode_robot.py +++ b/wpilibc/src/test/python/test_opmode_robot.py @@ -73,8 +73,8 @@ def test_add_op_mode(): ) self.addOpMode( OneArgOpMode, - RobotMode.TEST, - "OneArgOpMode-Test", + RobotMode.UTILITY, + "OneArgOpMode-Utility", "Group", "Description", Color.WHITE, diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp index 4066a07b39..0dc98a27e5 100644 --- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp @@ -12,7 +12,7 @@ Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use * this for items like diagnostics that you want to run during disabled, - * autonomous, teleoperated and test. + * autonomous, teleoperated and utility. * *

This runs after the mode specific periodic functions, but before * LiveWindow and SmartDashboard integrated updating. @@ -62,9 +62,9 @@ void Robot::TeleopInit() { void Robot::TeleopPeriodic() {} /** - * This function is called periodically during test mode. + * This function is called periodically during utility mode. */ -void Robot::TestPeriodic() {} +void Robot::UtilityPeriodic() {} #ifndef RUNNING_WPILIB_TESTS int main() { diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.hpp index 06fd8e4082..0e9c426305 100644 --- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.hpp @@ -20,7 +20,7 @@ class Robot : public wpi::TimedRobot { void AutonomousPeriodic() override; void TeleopInit() override; void TeleopPeriodic() override; - void TestPeriodic() override; + void UtilityPeriodic() override; private: // Have it null by default so that if testing teleop it diff --git a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp index 1bdfbece68..71ad9ec71e 100644 --- a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp @@ -43,9 +43,9 @@ class Robot : public wpi::TimedRobot { m_controller.GetRightX()); } - void TestInit() override {} + void UtilityInit() override {} - void TestPeriodic() override {} + void UtilityPeriodic() override {} private: // Robot drive system diff --git a/wpilibcExamples/src/main/cpp/examples/HAL/c/Robot.c b/wpilibcExamples/src/main/cpp/examples/HAL/c/Robot.c index 125600d074..3a9802fad5 100644 --- a/wpilibcExamples/src/main/cpp/examples/HAL/c/Robot.c +++ b/wpilibcExamples/src/main/cpp/examples/HAL/c/Robot.c @@ -56,8 +56,8 @@ int main(void) { {"", 0}, -1, -1}, - {HAL_MAKE_OPMODEID(HAL_ROBOT_MODE_TEST, 0), - {"Test", 4}, + {HAL_MAKE_OPMODEID(HAL_ROBOT_MODE_UTILITY, 0), + {"Utility", 4}, {"", 0}, {"", 0}, -1, @@ -116,7 +116,7 @@ int main(void) { break; case HAL_ROBOT_MODE_AUTONOMOUS: break; - case HAL_ROBOT_MODE_TEST: + case HAL_ROBOT_MODE_UTILITY: break; default: break; diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp index 8254b6b646..9fc2a216c4 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp @@ -21,7 +21,7 @@ Robot::Robot() { /** * This function is called every 20 ms, no matter the mode. Use * this for items like diagnostics that you want to run during disabled, - * autonomous, teleoperated and test. + * autonomous, teleoperated and utility. * *

This runs after the mode specific periodic functions, but before * LiveWindow and SmartDashboard integrated updating. @@ -70,9 +70,9 @@ void Robot::TeleopInit() { void Robot::TeleopPeriodic() {} /** - * This function is called periodically during test mode. + * This function is called periodically during utility mode. */ -void Robot::TestPeriodic() {} +void Robot::UtilityPeriodic() {} #ifndef RUNNING_WPILIB_TESTS int main() { diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Robot.hpp index e85eeafd48..377ae1bfc2 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Robot.hpp @@ -18,7 +18,7 @@ class Robot : public wpi::TimedRobot { void AutonomousPeriodic() override; void TeleopInit() override; void TeleopPeriodic() override; - void TestPeriodic() override; + void UtilityPeriodic() override; private: // Have it null by default so that if testing teleop it diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp index 8254b6b646..9fc2a216c4 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp @@ -21,7 +21,7 @@ Robot::Robot() { /** * This function is called every 20 ms, no matter the mode. Use * this for items like diagnostics that you want to run during disabled, - * autonomous, teleoperated and test. + * autonomous, teleoperated and utility. * *

This runs after the mode specific periodic functions, but before * LiveWindow and SmartDashboard integrated updating. @@ -70,9 +70,9 @@ void Robot::TeleopInit() { void Robot::TeleopPeriodic() {} /** - * This function is called periodically during test mode. + * This function is called periodically during utility mode. */ -void Robot::TestPeriodic() {} +void Robot::UtilityPeriodic() {} #ifndef RUNNING_WPILIB_TESTS int main() { diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Robot.hpp index e85eeafd48..377ae1bfc2 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Robot.hpp @@ -18,7 +18,7 @@ class Robot : public wpi::TimedRobot { void AutonomousPeriodic() override; void TeleopInit() override; void TeleopPeriodic() override; - void TestPeriodic() override; + void UtilityPeriodic() override; private: // Have it null by default so that if testing teleop it diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp index 02810f7730..ef39cfe6dd 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp @@ -45,12 +45,12 @@ void Robot::TeleopInit() { void Robot::TeleopPeriodic() {} -void Robot::TestInit() { - // Cancels all running commands at the start of test mode. +void Robot::UtilityInit() { + // Cancels all running commands at the start of utility mode. wpi::cmd::CommandScheduler::GetInstance().CancelAll(); } -void Robot::TestPeriodic() {} +void Robot::UtilityPeriodic() {} #ifndef RUNNING_WPILIB_TESTS int main() { diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.hpp index a8a03790c4..151282ce6f 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.hpp @@ -20,8 +20,8 @@ class Robot : public wpi::TimedRobot { void AutonomousPeriodic() override; void TeleopInit() override; void TeleopPeriodic() override; - void TestInit() override; - void TestPeriodic() override; + void UtilityInit() override; + void UtilityPeriodic() override; private: RapidReactCommandBot m_robot; diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp index ac43e33927..2ec33e6770 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp @@ -11,7 +11,7 @@ Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use * this for items like diagnostics that you want to run during disabled, - * autonomous, teleoperated and test. + * autonomous, teleoperated and utility. * *

This runs after the mode specific periodic functions, but before * LiveWindow and SmartDashboard integrated updating. @@ -60,9 +60,9 @@ void Robot::TeleopInit() { void Robot::TeleopPeriodic() {} /** - * This function is called periodically during test mode. + * This function is called periodically during utility mode. */ -void Robot::TestPeriodic() {} +void Robot::UtilityPeriodic() {} #ifndef RUNNING_WPILIB_TESTS int main() { diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Robot.hpp index 491f60b9ce..2d2e802c16 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Robot.hpp @@ -18,7 +18,7 @@ class Robot : public wpi::TimedRobot { void AutonomousPeriodic() override; void TeleopInit() override; void TeleopPeriodic() override; - void TestPeriodic() override; + void UtilityPeriodic() override; private: // Have it null by default so that if testing teleop it diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/Robot.cpp index 82be3ea945..3dd2cac83b 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/Robot.cpp @@ -41,13 +41,13 @@ void Robot::TeleopPeriodic() {} void Robot::TeleopExit() {} -void Robot::TestInit() { +void Robot::UtilityInit() { wpi::cmd::CommandScheduler::GetInstance().CancelAll(); } -void Robot::TestPeriodic() {} +void Robot::UtilityPeriodic() {} -void Robot::TestExit() {} +void Robot::UtilityExit() {} #ifndef RUNNING_WPILIB_TESTS int main() { diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/Robot.hpp index 89d8bf5150..0eb843e390 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/Robot.hpp @@ -23,9 +23,9 @@ class Robot : public wpi::TimedRobot { void TeleopInit() override; void TeleopPeriodic() override; void TeleopExit() override; - void TestInit() override; - void TestPeriodic() override; - void TestExit() override; + void UtilityInit() override; + void UtilityPeriodic() override; + void UtilityExit() override; private: std::optional m_autonomousCommand; diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp index ac43e33927..2ec33e6770 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp @@ -11,7 +11,7 @@ Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use * this for items like diagnostics that you want to run during disabled, - * autonomous, teleoperated and test. + * autonomous, teleoperated and utility. * *

This runs after the mode specific periodic functions, but before * LiveWindow and SmartDashboard integrated updating. @@ -60,9 +60,9 @@ void Robot::TeleopInit() { void Robot::TeleopPeriodic() {} /** - * This function is called periodically during test mode. + * This function is called periodically during utility mode. */ -void Robot::TestPeriodic() {} +void Robot::UtilityPeriodic() {} #ifndef RUNNING_WPILIB_TESTS int main() { diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Robot.hpp index 491f60b9ce..2d2e802c16 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Robot.hpp @@ -18,7 +18,7 @@ class Robot : public wpi::TimedRobot { void AutonomousPeriodic() override; void TeleopInit() override; void TeleopPeriodic() override; - void TestPeriodic() override; + void UtilityPeriodic() override; private: // Have it null by default so that if testing teleop it diff --git a/wpilibcExamples/src/main/cpp/examples/Xrptimed/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Xrptimed/cpp/Robot.cpp index 9dc34d9a0a..5254620c9c 100644 --- a/wpilibcExamples/src/main/cpp/examples/Xrptimed/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Xrptimed/cpp/Robot.cpp @@ -17,7 +17,7 @@ Robot::Robot() { /** * This function is called every 20 ms, no matter the mode. Use * this for items like diagnostics that you want ran during disabled, - * autonomous, teleoperated and test. + * autonomous, teleoperated and utility. * *

This runs after the mode specific periodic functions, but before * LiveWindow and SmartDashboard integrated updating. diff --git a/wpilibcExamples/src/main/cpp/snippets/SelectCommand/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/SelectCommand/cpp/Robot.cpp index 4126afdfff..98d76a7228 100644 --- a/wpilibcExamples/src/main/cpp/snippets/SelectCommand/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/SelectCommand/cpp/Robot.cpp @@ -61,9 +61,9 @@ void Robot::TeleopInit() { void Robot::TeleopPeriodic() {} /** - * This function is called periodically during test mode. + * This function is called periodically during utility mode. */ -void Robot::TestPeriodic() {} +void Robot::UtilityPeriodic() {} #ifndef RUNNING_WPILIB_TESTS int main() { diff --git a/wpilibcExamples/src/main/cpp/snippets/SelectCommand/include/Robot.hpp b/wpilibcExamples/src/main/cpp/snippets/SelectCommand/include/Robot.hpp index e85eeafd48..377ae1bfc2 100644 --- a/wpilibcExamples/src/main/cpp/snippets/SelectCommand/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/snippets/SelectCommand/include/Robot.hpp @@ -18,7 +18,7 @@ class Robot : public wpi::TimedRobot { void AutonomousPeriodic() override; void TeleopInit() override; void TeleopPeriodic() override; - void TestPeriodic() override; + void UtilityPeriodic() override; private: // Have it null by default so that if testing teleop it diff --git a/wpilibcExamples/src/main/cpp/templates/commandv2/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/commandv2/cpp/Robot.cpp index 044ead3a30..9af2838a50 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandv2/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/commandv2/cpp/Robot.cpp @@ -11,7 +11,7 @@ Robot::Robot() {} /** * This function is called every 20 ms, no matter the mode. Use * this for items like diagnostics that you want to run during disabled, - * autonomous, teleoperated and test. + * autonomous, teleoperated and utility. * *

This runs after the mode specific periodic functions, but before * LiveWindow and SmartDashboard integrated updating. @@ -60,9 +60,9 @@ void Robot::TeleopInit() { void Robot::TeleopPeriodic() {} /** - * This function is called periodically during test mode. + * This function is called periodically during utility mode. */ -void Robot::TestPeriodic() {} +void Robot::UtilityPeriodic() {} /** * This function is called once when the robot is first started up. diff --git a/wpilibcExamples/src/main/cpp/templates/commandv2/include/Robot.hpp b/wpilibcExamples/src/main/cpp/templates/commandv2/include/Robot.hpp index b50f260d36..9c2241d1e1 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandv2/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/templates/commandv2/include/Robot.hpp @@ -20,7 +20,7 @@ class Robot : public wpi::TimedRobot { void AutonomousPeriodic() override; void TeleopInit() override; void TeleopPeriodic() override; - void TestPeriodic() override; + void UtilityPeriodic() override; void SimulationInit() override; void SimulationPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/templates/commandv2skeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/commandv2skeleton/cpp/Robot.cpp index 82be3ea945..3dd2cac83b 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandv2skeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/commandv2skeleton/cpp/Robot.cpp @@ -41,13 +41,13 @@ void Robot::TeleopPeriodic() {} void Robot::TeleopExit() {} -void Robot::TestInit() { +void Robot::UtilityInit() { wpi::cmd::CommandScheduler::GetInstance().CancelAll(); } -void Robot::TestPeriodic() {} +void Robot::UtilityPeriodic() {} -void Robot::TestExit() {} +void Robot::UtilityExit() {} #ifndef RUNNING_WPILIB_TESTS int main() { diff --git a/wpilibcExamples/src/main/cpp/templates/commandv2skeleton/include/Robot.hpp b/wpilibcExamples/src/main/cpp/templates/commandv2skeleton/include/Robot.hpp index ec88e140da..523b71406d 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandv2skeleton/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/templates/commandv2skeleton/include/Robot.hpp @@ -23,9 +23,9 @@ class Robot : public wpi::TimedRobot { void TeleopInit() override; void TeleopPeriodic() override; void TeleopExit() override; - void TestInit() override; - void TestPeriodic() override; - void TestExit() override; + void UtilityInit() override; + void UtilityPeriodic() override; + void UtilityExit() override; private: std::optional m_autonomousCommand; diff --git a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp index 3f510c8213..dc4d55139d 100644 --- a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp @@ -17,7 +17,7 @@ void Robot::Autonomous() {} void Robot::Teleop() {} -void Robot::Test() {} +void Robot::Utility() {} void Robot::StartCompetition() { wpi::internal::DriverStationModeThread modeThread{wpi::hal::GetControlWord()}; @@ -25,7 +25,7 @@ void Robot::StartCompetition() { // Create an opmode per robot mode wpi::RobotState::AddOpMode(wpi::RobotMode::AUTONOMOUS, "Auto"); wpi::RobotState::AddOpMode(wpi::RobotMode::TELEOPERATED, "Teleop"); - wpi::RobotState::AddOpMode(wpi::RobotMode::TEST, "Test"); + wpi::RobotState::AddOpMode(wpi::RobotMode::UTILITY, "Utility"); wpi::RobotState::PublishOpModes(); wpi::util::Event event{false, false}; @@ -47,9 +47,9 @@ void Robot::StartCompetition() { while (IsAutonomousEnabled()) { wpi::util::WaitForObject(event.GetHandle()); } - } else if (IsTest()) { - Test(); - while (IsTest() && IsEnabled()) { + } else if (IsUtility()) { + Utility(); + while (IsUtility() && IsEnabled()) { wpi::util::WaitForObject(event.GetHandle()); } } else { diff --git a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/include/Robot.hpp b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/include/Robot.hpp index a4399e3aec..a7504220ae 100644 --- a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/include/Robot.hpp @@ -14,7 +14,7 @@ class Robot : public wpi::RobotBase { void Disabled(); void Autonomous(); void Teleop(); - void Test(); + void Utility(); void StartCompetition() override; void EndCompetition() override; diff --git a/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp index 3d3fb611d9..6c8203f36f 100644 --- a/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp @@ -16,7 +16,7 @@ Robot::Robot() { /** * This function is called every 20 ms, no matter the mode. Use * this for items like diagnostics that you want ran during disabled, - * autonomous, teleoperated and test. + * autonomous, teleoperated and utility. * *

This runs after the mode specific periodic functions, but before * LiveWindow and SmartDashboard integrated updating. @@ -63,9 +63,9 @@ void Robot::DisabledInit() {} void Robot::DisabledPeriodic() {} -void Robot::TestInit() {} +void Robot::UtilityInit() {} -void Robot::TestPeriodic() {} +void Robot::UtilityPeriodic() {} void Robot::SimulationInit() {} diff --git a/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.hpp b/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.hpp index 8b03088c80..df91834109 100644 --- a/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.hpp @@ -19,8 +19,8 @@ class Robot : public wpi::TimedRobot { void TeleopPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; - void TestInit() override; - void TestPeriodic() override; + void UtilityInit() override; + void UtilityPeriodic() override; void SimulationInit() override; void SimulationPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp index 49b37d776d..39337d3456 100644 --- a/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp @@ -16,8 +16,8 @@ void Robot::TeleopPeriodic() {} void Robot::DisabledInit() {} void Robot::DisabledPeriodic() {} -void Robot::TestInit() {} -void Robot::TestPeriodic() {} +void Robot::UtilityInit() {} +void Robot::UtilityPeriodic() {} void Robot::SimulationInit() {} void Robot::SimulationPeriodic() {} diff --git a/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.hpp b/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.hpp index 92ce08434d..db14d9db48 100644 --- a/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.hpp @@ -20,8 +20,8 @@ class Robot : public wpi::TimedRobot { void DisabledInit() override; void DisabledPeriodic() override; - void TestInit() override; - void TestPeriodic() override; + void UtilityInit() override; + void UtilityPeriodic() override; void SimulationInit() override; void SimulationPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp index 5c4f300f80..ef489a9f02 100644 --- a/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp @@ -74,9 +74,9 @@ void Robot::DisabledInit() {} void Robot::DisabledPeriodic() {} -void Robot::TestInit() {} +void Robot::UtilityInit() {} -void Robot::TestPeriodic() {} +void Robot::UtilityPeriodic() {} #ifndef RUNNING_WPILIB_TESTS int main() { diff --git a/wpilibcExamples/src/main/cpp/templates/timeslice/include/Robot.hpp b/wpilibcExamples/src/main/cpp/templates/timeslice/include/Robot.hpp index 35cb7ebd47..7921465de8 100644 --- a/wpilibcExamples/src/main/cpp/templates/timeslice/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/templates/timeslice/include/Robot.hpp @@ -19,8 +19,8 @@ class Robot : public wpi::TimesliceRobot { void TeleopPeriodic() override; void DisabledInit() override; void DisabledPeriodic() override; - void TestInit() override; - void TestPeriodic() override; + void UtilityInit() override; + void UtilityPeriodic() override; private: wpi::SendableChooser m_chooser; diff --git a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp index bfc19469e1..f4c966c9a7 100644 --- a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp @@ -28,8 +28,8 @@ void Robot::TeleopPeriodic() {} void Robot::DisabledInit() {} void Robot::DisabledPeriodic() {} -void Robot::TestInit() {} -void Robot::TestPeriodic() {} +void Robot::UtilityInit() {} +void Robot::UtilityPeriodic() {} #ifndef RUNNING_WPILIB_TESTS int main() { diff --git a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/include/Robot.hpp b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/include/Robot.hpp index 70ff2f93c2..4b64036672 100644 --- a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/include/Robot.hpp @@ -21,6 +21,6 @@ class Robot : public wpi::TimesliceRobot { void DisabledInit() override; void DisabledPeriodic() override; - void TestInit() override; - void TestPeriodic() override; + void UtilityInit() override; + void UtilityPeriodic() override; }; diff --git a/wpilibj/src/main/java/org/wpilib/driverstation/RobotState.java b/wpilibj/src/main/java/org/wpilib/driverstation/RobotState.java index 142c79ba67..172d86cfeb 100644 --- a/wpilibj/src/main/java/org/wpilib/driverstation/RobotState.java +++ b/wpilibj/src/main/java/org/wpilib/driverstation/RobotState.java @@ -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(); } /** diff --git a/wpilibj/src/main/java/org/wpilib/driverstation/internal/DriverStationBackend.java b/wpilibj/src/main/java/org/wpilib/driverstation/internal/DriverStationBackend.java index ff4964dfc1..cd74c2c555 100644 --- a/wpilibj/src/main/java/org/wpilib/driverstation/internal/DriverStationBackend.java +++ b/wpilibj/src/main/java/org/wpilib/driverstation/internal/DriverStationBackend.java @@ -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(); } diff --git a/wpilibj/src/main/java/org/wpilib/framework/IterativeRobotBase.java b/wpilibj/src/main/java/org/wpilib/framework/IterativeRobotBase.java index b8a2a42e89..152566163b 100644 --- a/wpilibj/src/main/java/org/wpilib/framework/IterativeRobotBase.java +++ b/wpilibj/src/main/java/org/wpilib/framework/IterativeRobotBase.java @@ -33,7 +33,7 @@ import org.wpilib.system.Watchdog; *

  • disabledInit() -- called each and every time disabled is entered from another mode *
  • autonomousInit() -- called each and every time autonomous is entered from another mode *
  • teleopInit() -- called each and every time teleop is entered from another mode - *
  • testInit() -- called each and every time test is entered from another mode + *
  • utilityInit() -- called each and every time utility is entered from another mode * * *

    periodic() functions -- each of these functions is called on an interval: @@ -43,7 +43,7 @@ import org.wpilib.system.Watchdog; *

  • disabledPeriodic() *
  • autonomousPeriodic() *
  • teleopPeriodic() - *
  • testPeriodic() + *
  • utilityPeriodic() * * *

    exit() functions -- each of the following functions is called once when the appropriate mode @@ -53,7 +53,7 @@ import org.wpilib.system.Watchdog; *

  • disabledExit() -- called each and every time disabled is exited *
  • autonomousExit() -- called each and every time autonomous is exited *
  • teleopExit() -- called each and every time teleop is exited - *
  • testExit() -- called each and every time test is exited + *
  • utilityExit() -- called each and every time utility is exited * */ 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. * *

    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. * *

    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 diff --git a/wpilibj/src/main/java/org/wpilib/framework/OpModeRobot.java b/wpilibj/src/main/java/org/wpilib/framework/OpModeRobot.java index f652d391e2..0746f5c531 100644 --- a/wpilibj/src/main/java/org/wpilib/framework/OpModeRobot.java +++ b/wpilibj/src/main/java/org/wpilib/framework/OpModeRobot.java @@ -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; * *

    The OpModeRobot class is intended to be subclassed by a user creating a robot program. * - *

    Classes annotated with {@link Autonomous}, {@link Teleop}, and {@link TestOpMode} in the same + *

    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. * *

    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 cls, Autonomous auto, Teleop teleop, TestOpMode test) { + Class 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 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 diff --git a/wpilibj/src/main/java/org/wpilib/framework/RobotBase.java b/wpilibj/src/main/java/org/wpilib/framework/RobotBase.java index 5bf286a833..16aef6abe9 100644 --- a/wpilibj/src/main/java/org/wpilib/framework/RobotBase.java +++ b/wpilibj/src/main/java/org/wpilib/framework/RobotBase.java @@ -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(); } /** diff --git a/wpilibj/src/main/java/org/wpilib/hardware/motor/MotorSafety.java b/wpilibj/src/main/java/org/wpilib/hardware/motor/MotorSafety.java index 055c31f99f..632d40d0c6 100644 --- a/wpilibj/src/main/java/org/wpilib/hardware/motor/MotorSafety.java +++ b/wpilibj/src/main/java/org/wpilib/hardware/motor/MotorSafety.java @@ -134,7 +134,7 @@ public abstract class MotorSafety { stopTime = m_stopTime; } - if (!enabled || RobotState.isDisabled() || RobotState.isTest()) { + if (!enabled || RobotState.isDisabled() || RobotState.isUtility()) { return; } diff --git a/wpilibj/src/main/java/org/wpilib/opmode/TestOpMode.java b/wpilibj/src/main/java/org/wpilib/opmode/Utility.java similarity index 87% rename from wpilibj/src/main/java/org/wpilib/opmode/TestOpMode.java rename to wpilibj/src/main/java/org/wpilib/opmode/Utility.java index a8597b1e57..e32e6ad207 100644 --- a/wpilibj/src/main/java/org/wpilib/opmode/TestOpMode.java +++ b/wpilibj/src/main/java/org/wpilib/opmode/Utility.java @@ -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 */ diff --git a/wpilibj/src/test/java/org/wpilib/MockHardwareExtension.java b/wpilibj/src/test/java/org/wpilib/MockHardwareExtension.java index 2bea975b53..a4c660514c 100644 --- a/wpilibj/src/test/java/org/wpilib/MockHardwareExtension.java +++ b/wpilibj/src/test/java/org/wpilib/MockHardwareExtension.java @@ -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); } } diff --git a/wpilibj/src/test/java/org/wpilib/framework/OpModeRobotTest.java b/wpilibj/src/test/java/org/wpilib/framework/OpModeRobotTest.java index 482805336f..74c4c5fcf0 100644 --- a/wpilibj/src/test/java/org/wpilib/framework/OpModeRobotTest.java +++ b/wpilibj/src/test/java/org/wpilib/framework/OpModeRobotTest.java @@ -125,7 +125,7 @@ class OpModeRobotTest { Color.BLACK); addOpModeFactory( () -> new OneArgOpMode(this), - RobotMode.TEST, + RobotMode.UTILITY, "OneArgOpMode-Test", "Group", "Description", diff --git a/wpilibj/src/test/java/org/wpilib/framework/TimedRobotTest.java b/wpilibj/src/test/java/org/wpilib/framework/TimedRobotTest.java index 414fabdce4..c90e0a83b9 100644 --- a/wpilibj/src/test/java/org/wpilib/framework/TimedRobotTest.java +++ b/wpilibj/src/test/java/org/wpilib/framework/TimedRobotTest.java @@ -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 { diff --git a/wpilibj/src/test/java/org/wpilib/simulation/DriverStationSimTest.java b/wpilibj/src/test/java/org/wpilib/simulation/DriverStationSimTest.java index c6a6d4dcc7..915f5fe36a 100644 --- a/wpilibj/src/test/java/org/wpilib/simulation/DriverStationSimTest.java +++ b/wpilibj/src/test/java/org/wpilib/simulation/DriverStationSimTest.java @@ -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()); } } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/drivedistanceoffboard/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/drivedistanceoffboard/Robot.java index 03655e2944..24cf9b7666 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/drivedistanceoffboard/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/drivedistanceoffboard/Robot.java @@ -89,12 +89,12 @@ public class Robot extends TimedRobot { public void teleopPeriodic() {} @Override - public void testInit() { - // Cancels all running commands at the start of test mode. + public void utilityInit() { + // Cancels all running commands at the start of utility mode. CommandScheduler.getInstance().cancelAll(); } - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/gettingstarted/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/gettingstarted/Robot.java index 52ad3f2935..cc682b641f 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/gettingstarted/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/gettingstarted/Robot.java @@ -63,11 +63,11 @@ public class Robot extends TimedRobot { m_robotDrive.arcadeDrive(-m_controller.getLeftY(), -m_controller.getRightX()); } - /** This function is called once each time the robot enters test mode. */ + /** This function is called once each time the robot enters utility mode. */ @Override - public void testInit() {} + public void utilityInit() {} - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotinlined/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotinlined/Robot.java index 87f3711b11..634bf9d8d0 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotinlined/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotinlined/Robot.java @@ -91,12 +91,12 @@ public class Robot extends TimedRobot { public void teleopPeriodic() {} @Override - public void testInit() { - // Cancels all running commands at the start of test mode. + public void utilityInit() { + // Cancels all running commands at the start of utility mode. CommandScheduler.getInstance().cancelAll(); } - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbottraditional/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbottraditional/Robot.java index 97e9867501..ccab66ed8b 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbottraditional/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbottraditional/Robot.java @@ -39,7 +39,7 @@ public class Robot extends TimedRobot { /** * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics - * that you want ran during disabled, autonomous, teleoperated and test. + * that you want ran during disabled, autonomous, teleoperated and utility. * *

    This runs after the mode specific periodic functions, but before LiveWindow and * SmartDashboard integrated updating. @@ -98,12 +98,12 @@ public class Robot extends TimedRobot { public void teleopPeriodic() {} @Override - public void testInit() { - // Cancels all running commands at the start of test mode. + public void utilityInit() { + // Cancels all running commands at the start of utility mode. CommandScheduler.getInstance().cancelAll(); } - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/Robot.java index 94acc47779..62060dcc70 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/Robot.java @@ -87,12 +87,12 @@ public class Robot extends TimedRobot { public void teleopPeriodic() {} @Override - public void testInit() { - // Cancels all running commands at the start of test mode. + public void utilityInit() { + // Cancels all running commands at the start of utility mode. CommandScheduler.getInstance().cancelAll(); } - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/romireference/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/romireference/Robot.java index 1d60fba5b5..15e6eac312 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/romireference/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/romireference/Robot.java @@ -82,12 +82,12 @@ public class Robot extends TimedRobot { public void teleopPeriodic() {} @Override - public void testInit() { - // Cancels all running commands at the start of test mode. + public void utilityInit() { + // Cancels all running commands at the start of utility mode. CommandScheduler.getInstance().cancelAll(); } - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/sysidroutine/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/sysidroutine/Robot.java index d8a481ee67..161c0b0d1c 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/sysidroutine/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/sysidroutine/Robot.java @@ -79,12 +79,12 @@ public class Robot extends TimedRobot { public void teleopPeriodic() {} @Override - public void testInit() { - // Cancels all running commands at the start of test mode. + public void utilityInit() { + // Cancels all running commands at the start of utility mode. CommandScheduler.getInstance().cancelAll(); } - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/xrpreference/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/xrpreference/Robot.java index fe5eebebf0..312b0d8e89 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/xrpreference/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/xrpreference/Robot.java @@ -82,14 +82,14 @@ public class Robot extends TimedRobot { public void teleopPeriodic() {} @Override - public void testInit() { - // Cancels all running commands at the start of test mode. + public void utilityInit() { + // Cancels all running commands at the start of utility mode. CommandScheduler.getInstance().cancelAll(); } - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} /** This function is called once when the robot is first started up. */ @Override diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/xrptimed/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/xrptimed/Robot.java index 8a6d8feff0..8a2dd0e999 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/xrptimed/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/xrptimed/Robot.java @@ -64,11 +64,11 @@ public class Robot extends TimedRobot { m_robotDrive.arcadeDrive(-m_controller.getRawAxis(2), -m_controller.getRawAxis(1)); } - /** This function is called once each time the robot enters test mode. */ + /** This function is called once each time the robot enters utility mode. */ @Override - public void testInit() {} + public void utilityInit() {} - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/snippets/selectcommand/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/snippets/selectcommand/Robot.java index 1dbc7b6036..ec7b3718a0 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/snippets/selectcommand/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/snippets/selectcommand/Robot.java @@ -30,7 +30,7 @@ public class Robot extends TimedRobot { /** * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics - * that you want ran during disabled, autonomous, teleoperated and test. + * that you want ran during disabled, autonomous, teleoperated and utility. * *

    This runs after the mode specific periodic functions, but before LiveWindow and * SmartDashboard integrated updating. @@ -89,12 +89,12 @@ public class Robot extends TimedRobot { public void teleopPeriodic() {} @Override - public void testInit() { - // Cancels all running commands at the start of test mode. + public void utilityInit() { + // Cancels all running commands at the start of utility mode. CommandScheduler.getInstance().cancelAll(); } - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/commandv2/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/templates/commandv2/Robot.java index 073a1d17fd..c0ecbb3eb0 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/commandv2/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/commandv2/Robot.java @@ -30,7 +30,7 @@ public class Robot extends TimedRobot { /** * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics - * that you want ran during disabled, autonomous, teleoperated and test. + * that you want ran during disabled, autonomous, teleoperated and utility. * *

    This runs after the mode specific periodic functions, but before LiveWindow and * SmartDashboard integrated updating. @@ -82,14 +82,14 @@ public class Robot extends TimedRobot { public void teleopPeriodic() {} @Override - public void testInit() { - // Cancels all running commands at the start of test mode. + public void utilityInit() { + // Cancels all running commands at the start of utility mode. CommandScheduler.getInstance().cancelAll(); } - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} /** This function is called once when the robot is first started up. */ @Override diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/commandv2skeleton/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/templates/commandv2skeleton/Robot.java index 72bef51a34..58c83afcad 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/commandv2skeleton/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/commandv2skeleton/Robot.java @@ -60,13 +60,13 @@ public class Robot extends TimedRobot { public void teleopExit() {} @Override - public void testInit() { + public void utilityInit() { CommandScheduler.getInstance().cancelAll(); } @Override - public void testPeriodic() {} + public void utilityPeriodic() {} @Override - public void testExit() {} + public void utilityExit() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/educational/EducationalRobot.java b/wpilibjExamples/src/main/java/org/wpilib/templates/educational/EducationalRobot.java index e3b57d5bd3..2c75aafce0 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/educational/EducationalRobot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/educational/EducationalRobot.java @@ -28,7 +28,7 @@ public class EducationalRobot extends RobotBase { run(); } - public void test() { + public void utility() { run(); } @@ -39,7 +39,7 @@ public class EducationalRobot extends RobotBase { // Create an opmode per robot mode RobotState.addOpMode(RobotMode.AUTONOMOUS, "Auto"); RobotState.addOpMode(RobotMode.TELEOPERATED, "Teleop"); - RobotState.addOpMode(RobotMode.TEST, "Test"); + RobotState.addOpMode(RobotMode.UTILITY, "Utility"); RobotState.publishOpModes(); final ControlWord word = new ControlWord(); @@ -73,9 +73,9 @@ public class EducationalRobot extends RobotBase { Thread.currentThread().interrupt(); } } - } else if (isTest()) { - test(); - while (isTest() && isEnabled()) { + } else if (isUtility()) { + utility(); + while (isUtility() && isEnabled()) { try { WPIUtilJNI.waitForObject(event); } catch (InterruptedException e) { diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/robotbaseskeleton/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/templates/robotbaseskeleton/Robot.java index 965d7e5f85..135ab43cb7 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/robotbaseskeleton/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/robotbaseskeleton/Robot.java @@ -25,7 +25,7 @@ public class Robot extends RobotBase { public void teleop() {} - public void test() {} + public void utility() {} private volatile boolean m_exit; @@ -34,7 +34,7 @@ public class Robot extends RobotBase { // Create an opmode per robot mode RobotState.addOpMode(RobotMode.AUTONOMOUS, "Auto"); RobotState.addOpMode(RobotMode.TELEOPERATED, "Teleop"); - RobotState.addOpMode(RobotMode.TEST, "Test"); + RobotState.addOpMode(RobotMode.UTILITY, "Utility"); RobotState.publishOpModes(); final ControlWord word = new ControlWord(); @@ -68,9 +68,9 @@ public class Robot extends RobotBase { Thread.currentThread().interrupt(); } } - } else if (isTest()) { - test(); - while (isTest() && isEnabled()) { + } else if (isUtility()) { + utility(); + while (isUtility() && isEnabled()) { try { WPIUtilJNI.waitForObject(event); } catch (InterruptedException e) { diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/romicommandv2/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/templates/romicommandv2/Robot.java index d7066d97bc..fbe78e7c39 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/romicommandv2/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/romicommandv2/Robot.java @@ -30,7 +30,7 @@ public class Robot extends TimedRobot { /** * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics - * that you want ran during disabled, autonomous, teleoperated and test. + * that you want ran during disabled, autonomous, teleoperated and utility. * *

    This runs after the mode specific periodic functions, but before LiveWindow and * SmartDashboard integrated updating. @@ -82,12 +82,12 @@ public class Robot extends TimedRobot { public void teleopPeriodic() {} @Override - public void testInit() { - // Cancels all running commands at the start of test mode. + public void utilityInit() { + // Cancels all running commands at the start of utility mode. CommandScheduler.getInstance().cancelAll(); } - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/romieducational/EducationalRobot.java b/wpilibjExamples/src/main/java/org/wpilib/templates/romieducational/EducationalRobot.java index a549f66dc4..5041fb9df7 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/romieducational/EducationalRobot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/romieducational/EducationalRobot.java @@ -28,7 +28,7 @@ public class EducationalRobot extends RobotBase { run(); } - public void test() { + public void utility() { run(); } @@ -39,7 +39,7 @@ public class EducationalRobot extends RobotBase { // Create an opmode per robot mode RobotState.addOpMode(RobotMode.AUTONOMOUS, "Auto"); RobotState.addOpMode(RobotMode.TELEOPERATED, "Teleop"); - RobotState.addOpMode(RobotMode.TEST, "Test"); + RobotState.addOpMode(RobotMode.UTILITY, "Utility"); RobotState.publishOpModes(); final ControlWord word = new ControlWord(); @@ -73,9 +73,9 @@ public class EducationalRobot extends RobotBase { Thread.currentThread().interrupt(); } } - } else if (isTest()) { - test(); - while (isTest() && isEnabled()) { + } else if (isUtility()) { + utility(); + while (isUtility() && isEnabled()) { try { WPIUtilJNI.waitForObject(event); } catch (InterruptedException e) { diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/romitimed/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/templates/romitimed/Robot.java index 7654f6cd66..61e52bdde8 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/romitimed/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/romitimed/Robot.java @@ -33,7 +33,7 @@ public class Robot extends TimedRobot { /** * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics - * that you want ran during disabled, autonomous, teleoperated and test. + * that you want ran during disabled, autonomous, teleoperated and utility. * *

    This runs after the mode specific periodic functions, but before LiveWindow and * SmartDashboard integrated updating. @@ -90,11 +90,11 @@ public class Robot extends TimedRobot { @Override public void disabledPeriodic() {} - /** This function is called once when test mode is enabled. */ + /** This function is called once when utility mode is enabled. */ @Override - public void testInit() {} + public void utilityInit() {} - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/timed/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/templates/timed/Robot.java index 11c7bb933c..605d85de96 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/timed/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/timed/Robot.java @@ -31,7 +31,7 @@ public class Robot extends TimedRobot { /** * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics - * that you want ran during disabled, autonomous, teleoperated and test. + * that you want ran during disabled, autonomous, teleoperated and utility. * *

    This runs after the mode specific periodic functions, but before LiveWindow and * SmartDashboard integrated updating. @@ -86,13 +86,13 @@ public class Robot extends TimedRobot { @Override public void disabledPeriodic() {} - /** This function is called once when test mode is enabled. */ + /** This function is called once when utility mode is enabled. */ @Override - public void testInit() {} + public void utilityInit() {} - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} /** This function is called once when the robot is first started up. */ @Override diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/timedskeleton/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/templates/timedskeleton/Robot.java index e3dbac296e..16265fa8fc 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/timedskeleton/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/timedskeleton/Robot.java @@ -40,10 +40,10 @@ public class Robot extends TimedRobot { public void disabledPeriodic() {} @Override - public void testInit() {} + public void utilityInit() {} @Override - public void testPeriodic() {} + public void utilityPeriodic() {} @Override public void simulationInit() {} diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/timeslice/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/templates/timeslice/Robot.java index c1633973f0..6c510a1923 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/timeslice/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/timeslice/Robot.java @@ -40,7 +40,7 @@ public class Robot extends TimesliceRobot { /** * This function is called every robot packet, no matter the mode. Use this for items like - * diagnostics that you want ran during disabled, autonomous, teleoperated and test. + * diagnostics that you want ran during disabled, autonomous, teleoperated and utility. * *

    This runs after the mode specific periodic functions, but before LiveWindow and * SmartDashboard integrated updating. @@ -95,11 +95,11 @@ public class Robot extends TimesliceRobot { @Override public void disabledPeriodic() {} - /** This function is called once when test mode is enabled. */ + /** This function is called once when utility mode is enabled. */ @Override - public void testInit() {} + public void utilityInit() {} - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/timesliceskeleton/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/templates/timesliceskeleton/Robot.java index a2bf0fe25e..54f930c8ef 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/timesliceskeleton/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/timesliceskeleton/Robot.java @@ -50,8 +50,8 @@ public class Robot extends TimesliceRobot { public void disabledPeriodic() {} @Override - public void testInit() {} + public void utilityInit() {} @Override - public void testPeriodic() {} + public void utilityPeriodic() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/xrpcommandv2/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/templates/xrpcommandv2/Robot.java index db3eeb210c..9044b98232 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/xrpcommandv2/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/xrpcommandv2/Robot.java @@ -30,7 +30,7 @@ public class Robot extends TimedRobot { /** * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics - * that you want ran during disabled, autonomous, teleoperated and test. + * that you want ran during disabled, autonomous, teleoperated and utility. * *

    This runs after the mode specific periodic functions, but before LiveWindow and * SmartDashboard integrated updating. @@ -82,12 +82,12 @@ public class Robot extends TimedRobot { public void teleopPeriodic() {} @Override - public void testInit() { - // Cancels all running commands at the start of test mode. + public void utilityInit() { + // Cancels all running commands at the start of utility mode. CommandScheduler.getInstance().cancelAll(); } - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} } diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/xrpeducational/EducationalRobot.java b/wpilibjExamples/src/main/java/org/wpilib/templates/xrpeducational/EducationalRobot.java index 96b83978dd..b200d25884 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/xrpeducational/EducationalRobot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/xrpeducational/EducationalRobot.java @@ -28,7 +28,7 @@ public class EducationalRobot extends RobotBase { run(); } - public void test() { + public void utility() { run(); } @@ -39,7 +39,7 @@ public class EducationalRobot extends RobotBase { // Create an opmode per robot mode RobotState.addOpMode(RobotMode.AUTONOMOUS, "Auto"); RobotState.addOpMode(RobotMode.TELEOPERATED, "Teleop"); - RobotState.addOpMode(RobotMode.TEST, "Test"); + RobotState.addOpMode(RobotMode.UTILITY, "Utility"); RobotState.publishOpModes(); final ControlWord word = new ControlWord(); @@ -73,9 +73,9 @@ public class EducationalRobot extends RobotBase { Thread.currentThread().interrupt(); } } - } else if (isTest()) { - test(); - while (isTest() && isEnabled()) { + } else if (isUtility()) { + utility(); + while (isUtility() && isEnabled()) { try { WPIUtilJNI.waitForObject(event); } catch (InterruptedException e) { diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/xrptimed/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/templates/xrptimed/Robot.java index c2d957f3b1..98c0d13080 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/xrptimed/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/xrptimed/Robot.java @@ -33,7 +33,7 @@ public class Robot extends TimedRobot { /** * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics - * that you want ran during disabled, autonomous, teleoperated and test. + * that you want ran during disabled, autonomous, teleoperated and utility. * *

    This runs after the mode specific periodic functions, but before LiveWindow and * SmartDashboard integrated updating. @@ -90,11 +90,11 @@ public class Robot extends TimedRobot { @Override public void disabledPeriodic() {} - /** This function is called once when test mode is enabled. */ + /** This function is called once when utility mode is enabled. */ @Override - public void testInit() {} + public void utilityInit() {} - /** This function is called periodically during test mode. */ + /** This function is called periodically during utility mode. */ @Override - public void testPeriodic() {} + public void utilityPeriodic() {} }