|
| 1 | +""" |
| 2 | +Proof of concept to test TimedRobotPy using PyTest |
| 3 | +
|
| 4 | +This POC was made by deconstructing pytest_plugin.py so that it is no longer a plugin but a class that provides |
| 5 | +fixtures. |
| 6 | +
|
| 7 | +To run / debug this: |
| 8 | +
|
| 9 | +pytest subprojects/robotpy-wpilib/tests/test_poc_timedrobot.py --no-header -vvv -s |
| 10 | +
|
| 11 | +""" |
| 12 | + |
| 13 | +from pathlib import Path |
| 14 | +import pytest |
| 15 | + |
| 16 | +from wpilib.timedrobotpy import TimedRobotPy |
| 17 | + |
| 18 | + |
| 19 | +from pyfrc.tests.basic import test_practice as _test_practice |
| 20 | + |
| 21 | + |
| 22 | + |
| 23 | + |
| 24 | +class MyRobot(TimedRobotPy): |
| 25 | + def __init__(self): |
| 26 | + super().__init__(period=0.020) |
| 27 | + self.robotInitialized = False |
| 28 | + self.robotPeriodicCount = 0 |
| 29 | + |
| 30 | + ######################################################### |
| 31 | + ## Common init/update for all modes |
| 32 | + def robotInit(self): |
| 33 | + self.robotInitialized = True |
| 34 | + |
| 35 | + |
| 36 | + def robotPeriodic(self): |
| 37 | + self.robotPeriodicCount += 1 |
| 38 | + |
| 39 | + ######################################################### |
| 40 | + ## Autonomous-Specific init and update |
| 41 | + def autonomousInit(self): |
| 42 | + pass |
| 43 | + |
| 44 | + def autonomousPeriodic(self): |
| 45 | + pass |
| 46 | + |
| 47 | + def autonomousExit(self): |
| 48 | + pass |
| 49 | + |
| 50 | + |
| 51 | + ######################################################### |
| 52 | + ## Teleop-Specific init and update |
| 53 | + def teleopInit(self): |
| 54 | + pass |
| 55 | + |
| 56 | + def teleopPeriodic(self): |
| 57 | + pass |
| 58 | + |
| 59 | + ######################################################### |
| 60 | + ## Disabled-Specific init and update |
| 61 | + def disabledPeriodic(self): |
| 62 | + pass |
| 63 | + |
| 64 | + |
| 65 | + def disabledInit(self): |
| 66 | + pass |
| 67 | + |
| 68 | + ######################################################### |
| 69 | + ## Test-Specific init and update |
| 70 | + def testInit(self): |
| 71 | + pass |
| 72 | + |
| 73 | + def testPeriodic(self): |
| 74 | + pass |
| 75 | + |
| 76 | +import gc |
| 77 | +import pathlib |
| 78 | + |
| 79 | +from typing import Type |
| 80 | + |
| 81 | +import pytest |
| 82 | +import weakref |
| 83 | + |
| 84 | +import hal |
| 85 | +import hal.simulation |
| 86 | +import ntcore |
| 87 | +import wpilib |
| 88 | +import wpilib.shuffleboard |
| 89 | +from wpilib.simulation import DriverStationSim, pauseTiming, restartTiming |
| 90 | +import wpilib.simulation |
| 91 | + |
| 92 | +# TODO: get rid of special-casing.. maybe should register a HAL shutdown hook or something |
| 93 | +try: |
| 94 | + import commands2 |
| 95 | +except ImportError: |
| 96 | + commands2 = None |
| 97 | + |
| 98 | +from pyfrc.test_support.controller import TestController |
| 99 | +from pyfrc.physics.core import PhysicsInterface |
| 100 | + |
| 101 | +ROBOT_CLASS = MyRobot |
| 102 | +ISOLATED = True |
| 103 | +ROBOT_FILE = Path(__file__) |
| 104 | + |
| 105 | +# attach physics |
| 106 | +PHYSICS, ROBOT_CLASS = PhysicsInterface._create_and_attach( |
| 107 | + ROBOT_CLASS, |
| 108 | + ROBOT_FILE.parent, |
| 109 | +) |
| 110 | + |
| 111 | + |
| 112 | +# Tests need to know when robotInit is called, so override the robot |
| 113 | +# to do that |
| 114 | +class TestRobot(ROBOT_CLASS): |
| 115 | + def robotInit(self): |
| 116 | + try: |
| 117 | + super().robotInit() |
| 118 | + finally: |
| 119 | + self.__robotInitialized() |
| 120 | + |
| 121 | + |
| 122 | +TestRobot.__name__ = ROBOT_CLASS.__name__ |
| 123 | +TestRobot.__module__ = ROBOT_CLASS.__module__ |
| 124 | +TestRobot.__qualname__ = ROBOT_CLASS.__qualname__ |
| 125 | + |
| 126 | +ROBOT_CLASS = TestRobot |
| 127 | + |
| 128 | + |
| 129 | +if PHYSICS: |
| 130 | + PHYSICS.log_init_errors = False |
| 131 | + |
| 132 | + |
| 133 | +class PyFrcNotPlugin: |
| 134 | + |
| 135 | + @pytest.fixture(scope="function", autouse=True) |
| 136 | + def robot(self): |
| 137 | + """ |
| 138 | + Your robot instance |
| 139 | +
|
| 140 | + .. note:: RobotPy/WPILib testing infrastructure is really sensitive |
| 141 | + to ensuring that things get cleaned up properly. Make sure |
| 142 | + that you don't store references to your robot or other |
| 143 | + WPILib objects in a global or static context. |
| 144 | + """ |
| 145 | + |
| 146 | + # |
| 147 | + # This function needs to do the same things that RobotBase.main does |
| 148 | + # plus some extra things needed for testing |
| 149 | + # |
| 150 | + # Previously this was separate from robot fixture, but we need to |
| 151 | + # ensure that the robot cleanup happens deterministically relative to |
| 152 | + # when handle cleanup/etc happens, otherwise unnecessary HAL errors will |
| 153 | + # bubble up to the user |
| 154 | + # |
| 155 | + |
| 156 | + nt_inst = ntcore.NetworkTableInstance.getDefault() |
| 157 | + nt_inst.startLocal() |
| 158 | + |
| 159 | + pauseTiming() |
| 160 | + restartTiming() |
| 161 | + |
| 162 | + wpilib.DriverStation.silenceJoystickConnectionWarning(True) |
| 163 | + DriverStationSim.setAutonomous(False) |
| 164 | + DriverStationSim.setEnabled(False) |
| 165 | + DriverStationSim.notifyNewData() |
| 166 | + |
| 167 | + robot = ROBOT_CLASS() |
| 168 | + |
| 169 | + # Tests only get a proxy to ensure cleanup is more reliable |
| 170 | + yield weakref.proxy(robot) |
| 171 | + |
| 172 | + # If running in separate processes, no need to do cleanup |
| 173 | + if ISOLATED: |
| 174 | + # .. and funny enough, in isolated mode we *don't* want the |
| 175 | + # robot to be cleaned up, as that can deadlock |
| 176 | + self._saved_robot = robot |
| 177 | + return |
| 178 | + |
| 179 | + # reset engine to ensure it gets cleaned up too |
| 180 | + # -> might be holding wpilib objects, or the robot |
| 181 | + if PHYSICS: |
| 182 | + PHYSICS.engine = None |
| 183 | + |
| 184 | + # HACK: avoid motor safety deadlock |
| 185 | + wpilib.simulation._simulation._resetMotorSafety() |
| 186 | + |
| 187 | + del robot |
| 188 | + |
| 189 | + if commands2 is not None: |
| 190 | + commands2.CommandScheduler.resetInstance() |
| 191 | + |
| 192 | + # Double-check all objects are destroyed so that HAL handles are released |
| 193 | + gc.collect() |
| 194 | + |
| 195 | + # shutdown networktables before other kinds of global cleanup |
| 196 | + # -> some reset functions will re-register listeners, so it's important |
| 197 | + # to do this before so that the listeners are active on the current |
| 198 | + # NetworkTables instance |
| 199 | + nt_inst.stopLocal() |
| 200 | + nt_inst._reset() |
| 201 | + |
| 202 | + # Cleanup WPILib globals |
| 203 | + # -> preferences, SmartDashboard, Shuffleboard, LiveWindow, MotorSafety |
| 204 | + wpilib.simulation._simulation._resetWpilibSimulationData() |
| 205 | + wpilib._wpilib._clearSmartDashboardData() |
| 206 | + wpilib.shuffleboard._shuffleboard._clearShuffleboardData() |
| 207 | + |
| 208 | + # Cancel all periodic callbacks |
| 209 | + hal.simulation.cancelAllSimPeriodicCallbacks() |
| 210 | + |
| 211 | + # Reset the HAL handles |
| 212 | + hal.simulation.resetGlobalHandles() |
| 213 | + |
| 214 | + # Reset the HAL data |
| 215 | + hal.simulation.resetAllSimData() |
| 216 | + |
| 217 | + # Don't call HAL shutdown! This is only used to cleanup HAL extensions, |
| 218 | + # and functions will only be called the first time (unless re-registered) |
| 219 | + # hal.shutdown() |
| 220 | + |
| 221 | + @pytest.fixture(scope="function") |
| 222 | + def control(self, reraise, robot: wpilib.RobotBase) -> TestController: |
| 223 | + """ |
| 224 | + A pytest fixture that provides control over your robot |
| 225 | + """ |
| 226 | + return TestController(reraise, robot) |
| 227 | + |
| 228 | + @pytest.fixture() |
| 229 | + def robot_file(self) -> pathlib.Path: |
| 230 | + """The absolute filename your robot code is started from""" |
| 231 | + return ROBOT_FILE |
| 232 | + |
| 233 | + @pytest.fixture() |
| 234 | + def robot_path(self) -> pathlib.Path: |
| 235 | + """The absolute directory that your robot code is located at""" |
| 236 | + return ROBOT_FILE.parent |
| 237 | + |
| 238 | + |
| 239 | + |
| 240 | +@pytest.mark.usefixtures("control","robot_file","robot_path") |
| 241 | +class TestThings(PyFrcNotPlugin): |
| 242 | + |
| 243 | + |
| 244 | + def test_iterative(self, control, robot): |
| 245 | + """Ensure that all states of the iterative robot run""" |
| 246 | + assert robot.robotInitialized == False |
| 247 | + assert robot.robotPeriodicCount == 0 |
| 248 | + _test_practice(control) |
| 249 | + |
| 250 | + assert robot.robotInitialized == True |
| 251 | + assert robot.robotPeriodicCount > 0 |
| 252 | + |
| 253 | + def test_iterative_again(self, control, robot): |
| 254 | + """Ensure that all states of the iterative robot run""" |
| 255 | + assert robot.robotInitialized == False |
| 256 | + assert robot.robotPeriodicCount == 0 |
| 257 | + _test_practice(control) |
| 258 | + |
| 259 | + assert robot.robotInitialized == True |
| 260 | + assert robot.robotPeriodicCount > 0 |
0 commit comments