Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
74 changes: 73 additions & 1 deletion subprojects/robotpy-wpilib/tests/test_pytest_plugins.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
def _make_robot_module(pytester):
pytester.makepyfile(robot_module="""
import wpilib
from hal import RobotMode


class DummyRobot(wpilib.TimedRobot):
Expand Down Expand Up @@ -50,6 +51,42 @@ def teleopInit(self):
def teleopPeriodic(self):
self.did_teleop_periodic = True


class OpModeAuto(wpilib.OpMode):
label = "OpModeAuto"

def __init__(self, robot):
super().__init__()
self._robot = robot

def opModeRun(self, op_mode_id: int):
self._robot.opmode_test_observed.add(self.label)

def opModeStop(self):
pass


class OpModeTeleop(wpilib.OpMode):
label = "OpModeTeleop"

def __init__(self, robot):
super().__init__()
self._robot = robot

def opModeRun(self, op_mode_id: int):
self._robot.opmode_test_observed.add(self.label)

def opModeStop(self):
pass


class OpModeDemoRobot(wpilib.OpModeRobot):
def __init__(self):
super().__init__()
self.opmode_test_observed = set()
self.addOpMode(OpModeAuto, RobotMode.AUTONOMOUS, "OpModeAuto")
self.addOpMode(OpModeTeleop, RobotMode.TELEOPERATED, "OpModeTeleop")
self.publishOpModes()
""")


Expand Down Expand Up @@ -275,7 +312,42 @@ def test_builtin_tests_module(pytester, isolated):

result = pytester.runpytest_subprocess("-q")

result.assert_outcomes(passed=4)
result.assert_outcomes(passed=4, skipped=1)


@pytest.mark.parametrize("isolated", [False, True])
def test_builtin_tests_module_opmode(pytester, isolated):
_make_robot_module(pytester)
if isolated:
_configure_isolated_plugin(pytester, robot_class="OpModeDemoRobot")
else:
_configure_robot_testing_plugin(pytester, robot_class="OpModeDemoRobot")
pytester.makepyfile(pyfrc_test="from wpilib.testing.robot_tests import *\n")

result = pytester.runpytest_subprocess("-q")

result.assert_outcomes(passed=5)


@pytest.mark.parametrize("isolated", [False, True])
def test_opmode_robot_runs_opmodes(pytester, isolated):
_make_robot_module(pytester)
if isolated:
_configure_isolated_plugin(pytester, robot_class="OpModeDemoRobot")
else:
_configure_robot_testing_plugin(pytester, robot_class="OpModeDemoRobot")
pytester.makepyfile(test_robot="""
from wpilib.testing.robot_tests import test_all_opmodes


def test_opmodes_run(robot, control):
test_all_opmodes(control)
assert robot.opmode_test_observed == {"OpModeAuto", "OpModeTeleop"}
""")

result = pytester.runpytest_subprocess("-q")

result.assert_outcomes(passed=2)


def _run_robot_suite(pytester, isolated, robot_class, test_source, *args):
Expand Down
2 changes: 2 additions & 0 deletions subprojects/robotpy-wpilib/wpilib/testing/pytest_plugin.py
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,9 @@ def robot(self):
wpilib.DriverStation.silenceJoystickConnectionWarning(True)
DriverStationSim.setRobotMode(RobotMode.AUTONOMOUS)
DriverStationSim.setEnabled(False)
DriverStationSim.setOpMode(0)
DriverStationSim.notifyNewData()
wpilib.DriverStation.clearOpModes()

# Create the user's robot instance
robot = self._robot_class()
Expand Down
75 changes: 75 additions & 0 deletions subprojects/robotpy-wpilib/wpilib/testing/robot_tests.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,45 @@

import pytest

import wpilib
from hal._wpiHal import _RobotMode as RobotMode
from hal._wpiHal import opMode_GetRobotMode
from wpilib.simulation import DriverStationSim, stepTiming

from .controller import RobotTestController


def _step_timing_with_mode(
control: RobotTestController,
*,
seconds: float,
robot_mode: RobotMode,
enabled: bool,
assert_alive: bool = True,
record_opmode_ids: set[int] | None = None,
) -> float:
"""Step simulation time while explicitly setting the robot mode."""

assert control.robot_is_alive, "did you call control.run_robot()?"
assert seconds > 0

DriverStationSim.setDsAttached(True)
DriverStationSim.setRobotMode(robot_mode)
DriverStationSim.setEnabled(enabled)

tm = 0.0
while tm < seconds + 0.01:
DriverStationSim.notifyNewData()
stepTiming(0.2)
if record_opmode_ids is not None:
record_opmode_ids.add(wpilib.DriverStation.getOpModeId())
if assert_alive:
assert control.robot_is_alive
tm += 0.2

return tm


def test_autonomous(control: RobotTestController):
"""Runs autonomous mode by itself"""

Expand Down Expand Up @@ -72,3 +108,42 @@ def test_practice(control: RobotTestController):

# Run teleop + enabled for 2 minutes
control.step_timing(seconds=120, autonomous=False, enabled=True)


@pytest.mark.filterwarnings("ignore")
def test_all_opmodes(control: RobotTestController):
"""Runs each registered opmode briefly."""

with control.run_robot():
opmodes = DriverStationSim.getOpModeOptions()
if len(opmodes) == 0:
pytest.skip("robot did not register opmodes")

selected = []
seen = set()
for opmode in reversed(opmodes):
mode = opMode_GetRobotMode(opmode.id)
if mode == RobotMode.UNKNOWN:
continue
key = (opmode.name, mode)
if key in seen:
continue
seen.add(key)
selected.append((opmode, mode))

for opmode, mode in reversed(selected):
DriverStationSim.setOpMode(opmode.id)

_step_timing_with_mode(control, seconds=0.5, robot_mode=mode, enabled=False)
opmode_ids = set()
_step_timing_with_mode(
control,
seconds=2.0,
robot_mode=mode,
enabled=True,
record_opmode_ids=opmode_ids,
)
_step_timing_with_mode(control, seconds=0.5, robot_mode=mode, enabled=False)
assert (
opmode.id in opmode_ids
), f"opmode {opmode.name} ({opmode.id}) did not run"
Loading