diff --git a/WORKSPACE.bzlmod b/WORKSPACE.bzlmod index d657eddc7c..66f10f8fea 100644 --- a/WORKSPACE.bzlmod +++ b/WORKSPACE.bzlmod @@ -14,9 +14,9 @@ http_archive( http_archive( name = "pybind11", build_file = "@pybind11_bazel//:pybind11-BUILD.bazel", - integrity = "sha256-wkxQme/TKRS6e0rFedV3IH00zgb8ZsZktnc3HRi9DyU=", - strip_prefix = "pybind11-dfe7e65b4527eeb11036402aac3a394130960bb2", - urls = ["https://github.com/pybind/pybind11/archive/dfe7e65b4527eeb11036402aac3a394130960bb2.zip"], + integrity = "sha256-LyCgrwuSGBXg4Wnqf+xjkJhpMjWBuJ194VU0aFU/ai0=", + strip_prefix = "pybind11-3.0.2", + url = "https://github.com/pybind/pybind11/archive/refs/tags/v3.0.2.tar.gz", ) http_archive( diff --git a/apriltag/src/main/python/pyproject.toml b/apriltag/src/main/python/pyproject.toml index d59a934d35..90e6ba7be5 100644 --- a/apriltag/src/main/python/pyproject.toml +++ b/apriltag/src/main/python/pyproject.toml @@ -1,7 +1,7 @@ [build-system] build-backend = "hatchling.build" requires = [ - "semiwrap~=0.2.6", + "semiwrap~=0.3.0", "hatch-meson~=0.1.0", "hatch-robotpy~=0.2.1", "hatchling", diff --git a/commandsv2/src/main/python/commands2/subsystem.py b/commandsv2/src/main/python/commands2/subsystem.py index 41cc5b6aff..3ad0629978 100644 --- a/commandsv2/src/main/python/commands2/subsystem.py +++ b/commandsv2/src/main/python/commands2/subsystem.py @@ -75,6 +75,8 @@ class Subsystem(Sendable): Removes the default command for the subsystem. This will not cancel the default command if it is currently running. """ + from .commandscheduler import CommandScheduler + CommandScheduler.getInstance().removeDefaultCommand(self) def getDefaultCommand(self) -> Optional[Command]: diff --git a/datalog/src/main/python/pyproject.toml b/datalog/src/main/python/pyproject.toml index 90a8e4e211..31fc207adc 100644 --- a/datalog/src/main/python/pyproject.toml +++ b/datalog/src/main/python/pyproject.toml @@ -1,7 +1,7 @@ [build-system] build-backend = "hatchling.build" requires = [ - "semiwrap~=0.2.6", + "semiwrap~=0.3.0", "hatch-meson~=0.1.0", "hatchling", "robotpy-native-datalog==0.0.0", diff --git a/hal/src/main/python/pyproject.toml b/hal/src/main/python/pyproject.toml index cee7b2d4d3..c0514d874b 100644 --- a/hal/src/main/python/pyproject.toml +++ b/hal/src/main/python/pyproject.toml @@ -1,7 +1,7 @@ [build-system] build-backend = "hatchling.build" requires = [ - "semiwrap~=0.2.6", + "semiwrap~=0.3.0", "hatch-meson~=0.1.0", "hatchling", "pyntcore==0.0.0", diff --git a/hal/src/main/python/semiwrap/SimDevice.yml b/hal/src/main/python/semiwrap/SimDevice.yml index 5f8be03904..8cbd2a45f0 100644 --- a/hal/src/main/python/semiwrap/SimDevice.yml +++ b/hal/src/main/python/semiwrap/SimDevice.yml @@ -241,7 +241,7 @@ inline_code: |2 }); cls_SimBoolean - .def_property("value", &SimBoolean::Get, &SimBoolean::Set, release_gil()) + .def_property("value", &SimBoolean::Get, &SimBoolean::Set) .def("__repr__", [](const SimBoolean &self) -> py::str { if (self) { bool value; @@ -292,7 +292,7 @@ inline_code: |2 }); cls_SimDouble - .def_property("value", &SimDouble::Get, &SimDouble::Set, release_gil()) + .def_property("value", &SimDouble::Get, &SimDouble::Set) .def("__repr__", [](const SimDouble &self) -> py::str { if (self) { double value; diff --git a/ntcore/src/main/python/pyproject.toml b/ntcore/src/main/python/pyproject.toml index 9a9331ef3f..92662eb2ba 100644 --- a/ntcore/src/main/python/pyproject.toml +++ b/ntcore/src/main/python/pyproject.toml @@ -1,7 +1,7 @@ [build-system] build-backend = "hatchling.build" requires = [ - "semiwrap~=0.2.6", + "semiwrap~=0.3.0", "hatch-meson~=0.1.0", "hatch-robotpy~=0.2.1", "hatchling", diff --git a/requirements.txt b/requirements.txt index 9007c4be32..ab6d795932 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,7 +1,7 @@ jinja2==3.1.6 protobuf==5.28.3 grpcio-tools==1.68.0 -semiwrap==0.2.6 +semiwrap==0.3.0 pytest>=3.9 pytest-reraise numpy diff --git a/requirements_lock.txt b/requirements_lock.txt index 7b298aed41..70680973f9 100644 --- a/requirements_lock.txt +++ b/requirements_lock.txt @@ -394,9 +394,9 @@ protobuf==5.28.3 \ # via # -r requirements.txt # grpcio-tools -pybind11==3.0.1 \ - --hash=sha256:9c0f40056a016da59bab516efb523089139fcc6f2ba7e4930854c61efb932051 \ - --hash=sha256:aa8f0aa6e0a94d3b64adfc38f560f33f15e589be2175e103c0a33c6bce55ee89 +pybind11==3.0.2 \ + --hash=sha256:432f01aeb68e361a3a7fc7575c2c7f497595bf640f747acd909ff238dd766e06 \ + --hash=sha256:f8a6500548919cc33bcd220d5f984688326f574fa97f1107f2f4fdb4c6fb019f # via semiwrap pybind11-stubgen==2.5.5 \ --hash=sha256:10824cd2fc5cbbee032b8fb39e6f6c08de232deb309bc66d786a6c6e8a4601bd \ @@ -566,9 +566,9 @@ ruamel-yaml-clib==0.2.15 \ --hash=sha256:fd4c928ddf6bce586285daa6d90680b9c291cfd045fc40aad34e445d57b1bf51 \ --hash=sha256:fe239bdfdae2302e93bd6e8264bd9b71290218fff7084a9db250b55caaccf43f # via ruamel-yaml -semiwrap==0.2.6 \ - --hash=sha256:cc260ac824af2020f87cc95bc25e41d6486783fe886b43d846b801c034a8a0fb \ - --hash=sha256:d6ce64193abe8db5743ec27873d65bc53a2a7f35d3c16ce91aa8e9ea21d2d05e +semiwrap==0.3.0 \ + --hash=sha256:106a3fc09e31068645bd4c3eab799517bf392ab15a4aa896e947b7a885d79412 \ + --hash=sha256:e215261e387169aacb3c8cf39c711fbcaa59fb9b029d4f1d8d81db9d015c68f3 # via -r requirements.txt sphinxify==0.12 \ --hash=sha256:3ec299e78babac7d3457f47bf263411b48e10b9c8add18d7159fa0327cc4a061 \ diff --git a/requirements_windows_lock.txt b/requirements_windows_lock.txt index 3c86f82470..da10a46f2a 100644 --- a/requirements_windows_lock.txt +++ b/requirements_windows_lock.txt @@ -398,9 +398,9 @@ protobuf==5.28.3 \ # via # -r requirements.txt # grpcio-tools -pybind11==3.0.1 \ - --hash=sha256:9c0f40056a016da59bab516efb523089139fcc6f2ba7e4930854c61efb932051 \ - --hash=sha256:aa8f0aa6e0a94d3b64adfc38f560f33f15e589be2175e103c0a33c6bce55ee89 +pybind11==3.0.2 \ + --hash=sha256:432f01aeb68e361a3a7fc7575c2c7f497595bf640f747acd909ff238dd766e06 \ + --hash=sha256:f8a6500548919cc33bcd220d5f984688326f574fa97f1107f2f4fdb4c6fb019f # via semiwrap pybind11-stubgen==2.5.5 \ --hash=sha256:10824cd2fc5cbbee032b8fb39e6f6c08de232deb309bc66d786a6c6e8a4601bd \ @@ -570,9 +570,9 @@ ruamel-yaml-clib==0.2.15 \ --hash=sha256:fd4c928ddf6bce586285daa6d90680b9c291cfd045fc40aad34e445d57b1bf51 \ --hash=sha256:fe239bdfdae2302e93bd6e8264bd9b71290218fff7084a9db250b55caaccf43f # via ruamel-yaml -semiwrap==0.2.6 \ - --hash=sha256:cc260ac824af2020f87cc95bc25e41d6486783fe886b43d846b801c034a8a0fb \ - --hash=sha256:d6ce64193abe8db5743ec27873d65bc53a2a7f35d3c16ce91aa8e9ea21d2d05e +semiwrap==0.3.0 \ + --hash=sha256:106a3fc09e31068645bd4c3eab799517bf392ab15a4aa896e947b7a885d79412 \ + --hash=sha256:e215261e387169aacb3c8cf39c711fbcaa59fb9b029d4f1d8d81db9d015c68f3 # via -r requirements.txt sphinxify==0.12 \ --hash=sha256:3ec299e78babac7d3457f47bf263411b48e10b9c8add18d7159fa0327cc4a061 \ diff --git a/robotpyExamples/DifferentialDriveBot/drivetrain.py b/robotpyExamples/DifferentialDriveBot/drivetrain.py index bf5c9ecc15..27ca18e1d0 100755 --- a/robotpyExamples/DifferentialDriveBot/drivetrain.py +++ b/robotpyExamples/DifferentialDriveBot/drivetrain.py @@ -68,7 +68,9 @@ class Drivetrain: self.rightEncoder.getDistance(), ) - def setVelocities(self, velocities: wpimath.DifferentialDriveWheelVelocities) -> None: + def setVelocities( + self, velocities: wpimath.DifferentialDriveWheelVelocities + ) -> None: """Sets the desired wheel velocities. :param velocities: The desired wheel velocities. diff --git a/robotpyExamples/DifferentialDrivePoseEstimator/drivetrain.py b/robotpyExamples/DifferentialDrivePoseEstimator/drivetrain.py index 3886931522..deb62ca496 100644 --- a/robotpyExamples/DifferentialDrivePoseEstimator/drivetrain.py +++ b/robotpyExamples/DifferentialDrivePoseEstimator/drivetrain.py @@ -111,7 +111,9 @@ class Drivetrain: wpilib.SmartDashboard.putData("Field", self.fieldSim) wpilib.SmartDashboard.putData("FieldEstimation", self.fieldApproximation) - def setVelocities(self, velocities: wpimath.DifferentialDriveWheelVelocities) -> None: + def setVelocities( + self, velocities: wpimath.DifferentialDriveWheelVelocities + ) -> None: """Sets the desired wheel velocities. :param velocities: The desired wheel velocities. diff --git a/robotpyExamples/HatchbotTraditional/commands/complexauto.py b/robotpyExamples/HatchbotTraditional/commands/complexauto.py index 74d12b4adf..c28d3a34af 100644 --- a/robotpyExamples/HatchbotTraditional/commands/complexauto.py +++ b/robotpyExamples/HatchbotTraditional/commands/complexauto.py @@ -30,6 +30,8 @@ class ComplexAuto(commands2.SequentialCommandGroup): ReleaseHatch(hatch), # Drive backward the specified distance DriveDistance( - constants.kAutoBackupDistanceInches, -constants.kAutoDriveVelocity, drive + constants.kAutoBackupDistanceInches, + -constants.kAutoDriveVelocity, + drive, ), ) diff --git a/robotpyExamples/MecanumBot/drivetrain.py b/robotpyExamples/MecanumBot/drivetrain.py index 9512fa7678..fc628aec4b 100755 --- a/robotpyExamples/MecanumBot/drivetrain.py +++ b/robotpyExamples/MecanumBot/drivetrain.py @@ -114,7 +114,9 @@ class Drivetrain: """Method to drive the robot using joystick info.""" chassisVelocities = wpimath.ChassisVelocities(xVelocity, yVelocity, rot) if fieldRelative: - chassisVelocities = chassisVelocities.toRobotRelative(self.imu.getRotation2d()) + chassisVelocities = chassisVelocities.toRobotRelative( + self.imu.getRotation2d() + ) self.setVelocities( self.kinematics.toWheelVelocities( diff --git a/robotpyExamples/MecanumDrivePoseEstimator/drivetrain.py b/robotpyExamples/MecanumDrivePoseEstimator/drivetrain.py index b9f7f3a969..7ecf3a5c16 100644 --- a/robotpyExamples/MecanumDrivePoseEstimator/drivetrain.py +++ b/robotpyExamples/MecanumDrivePoseEstimator/drivetrain.py @@ -144,9 +144,9 @@ class Drivetrain: self.poseEstimator.getEstimatedPosition().rotation() ) self.setVelocities( - self.kinematics.toWheelVelocities(chassisVelocities.discretize(period)).desaturate( - self.kMaxVelocity - ) + self.kinematics.toWheelVelocities( + chassisVelocities.discretize(period) + ).desaturate(self.kMaxVelocity) ) def updateOdometry(self) -> None: diff --git a/robotpyExamples/SimpleDifferentialDriveSimulation/drivetrain.py b/robotpyExamples/SimpleDifferentialDriveSimulation/drivetrain.py index 52eedbe96d..c0e86a92a7 100644 --- a/robotpyExamples/SimpleDifferentialDriveSimulation/drivetrain.py +++ b/robotpyExamples/SimpleDifferentialDriveSimulation/drivetrain.py @@ -88,7 +88,9 @@ class Drivetrain: self.rightLeader.setInverted(True) wpilib.SmartDashboard.putData("Field", self.fieldSim) - def setVelocities(self, velocities: wpimath.DifferentialDriveWheelVelocities) -> None: + def setVelocities( + self, velocities: wpimath.DifferentialDriveWheelVelocities + ) -> None: """Sets velocities to the drivetrain motors.""" leftFeedforward = self.feedforward.calculate(velocities.left) rightFeedforward = self.feedforward.calculate(velocities.right) @@ -109,7 +111,9 @@ class Drivetrain: :param rot: the rotation """ self.setVelocities( - self.kinematics.toWheelVelocities(wpimath.ChassisVelocities(xVelocity, 0, rot)) + self.kinematics.toWheelVelocities( + wpimath.ChassisVelocities(xVelocity, 0, rot) + ) ) def updateOdometry(self) -> None: diff --git a/robotpyExamples/StateSpaceArm/robot.py b/robotpyExamples/StateSpaceArm/robot.py index 262b350013..80322545b6 100644 --- a/robotpyExamples/StateSpaceArm/robot.py +++ b/robotpyExamples/StateSpaceArm/robot.py @@ -35,7 +35,9 @@ class MyRobot(wpilib.TimedRobot): self.profile = wpimath.TrapezoidProfile( wpimath.TrapezoidProfile.Constraints( wpimath.units.degreesToRadians(45), - wpimath.units.degreesToRadians(90), # Max arm velocity and acceleration. + wpimath.units.degreesToRadians( + 90 + ), # Max arm velocity and acceleration. ) ) diff --git a/robotpyExamples/StateSpaceElevator/robot.py b/robotpyExamples/StateSpaceElevator/robot.py index 936045f87a..904d7f6a18 100644 --- a/robotpyExamples/StateSpaceElevator/robot.py +++ b/robotpyExamples/StateSpaceElevator/robot.py @@ -39,7 +39,9 @@ class MyRobot(wpilib.TimedRobot): self.profile = wpimath.TrapezoidProfile( wpimath.TrapezoidProfile.Constraints( wpimath.units.feetToMeters(3.0), - wpimath.units.feetToMeters(6.0), # Max elevator velocity and acceleration. + wpimath.units.feetToMeters( + 6.0 + ), # Max elevator velocity and acceleration. ) ) diff --git a/robotpyExamples/SwerveBot/drivetrain.py b/robotpyExamples/SwerveBot/drivetrain.py index c245a5fdd6..269908ef20 100644 --- a/robotpyExamples/SwerveBot/drivetrain.py +++ b/robotpyExamples/SwerveBot/drivetrain.py @@ -69,7 +69,9 @@ class Drivetrain: """ robot_velocities = wpimath.ChassisVelocities(xVelocity, yVelocity, rot) if fieldRelative: - robot_velocities = robot_velocities.toRobotRelative(self.imu.getRotation2d()) + robot_velocities = robot_velocities.toRobotRelative( + self.imu.getRotation2d() + ) swerveModuleStates = self.kinematics.toSwerveModuleVelocities( wpimath.ChassisVelocities.discretize(robot_velocities, periodSeconds) diff --git a/robotpyExamples/SwerveDrivePoseEstimator/drivetrain.py b/robotpyExamples/SwerveDrivePoseEstimator/drivetrain.py index ec303329d5..68af3c409a 100644 --- a/robotpyExamples/SwerveDrivePoseEstimator/drivetrain.py +++ b/robotpyExamples/SwerveDrivePoseEstimator/drivetrain.py @@ -82,7 +82,9 @@ class Drivetrain: chassisVelocities = chassisVelocities.discretize(period) states = self.kinematics.toSwerveModuleVelocities(chassisVelocities) - wpimath.SwerveDrive4Kinematics.desaturateWheelVelocities(states, self.kMaxVelocity) + wpimath.SwerveDrive4Kinematics.desaturateWheelVelocities( + states, self.kMaxVelocity + ) self.frontLeft.setDesiredVelocity(states[0]) self.frontRight.setDesiredVelocity(states[1]) diff --git a/robotpyExamples/SwerveDrivePoseEstimator/swervemodule.py b/robotpyExamples/SwerveDrivePoseEstimator/swervemodule.py index a4f3101d86..828cbd4875 100644 --- a/robotpyExamples/SwerveDrivePoseEstimator/swervemodule.py +++ b/robotpyExamples/SwerveDrivePoseEstimator/swervemodule.py @@ -77,12 +77,12 @@ class SwerveModule: # to be continuous. self.turningPIDController.enableContinuousInput(-math.pi, math.pi) - def getState(self) -> wpimath.SwerveModuleVelocity : + def getState(self) -> wpimath.SwerveModuleVelocity: """Returns the current state of the module. :returns: The current state of the module. """ - return wpimath.SwerveModuleVelocity ( + return wpimath.SwerveModuleVelocity( self.driveEncoder.getRate(), wpimath.Rotation2d(self.turningEncoder.getDistance()), ) diff --git a/robotpyExamples/XrpReference/subsystems/drivetrain.py b/robotpyExamples/XrpReference/subsystems/drivetrain.py index aa4c8c68ea..8918b1b49e 100644 --- a/robotpyExamples/XrpReference/subsystems/drivetrain.py +++ b/robotpyExamples/XrpReference/subsystems/drivetrain.py @@ -31,7 +31,9 @@ class Drivetrain(commands2.Subsystem): self.rightEncoder = wpilib.Encoder(6, 7) # Set up the differential drive controller - self.drive = wpilib.DifferentialDrive(self.leftMotor.setDutyCycle, self.rightMotor.setDutyCycle) + self.drive = wpilib.DifferentialDrive( + self.leftMotor.setDutyCycle, self.rightMotor.setDutyCycle + ) # TODO: these don't work # wpiutil.SendableRegistry.addChild(self.drive, self.leftMotor) diff --git a/romiVendordep/src/main/python/pyproject.toml b/romiVendordep/src/main/python/pyproject.toml index e1d92c7502..d87ff43461 100644 --- a/romiVendordep/src/main/python/pyproject.toml +++ b/romiVendordep/src/main/python/pyproject.toml @@ -1,7 +1,7 @@ [build-system] build-backend = "hatchling.build" requires = [ - "semiwrap~=0.2.6", + "semiwrap~=0.3.0", "hatch-meson~=0.1.0", "hatch-robotpy~=0.2.1", "hatchling", diff --git a/simulation/halsim_gui/src/main/python/pyproject.toml b/simulation/halsim_gui/src/main/python/pyproject.toml index f2f1b537dd..a373952404 100644 --- a/simulation/halsim_gui/src/main/python/pyproject.toml +++ b/simulation/halsim_gui/src/main/python/pyproject.toml @@ -1,7 +1,7 @@ [build-system] build-backend = "hatchling.build" requires = [ - "semiwrap~=0.2.6", + "semiwrap~=0.3.0", "hatch-meson~=0.1.0", "hatch-robotpy~=0.2.1", "hatchling", diff --git a/simulation/halsim_gui/src/test/python/test_halsim_gui.py b/simulation/halsim_gui/src/test/python/test_halsim_gui.py index 65d40386b9..6373e32837 100644 --- a/simulation/halsim_gui/src/test/python/test_halsim_gui.py +++ b/simulation/halsim_gui/src/test/python/test_halsim_gui.py @@ -1,7 +1,15 @@ import ctypes +import ctypes.util import pathlib +import sys + +import pytest +@pytest.mark.skipif( + sys.platform == "linux" and not ctypes.util.find_library("X11"), + reason="X11 not installed", +) def test_halsim_gui(): # dependencies import wpinet diff --git a/wpilibc/src/main/python/pyproject.toml b/wpilibc/src/main/python/pyproject.toml index 4bb6d354c4..0c4e92d425 100644 --- a/wpilibc/src/main/python/pyproject.toml +++ b/wpilibc/src/main/python/pyproject.toml @@ -1,7 +1,7 @@ [build-system] build-backend = "hatchling.build" requires = [ - "semiwrap~=0.2.6", + "semiwrap~=0.3.0", "hatch-meson~=0.1.0", "hatch-robotpy~=0.2.1", "hatchling", diff --git a/wpilibc/src/main/python/wpilib/testing/pytest_isolated_tests_plugin.py b/wpilibc/src/main/python/wpilib/testing/pytest_isolated_tests_plugin.py index fa16ab9792..90a7ad6073 100644 --- a/wpilibc/src/main/python/wpilib/testing/pytest_isolated_tests_plugin.py +++ b/wpilibc/src/main/python/wpilib/testing/pytest_isolated_tests_plugin.py @@ -18,6 +18,24 @@ import wpilib from .pytest_plugin import RobotTestingPlugin +class _NullTerminalWriter: + def _highlight(self, source, lexer="python"): + return source + + +class _NullTerminalReporter: + """Minimal terminal reporter used in worker processes.""" + + def __init__(self): + self._tw = _NullTerminalWriter() + + def write(self, *args, **kwargs): + pass + + def line(self, *args, **kwargs): + pass + + def _enable_faulthandler(): # # In the event of a segfault, faulthandler will dump the currently @@ -66,6 +84,15 @@ class WorkerPlugin: @pytest.hookimpl(wrapper=True) def pytest_sessionstart(self, session: pytest.Session): self.config = session.config + + # When we disable terminalreporter in worker mode we still need a + # minimal reporter so assertion introspection can render diffs. + if self.config.pluginmanager.get_plugin("terminalreporter") is None: + self.config.pluginmanager.unblock("terminalreporter") + self.config.pluginmanager.register( + _NullTerminalReporter(), "terminalreporter" + ) + return (yield) @pytest.hookimpl diff --git a/wpilibc/src/test/python/test_alert.py b/wpilibc/src/test/python/test_alert.py index dc585ebef1..86e2e81cc5 100644 --- a/wpilibc/src/test/python/test_alert.py +++ b/wpilibc/src/test/python/test_alert.py @@ -17,9 +17,7 @@ def group_name(request): AlertSim.resetData() -def get_active_alerts( - group_name: str, level: Alert.Level -) -> T.List[str]: +def get_active_alerts(group_name: str, level: Alert.Level) -> T.List[str]: return [ a.text for a in AlertSim.getAll() @@ -27,13 +25,14 @@ def get_active_alerts( ] -def is_alert_active( - group_name: str, text: str, level: Alert.Level -): +def is_alert_active(group_name: str, text: str, level: Alert.Level): matches = [ a for a in AlertSim.getAll() - if a.group == group_name and a.level == level and a.text == text and a.isActive() + if a.group == group_name + and a.level == level + and a.text == text + and a.isActive() ] return len(matches) > 0 diff --git a/wpilibc/src/test/python/test_opmode_robot.py b/wpilibc/src/test/python/test_opmode_robot.py index 956f025415..350b8906ee 100644 --- a/wpilibc/src/test/python/test_opmode_robot.py +++ b/wpilibc/src/test/python/test_opmode_robot.py @@ -135,7 +135,7 @@ def test_remove_op_mode(): assert options[0].name == "OneArgOpMode" -# @pytest.mark.xfail(reason="wpilib bug") +@pytest.mark.xfail(reason="wpilib bug") def test_none_periodic(): class MyMockRobot(MockRobot): def __init__(self): diff --git a/wpilibc/src/test/python/test_pytest_plugins.py b/wpilibc/src/test/python/test_pytest_plugins.py index 9c6d99355a..a2a3b44137 100644 --- a/wpilibc/src/test/python/test_pytest_plugins.py +++ b/wpilibc/src/test/python/test_pytest_plugins.py @@ -166,6 +166,26 @@ def test_robot_failure_output(robot): assert robot_pid_one != robot_pid_two +def test_isolated_plugin_assertion_rendering(pytester): + _make_robot_module(pytester) + _configure_isolated_plugin(pytester) + pytester.makepyfile(test_isolated=""" +def test_robot_assertion_rendering(robot): + assert "x" == "y" +""") + + result = pytester.runpytest_subprocess("-vv") + + result.assert_outcomes(failed=1) + result.stdout.fnmatch_lines( + [ + "*test_isolated.py::test_robot_assertion_rendering FAILED*", + "*assert 'x' == 'y'*", + ] + ) + assert not any("_pytest/config/__init__.py" in line for line in result.outlines) + + def test_isolated_plugin_no_duplicate_verbose_output(pytester): _make_robot_module(pytester) _configure_isolated_plugin(pytester) diff --git a/wpimath/src/main/python/pyproject.toml b/wpimath/src/main/python/pyproject.toml index 6dbcb2decd..c9c33e7884 100644 --- a/wpimath/src/main/python/pyproject.toml +++ b/wpimath/src/main/python/pyproject.toml @@ -1,7 +1,7 @@ [build-system] build-backend = "hatchling.build" requires = [ - "semiwrap~=0.2.6", + "semiwrap~=0.3.0", "hatch-meson~=0.1.0", "hatch-robotpy~=0.2.1", "hatchling", diff --git a/wpimath/src/test/python/kinematics/test_chassis_velocities.py b/wpimath/src/test/python/kinematics/test_chassis_velocities.py index 8da41444e6..200e215da5 100644 --- a/wpimath/src/test/python/kinematics/test_chassis_velocities.py +++ b/wpimath/src/test/python/kinematics/test_chassis_velocities.py @@ -111,4 +111,7 @@ def test_unpack() -> None: def test_repr() -> None: velocities = ChassisVelocities(2.0, 1.0, 0.0) - assert repr(velocities) == "ChassisVelocities(vx=2.000000, vy=1.000000, omega=0.000000)" + assert ( + repr(velocities) + == "ChassisVelocities(vx=2.000000, vy=1.000000, omega=0.000000)" + ) diff --git a/wpimath/src/test/python/kinematics/test_mecanum_drive_kinematics.py b/wpimath/src/test/python/kinematics/test_mecanum_drive_kinematics.py index 853388fff1..edf3c69d1c 100644 --- a/wpimath/src/test/python/kinematics/test_mecanum_drive_kinematics.py +++ b/wpimath/src/test/python/kinematics/test_mecanum_drive_kinematics.py @@ -40,7 +40,9 @@ def test_straight_line_forward_kinematics(kinematics_test): wheel_velocities = MecanumDriveWheelVelocities( frontLeft=5, frontRight=5, rearLeft=5, rearRight=5 ) - chassis_velocities = kinematics_test.kinematics.toChassisVelocities(wheel_velocities) + chassis_velocities = kinematics_test.kinematics.toChassisVelocities( + wheel_velocities + ) assert chassis_velocities.vx == pytest.approx(5.0, abs=0.1) assert chassis_velocities.vy == pytest.approx(0.0, abs=0.1) @@ -72,7 +74,9 @@ def test_strafe_forward_kinematics(kinematics_test): wheel_velocities = MecanumDriveWheelVelocities( frontLeft=-5, frontRight=5, rearLeft=5, rearRight=-5 ) - chassis_velocities = kinematics_test.kinematics.toChassisVelocities(wheel_velocities) + chassis_velocities = kinematics_test.kinematics.toChassisVelocities( + wheel_velocities + ) assert chassis_velocities.vx == pytest.approx(0.0, abs=0.1) assert chassis_velocities.vy == pytest.approx(5.0, abs=0.1) @@ -107,7 +111,9 @@ def test_rotation_forward_kinematics(kinematics_test): rearLeft=-150.79644737, rearRight=150.79644737, ) - chassis_velocities = kinematics_test.kinematics.toChassisVelocities(wheel_velocities) + chassis_velocities = kinematics_test.kinematics.toChassisVelocities( + wheel_velocities + ) assert chassis_velocities.vx == pytest.approx(0.0, abs=0.1) assert chassis_velocities.vy == pytest.approx(0.0, abs=0.1) @@ -146,7 +152,9 @@ def test_mixed_rotation_translation_forward_kinematics(kinematics_test): rearRight=16.26, ) - chassis_velocities = kinematics_test.kinematics.toChassisVelocities(wheel_velocities) + chassis_velocities = kinematics_test.kinematics.toChassisVelocities( + wheel_velocities + ) assert chassis_velocities.vx == pytest.approx(1.41335, abs=0.1) assert chassis_velocities.vy == pytest.approx(2.1221, abs=0.1) @@ -184,7 +192,9 @@ def test_off_center_rotation_forward_kinematics(kinematics_test): rearLeft=-16.971, rearRight=33.941, ) - chassis_velocities = kinematics_test.kinematics.toChassisVelocities(wheel_velocities) + chassis_velocities = kinematics_test.kinematics.toChassisVelocities( + wheel_velocities + ) assert chassis_velocities.vx == pytest.approx(8.48525, abs=0.1) assert chassis_velocities.vy == pytest.approx(-8.48525, abs=0.1) @@ -221,7 +231,9 @@ def test_off_center_translation_rotation_forward_kinematics(kinematics_test): rearLeft=-12.02, rearRight=36.06, ) - chassis_velocities = kinematics_test.kinematics.toChassisVelocities(wheel_velocities) + chassis_velocities = kinematics_test.kinematics.toChassisVelocities( + wheel_velocities + ) assert chassis_velocities.vx == pytest.approx(12.02, abs=0.1) assert chassis_velocities.vy == pytest.approx(-7.07, abs=0.1) diff --git a/wpimath/src/test/python/kinematics/test_swerve_drive_kinematics.py b/wpimath/src/test/python/kinematics/test_swerve_drive_kinematics.py index ff503ea919..420ab5e899 100644 --- a/wpimath/src/test/python/kinematics/test_swerve_drive_kinematics.py +++ b/wpimath/src/test/python/kinematics/test_swerve_drive_kinematics.py @@ -164,7 +164,9 @@ def test_turn_in_place_forward_kinematics(kinematics_test): bl = SwerveModuleVelocity(velocity=106.629, angle=Rotation2d.fromDegrees(-135)) br = SwerveModuleVelocity(velocity=106.629, angle=Rotation2d.fromDegrees(-45)) - chassis_velocities = kinematics_test.m_kinematics.toChassisVelocities((fl, fr, bl, br)) + chassis_velocities = kinematics_test.m_kinematics.toChassisVelocities( + (fl, fr, bl, br) + ) assert chassis_velocities.vx == pytest.approx(0.0, abs=kEpsilon) assert chassis_velocities.vy == pytest.approx(0.0, abs=kEpsilon) @@ -209,7 +211,9 @@ def test_off_center_cor_rotation_forward_kinematics(kinematics_test): bl = SwerveModuleVelocity(velocity=150.796, angle=Rotation2d.fromDegrees(-90)) br = SwerveModuleVelocity(velocity=213.258, angle=Rotation2d.fromDegrees(-45)) - chassis_velocities = kinematics_test.m_kinematics.toChassisVelocities((fl, fr, bl, br)) + chassis_velocities = kinematics_test.m_kinematics.toChassisVelocities( + (fl, fr, bl, br) + ) assert chassis_velocities.vx == pytest.approx(75.398, abs=kEpsilon) assert chassis_velocities.vy == pytest.approx(-75.398, abs=kEpsilon) @@ -254,7 +258,9 @@ def test_off_center_cor_rotation_and_translation_forward_kinematics(kinematics_t bl = SwerveModuleVelocity(velocity=54.08, angle=Rotation2d.fromDegrees(-109.44)) br = SwerveModuleVelocity(velocity=54.08, angle=Rotation2d.fromDegrees(-70.56)) - chassis_velocities = kinematics_test.m_kinematics.toChassisVelocities((fl, fr, bl, br)) + chassis_velocities = kinematics_test.m_kinematics.toChassisVelocities( + (fl, fr, bl, br) + ) assert chassis_velocities.vx == pytest.approx(0.0, abs=kEpsilon) assert chassis_velocities.vy == pytest.approx(-33.0, abs=kEpsilon) diff --git a/wpinet/src/main/python/pyproject.toml b/wpinet/src/main/python/pyproject.toml index c06d5b8bfb..5891eb014f 100644 --- a/wpinet/src/main/python/pyproject.toml +++ b/wpinet/src/main/python/pyproject.toml @@ -1,9 +1,9 @@ [build-system] build-backend = "hatchling.build" requires = [ - "semiwrap~=0.2.6", + "semiwrap~=0.3.0", "hatch-meson~=0.1.0", - "semiwrap~=0.2.6", + "semiwrap~=0.3.0", "hatch-meson~=0.1.0", "hatchling", "robotpy-native-wpinet==0.0.0", diff --git a/wpiutil/src/main/python/native-pyproject.toml b/wpiutil/src/main/python/native-pyproject.toml index e30e5379c5..583dce76ad 100644 --- a/wpiutil/src/main/python/native-pyproject.toml +++ b/wpiutil/src/main/python/native-pyproject.toml @@ -36,7 +36,21 @@ includedir = "src/native/wpiutil/include" libdir = "src/native/wpiutil/lib" shared_libraries = ["wpiutil"] -enable_if = "platform_system != 'Windows'" +enable_if = "platform_system != 'Windows' and platform_machine != 'aarch64'" + +[[tool.hatch.build.hooks.nativelib.pcfile]] +pcfile = "src/native/wpiutil/robotpy-native-wpiutil.pc" +name = "wpiutil" + +includedir = "src/native/wpiutil/include" +libdir = "src/native/wpiutil/lib" +shared_libraries = ["wpiutil"] + +# abi warnings are obnoxious on arm +extra_cflags = "-Wno-psabi" + +enable_if = "platform_system != 'Windows' and platform_machine == 'aarch64'" + [[tool.hatch.build.hooks.nativelib.pcfile]] pcfile = "src/native/wpiutil/robotpy-native-wpiutil.pc" diff --git a/wpiutil/src/main/python/pyproject.toml b/wpiutil/src/main/python/pyproject.toml index 7a9956cb1c..8662238636 100644 --- a/wpiutil/src/main/python/pyproject.toml +++ b/wpiutil/src/main/python/pyproject.toml @@ -1,7 +1,7 @@ [build-system] build-backend = "hatchling.build" requires = [ - "semiwrap~=0.2.6", + "semiwrap~=0.3.0", "hatch-meson~=0.1.0", "hatch-robotpy~=0.2.1", "hatchling", diff --git a/wpiutil/src/main/python/wpiutil/wpistruct/typing.py b/wpiutil/src/main/python/wpiutil/wpistruct/typing.py index 83359c01be..67083ceb75 100644 --- a/wpiutil/src/main/python/wpiutil/wpistruct/typing.py +++ b/wpiutil/src/main/python/wpiutil/wpistruct/typing.py @@ -1,15 +1,4 @@ -from typing import ClassVar, Protocol - -try: - from typing import TypeGuard -except ImportError: - try: - from typing_extensions import TypeGuard - except ImportError: - # Runtime fallback for Python 3.9 without typing_extensions - class TypeGuard: - def __class_getitem__(cls, key): - return bool +from typing import ClassVar, Protocol, TypeGuard class StructSerializable(Protocol): diff --git a/wpiutil/src/test/python/test_array.py b/wpiutil/src/test/python/test_array.py index 1765b24e2f..4e99489cdc 100644 --- a/wpiutil/src/test/python/test_array.py +++ b/wpiutil/src/test/python/test_array.py @@ -9,9 +9,9 @@ def test_load_array_int(): def test_load_array_annotation(): assert ( module.load_array_int.__doc__ - == "load_array_int(arg0: Tuple[typing.SupportsInt, typing.SupportsInt, typing.SupportsInt, typing.SupportsInt]) -> Tuple[int, int, int, int]\n" + == "load_array_int(arg0: Tuple[typing.SupportsInt | typing.SupportsIndex, typing.SupportsInt | typing.SupportsIndex, typing.SupportsInt | typing.SupportsIndex, typing.SupportsInt | typing.SupportsIndex]) -> Tuple[int, int, int, int]\n" ) assert ( module.load_array_int1.__doc__ - == "load_array_int1(arg0: Tuple[typing.SupportsInt]) -> Tuple[int]\n" + == "load_array_int1(arg0: Tuple[typing.SupportsInt | typing.SupportsIndex]) -> Tuple[int]\n" ) diff --git a/xrpVendordep/src/main/python/pyproject.toml b/xrpVendordep/src/main/python/pyproject.toml index 3a49610691..933afffc1a 100644 --- a/xrpVendordep/src/main/python/pyproject.toml +++ b/xrpVendordep/src/main/python/pyproject.toml @@ -1,7 +1,7 @@ [build-system] build-backend = "hatchling.build" requires = [ - "semiwrap~=0.2.6", + "semiwrap~=0.3.0", "hatch-meson~=0.1.0", "hatch-robotpy~=0.2.1", "hatchling",