Skip to content

Commit 07940c3

Browse files
committed
Add builtin robot tests that exercise all opmodes
- Fixes #220
1 parent 1baf93a commit 07940c3

File tree

3 files changed

+150
-1
lines changed

3 files changed

+150
-1
lines changed

subprojects/robotpy-wpilib/tests/test_pytest_plugins.py

Lines changed: 73 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
def _make_robot_module(pytester):
88
pytester.makepyfile(robot_module="""
99
import wpilib
10+
from hal import RobotMode
1011
1112
1213
class DummyRobot(wpilib.TimedRobot):
@@ -50,6 +51,42 @@ def teleopInit(self):
5051
def teleopPeriodic(self):
5152
self.did_teleop_periodic = True
5253
54+
55+
class OpModeAuto(wpilib.OpMode):
56+
label = "OpModeAuto"
57+
58+
def __init__(self, robot):
59+
super().__init__()
60+
self._robot = robot
61+
62+
def opModeRun(self, op_mode_id: int):
63+
self._robot.opmode_test_observed.add(self.label)
64+
65+
def opModeStop(self):
66+
pass
67+
68+
69+
class OpModeTeleop(wpilib.OpMode):
70+
label = "OpModeTeleop"
71+
72+
def __init__(self, robot):
73+
super().__init__()
74+
self._robot = robot
75+
76+
def opModeRun(self, op_mode_id: int):
77+
self._robot.opmode_test_observed.add(self.label)
78+
79+
def opModeStop(self):
80+
pass
81+
82+
83+
class OpModeDemoRobot(wpilib.OpModeRobot):
84+
def __init__(self):
85+
super().__init__()
86+
self.opmode_test_observed = set()
87+
self.addOpMode(OpModeAuto, RobotMode.AUTONOMOUS, "OpModeAuto")
88+
self.addOpMode(OpModeTeleop, RobotMode.TELEOPERATED, "OpModeTeleop")
89+
self.publishOpModes()
5390
""")
5491

5592

@@ -275,7 +312,42 @@ def test_builtin_tests_module(pytester, isolated):
275312

276313
result = pytester.runpytest_subprocess("-q")
277314

278-
result.assert_outcomes(passed=4)
315+
result.assert_outcomes(passed=4, skipped=1)
316+
317+
318+
@pytest.mark.parametrize("isolated", [False, True])
319+
def test_builtin_tests_module_opmode(pytester, isolated):
320+
_make_robot_module(pytester)
321+
if isolated:
322+
_configure_isolated_plugin(pytester, robot_class="OpModeDemoRobot")
323+
else:
324+
_configure_robot_testing_plugin(pytester, robot_class="OpModeDemoRobot")
325+
pytester.makepyfile(pyfrc_test="from wpilib.testing.robot_tests import *\n")
326+
327+
result = pytester.runpytest_subprocess("-q")
328+
329+
result.assert_outcomes(passed=5)
330+
331+
332+
@pytest.mark.parametrize("isolated", [False, True])
333+
def test_opmode_robot_runs_opmodes(pytester, isolated):
334+
_make_robot_module(pytester)
335+
if isolated:
336+
_configure_isolated_plugin(pytester, robot_class="OpModeDemoRobot")
337+
else:
338+
_configure_robot_testing_plugin(pytester, robot_class="OpModeDemoRobot")
339+
pytester.makepyfile(test_robot="""
340+
from wpilib.testing.robot_tests import test_all_opmodes
341+
342+
343+
def test_opmodes_run(robot, control):
344+
test_all_opmodes(control)
345+
assert robot.opmode_test_observed == {"OpModeAuto", "OpModeTeleop"}
346+
""")
347+
348+
result = pytester.runpytest_subprocess("-q")
349+
350+
result.assert_outcomes(passed=2)
279351

280352

281353
def _run_robot_suite(pytester, isolated, robot_class, test_source, *args):

subprojects/robotpy-wpilib/wpilib/testing/pytest_plugin.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,9 @@ def robot(self):
7676
wpilib.DriverStation.silenceJoystickConnectionWarning(True)
7777
DriverStationSim.setRobotMode(RobotMode.AUTONOMOUS)
7878
DriverStationSim.setEnabled(False)
79+
DriverStationSim.setOpMode(0)
7980
DriverStationSim.notifyNewData()
81+
wpilib.DriverStation.clearOpModes()
8082

8183
# Create the user's robot instance
8284
robot = self._robot_class()

subprojects/robotpy-wpilib/wpilib/testing/robot_tests.py

Lines changed: 75 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,45 @@
1212

1313
import pytest
1414

15+
import wpilib
16+
from hal._wpiHal import _RobotMode as RobotMode
17+
from hal._wpiHal import opMode_GetRobotMode
18+
from wpilib.simulation import DriverStationSim, stepTiming
19+
1520
from .controller import RobotTestController
1621

1722

23+
def _step_timing_with_mode(
24+
control: RobotTestController,
25+
*,
26+
seconds: float,
27+
robot_mode: RobotMode,
28+
enabled: bool,
29+
assert_alive: bool = True,
30+
record_opmode_ids: set[int] | None = None,
31+
) -> float:
32+
"""Step simulation time while explicitly setting the robot mode."""
33+
34+
assert control.robot_is_alive, "did you call control.run_robot()?"
35+
assert seconds > 0
36+
37+
DriverStationSim.setDsAttached(True)
38+
DriverStationSim.setRobotMode(robot_mode)
39+
DriverStationSim.setEnabled(enabled)
40+
41+
tm = 0.0
42+
while tm < seconds + 0.01:
43+
DriverStationSim.notifyNewData()
44+
stepTiming(0.2)
45+
if record_opmode_ids is not None:
46+
record_opmode_ids.add(wpilib.DriverStation.getOpModeId())
47+
if assert_alive:
48+
assert control.robot_is_alive
49+
tm += 0.2
50+
51+
return tm
52+
53+
1854
def test_autonomous(control: RobotTestController):
1955
"""Runs autonomous mode by itself"""
2056

@@ -72,3 +108,42 @@ def test_practice(control: RobotTestController):
72108

73109
# Run teleop + enabled for 2 minutes
74110
control.step_timing(seconds=120, autonomous=False, enabled=True)
111+
112+
113+
@pytest.mark.filterwarnings("ignore")
114+
def test_all_opmodes(control: RobotTestController):
115+
"""Runs each registered opmode briefly."""
116+
117+
with control.run_robot():
118+
opmodes = DriverStationSim.getOpModeOptions()
119+
if len(opmodes) == 0:
120+
pytest.skip("robot did not register opmodes")
121+
122+
selected = []
123+
seen = set()
124+
for opmode in reversed(opmodes):
125+
mode = opMode_GetRobotMode(opmode.id)
126+
if mode == RobotMode.UNKNOWN:
127+
continue
128+
key = (opmode.name, mode)
129+
if key in seen:
130+
continue
131+
seen.add(key)
132+
selected.append((opmode, mode))
133+
134+
for opmode, mode in reversed(selected):
135+
DriverStationSim.setOpMode(opmode.id)
136+
137+
_step_timing_with_mode(control, seconds=0.5, robot_mode=mode, enabled=False)
138+
opmode_ids = set()
139+
_step_timing_with_mode(
140+
control,
141+
seconds=2.0,
142+
robot_mode=mode,
143+
enabled=True,
144+
record_opmode_ids=opmode_ids,
145+
)
146+
_step_timing_with_mode(control, seconds=0.5, robot_mode=mode, enabled=False)
147+
assert (
148+
opmode.id in opmode_ids
149+
), f"opmode {opmode.name} ({opmode.id}) did not run"

0 commit comments

Comments
 (0)