mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-19 00:41:41 +00:00
[python] Fixup python examples / build (#2509)
## Description This fixes up and renables the python examples builds. Main fixes - Test shell script just straight up didn't do what it was intended to do - Replace analog imus (and half refactored sims) with OnboardIMU - Fixes swerve velocities function signature - "regenerates" the default robotpy test ## Meta Merge checklist: - [x] Pull Request title is [short, imperative summary](https://cbea.ms/git-commit/) of proposed changes - [x] The description documents the _what_ and _why_, including events that led to this PR - [ ] If this PR changes behavior or adds a feature, user documentation is updated - [ ] If this PR touches photon-serde, all messages have been regenerated and hashes have not changed unexpectedly - [ ] If this PR touches configuration, this is backwards compatible with all settings going back to the previous seasons's last release (seasons end after champs ends) - [ ] If this PR touches pipeline settings or anything related to data exchange, the frontend typing is updated - [ ] If this PR addresses a bug, a regression test for it is added - [ ] If this PR adds a dependency, the license has been checked for compatibility and steps taken to follow it --------- Co-authored-by: Matt Morley <matthew.morley.ca@gmail.com> Co-authored-by: David Vo <auscompgeek@users.noreply.github.com>
This commit is contained in:
79
.github/workflows/python.yml
vendored
79
.github/workflows/python.yml
vendored
@@ -78,55 +78,54 @@ jobs:
|
||||
- name: Run mypy type checking
|
||||
run: mypy --show-column-numbers --config-file photon-lib/py/pyproject.toml photon-lib
|
||||
|
||||
# build-python-examples:
|
||||
# needs: build-py
|
||||
# strategy:
|
||||
# matrix:
|
||||
# os: [ubuntu-24.04, windows-2022, macos-14]
|
||||
# runs-on: ${{ matrix.os }}
|
||||
build-python-examples:
|
||||
needs: build-py
|
||||
strategy:
|
||||
matrix:
|
||||
os: [ubuntu-24.04, windows-2022, macos-14]
|
||||
runs-on: ${{ matrix.os }}
|
||||
|
||||
# steps:
|
||||
steps:
|
||||
|
||||
# - name: Checkout code
|
||||
# uses: actions/checkout@v6
|
||||
# with:
|
||||
# fetch-depth: 0
|
||||
- name: Checkout code
|
||||
uses: actions/checkout@v6
|
||||
with:
|
||||
fetch-depth: 0
|
||||
|
||||
# - name: Set up Python
|
||||
# uses: actions/setup-python@v6
|
||||
# with:
|
||||
# python-version: 3.14
|
||||
- name: Set up Python
|
||||
uses: actions/setup-python@v6
|
||||
with:
|
||||
python-version: 3.14
|
||||
|
||||
# - name: Install dependencies
|
||||
# run: |
|
||||
# python -m pip install --upgrade pip
|
||||
# python -m pip install mypy
|
||||
- name: Install dependencies
|
||||
run: |
|
||||
python -m pip install --upgrade pip
|
||||
python -m pip install mypy
|
||||
|
||||
# - name: Download artifacts
|
||||
# uses: actions/download-artifact@v8
|
||||
# with:
|
||||
# name: dist
|
||||
# path: ./photon-lib/py/dist/
|
||||
- name: Download artifacts
|
||||
uses: actions/download-artifact@v8
|
||||
with:
|
||||
name: dist
|
||||
path: ./photon-lib/py/dist/
|
||||
|
||||
# - name: Install PhotonLibPy package
|
||||
# working-directory: ./photon-lib/py
|
||||
# shell: bash
|
||||
# run: |
|
||||
# pip install --no-cache-dir dist/*.whl
|
||||
- name: Install PhotonLibPy package
|
||||
working-directory: ./photon-lib/py
|
||||
shell: bash
|
||||
run: |
|
||||
pip install --no-cache-dir dist/*.whl
|
||||
|
||||
# - name: Build Python examples
|
||||
# working-directory: photonlib-python-examples
|
||||
# shell: bash
|
||||
# run: |
|
||||
# for folder in */;
|
||||
# do
|
||||
# echo $folder
|
||||
# ./run.sh $folder
|
||||
# done
|
||||
- name: Build Python examples
|
||||
working-directory: photonlib-python-examples
|
||||
shell: bash
|
||||
run: |
|
||||
for folder in */;
|
||||
do
|
||||
echo $folder
|
||||
./test.sh $folder
|
||||
done
|
||||
|
||||
deploy:
|
||||
# TODO: BRING BACK PYTHON EXAMPLES
|
||||
needs: [test-py]
|
||||
needs: [test-py, build-python-examples]
|
||||
runs-on: ubuntu-24.04
|
||||
# Only upload on tags
|
||||
if: startsWith(github.ref, 'refs/tags/v')
|
||||
|
||||
@@ -53,8 +53,8 @@ class Drivetrain:
|
||||
self.debugField = wpilib.Field2d()
|
||||
wpilib.SmartDashboard.putData("Drivetrain Debug", self.debugField)
|
||||
|
||||
self.gyro = wpilib.AnalogGyro(0)
|
||||
self.simGyro = wpilib.simulation.OnboardIMUSim(self.gyro)
|
||||
self.gyro = wpilib.OnboardIMU(wpilib.OnboardIMU.MountOrientation.FLAT)
|
||||
self.simGyro = wpilib.simulation.OnboardIMUSim()
|
||||
self._yaw = 0.0
|
||||
|
||||
self.kinematics = wpimath.SwerveDrive4Kinematics(
|
||||
@@ -77,7 +77,7 @@ class Drivetrain:
|
||||
|
||||
self.targetChassisVelocities = wpimath.ChassisVelocities()
|
||||
|
||||
self.gyro.reset()
|
||||
self.gyro.resetYaw()
|
||||
|
||||
def drive(
|
||||
self,
|
||||
@@ -126,13 +126,20 @@ class Drivetrain:
|
||||
),
|
||||
)
|
||||
|
||||
def getModuleVelocities(self) -> list[wpimath.SwerveModuleVelocity]:
|
||||
return [
|
||||
def getModuleVelocities(
|
||||
self,
|
||||
) -> tuple[
|
||||
wpimath.SwerveModuleVelocity,
|
||||
wpimath.SwerveModuleVelocity,
|
||||
wpimath.SwerveModuleVelocity,
|
||||
wpimath.SwerveModuleVelocity,
|
||||
]:
|
||||
return (
|
||||
self.frontLeft.getVelocity(),
|
||||
self.frontRight.getVelocity(),
|
||||
self.backLeft.getVelocity(),
|
||||
self.backRight.getVelocity(),
|
||||
]
|
||||
)
|
||||
|
||||
def getModulePoses(self) -> list[wpimath.Pose2d]:
|
||||
p = self.odometry.getPose()
|
||||
@@ -197,6 +204,6 @@ class Drivetrain:
|
||||
self.backLeft.simulationPeriodic()
|
||||
self.backRight.simulationPeriodic()
|
||||
rate = -1.0 * self.getChassisVelocities().omega_dps
|
||||
self.simGyro.setRate(rate)
|
||||
self.simGyro.setGyroRateZ(rate)
|
||||
self._yaw += rate * 0.02
|
||||
self.simGyro.setYaw(self._yaw)
|
||||
self.simGyro.setYaw(math.radians(self._yaw))
|
||||
|
||||
@@ -92,6 +92,6 @@ class MyRobot(wpilib.TimedRobot):
|
||||
|
||||
self.swerve.drive(xSpeed, ySpeed, rot, True, self.getPeriod())
|
||||
|
||||
def _simulationPeriodic(self) -> None:
|
||||
def simulationPeriodic(self) -> None:
|
||||
self.swerve.simulationPeriodic()
|
||||
return super()._simulationPeriodic()
|
||||
return super().simulationPeriodic()
|
||||
|
||||
@@ -95,12 +95,16 @@ class SwerveModule:
|
||||
# Simulation Support
|
||||
self.simDriveEncoder = wpilib.simulation.EncoderSim(self.driveEncoder)
|
||||
self.simTurningEncoder = wpilib.simulation.EncoderSim(self.turningEncoder)
|
||||
self.simDrivingMotor = wpilib.simulation.PWMSim(driveMotorChannel)
|
||||
self.simTurningMotor = wpilib.simulation.PWMSim(turningMotorChannel)
|
||||
self.simDrivingMotor = wpilib.simulation.PWMMotorControllerSim(
|
||||
driveMotorChannel
|
||||
)
|
||||
self.simTurningMotor = wpilib.simulation.PWMMotorControllerSim(
|
||||
turningMotorChannel
|
||||
)
|
||||
self.simDrivingMotorFilter = wpimath.LinearFilter.singlePoleIIR(0.1, 0.02)
|
||||
self.simTurningMotorFilter = wpimath.LinearFilter.singlePoleIIR(0.0001, 0.02)
|
||||
self.simTurningEncoderPos = 0
|
||||
self.simDrivingEncoderPos = 0
|
||||
self.simTurningEncoderPos = 0.0
|
||||
self.simDrivingEncoderPos = 0.0
|
||||
|
||||
def getVelocity(self) -> wpimath.SwerveModuleVelocity:
|
||||
"""Returns the current state of the module.
|
||||
@@ -188,10 +192,12 @@ class SwerveModule:
|
||||
|
||||
def simulationPeriodic(self) -> None:
|
||||
driveVoltage = (
|
||||
self.simDrivingMotor.getSpeed() * wpilib.RobotController.getBatteryVoltage()
|
||||
self.simDrivingMotor.getThrottle()
|
||||
* wpilib.RobotController.getBatteryVoltage()
|
||||
)
|
||||
turnVoltage = (
|
||||
self.simTurningMotor.getSpeed() * wpilib.RobotController.getBatteryVoltage()
|
||||
self.simTurningMotor.getThrottle()
|
||||
* wpilib.RobotController.getBatteryVoltage()
|
||||
)
|
||||
driveSpdRaw = (
|
||||
driveVoltage / 12.0 * self.driveFeedforward.maxAchievableVelocity(12.0, 0)
|
||||
|
||||
@@ -1,4 +0,0 @@
|
||||
"""
|
||||
This test module imports tests that come with pyfrc, and can be used
|
||||
to test basic functionality of just about any robot.
|
||||
"""
|
||||
@@ -0,0 +1,6 @@
|
||||
"""
|
||||
This test module imports tests that come with wpilib, and can be used
|
||||
to test basic functionality of just about any robot.
|
||||
"""
|
||||
|
||||
from wpilib.testing.robot_tests import * # noqa
|
||||
@@ -53,8 +53,8 @@ class Drivetrain:
|
||||
self.debugField = wpilib.Field2d()
|
||||
wpilib.SmartDashboard.putData("Drivetrain Debug", self.debugField)
|
||||
|
||||
self.gyro = wpilib.AnalogGyro(0)
|
||||
self.simGyro = wpilib.simulation.OnboardIMUSim(self.gyro)
|
||||
self.gyro = wpilib.OnboardIMU(wpilib.OnboardIMU.MountOrientation.FLAT)
|
||||
self.simGyro = wpilib.simulation.OnboardIMUSim()
|
||||
self._yaw = 0.0
|
||||
|
||||
self.kinematics = wpimath.SwerveDrive4Kinematics(
|
||||
@@ -77,7 +77,7 @@ class Drivetrain:
|
||||
|
||||
self.targetChassisVelocities = wpimath.ChassisVelocities()
|
||||
|
||||
self.gyro.reset()
|
||||
self.gyro.resetYaw()
|
||||
|
||||
def drive(
|
||||
self,
|
||||
@@ -126,13 +126,20 @@ class Drivetrain:
|
||||
),
|
||||
)
|
||||
|
||||
def getModuleVelocities(self) -> list[wpimath.SwerveModuleVelocity]:
|
||||
return [
|
||||
def getModuleVelocities(
|
||||
self,
|
||||
) -> tuple[
|
||||
wpimath.SwerveModuleVelocity,
|
||||
wpimath.SwerveModuleVelocity,
|
||||
wpimath.SwerveModuleVelocity,
|
||||
wpimath.SwerveModuleVelocity,
|
||||
]:
|
||||
return (
|
||||
self.frontLeft.getVelocity(),
|
||||
self.frontRight.getVelocity(),
|
||||
self.backLeft.getVelocity(),
|
||||
self.backRight.getVelocity(),
|
||||
]
|
||||
)
|
||||
|
||||
def getModulePoses(self) -> list[wpimath.Pose2d]:
|
||||
p = self.odometry.getPose()
|
||||
@@ -197,6 +204,6 @@ class Drivetrain:
|
||||
self.backLeft.simulationPeriodic()
|
||||
self.backRight.simulationPeriodic()
|
||||
rate = -1.0 * self.getChassisVelocities().omega_dps
|
||||
self.simGyro.setRate(rate)
|
||||
self.simGyro.setGyroRateZ(rate)
|
||||
self._yaw += rate * 0.02
|
||||
self.simGyro.setYaw(self._yaw)
|
||||
self.simGyro.setYaw(math.radians(self._yaw))
|
||||
|
||||
@@ -69,6 +69,6 @@ class MyRobot(wpilib.TimedRobot):
|
||||
|
||||
self.swerve.drive(xSpeed, ySpeed, rot, True, self.getPeriod())
|
||||
|
||||
def _simulationPeriodic(self) -> None:
|
||||
def simulationPeriodic(self) -> None:
|
||||
self.swerve.simulationPeriodic()
|
||||
return super()._simulationPeriodic()
|
||||
return super().simulationPeriodic()
|
||||
|
||||
@@ -95,12 +95,16 @@ class SwerveModule:
|
||||
# Simulation Support
|
||||
self.simDriveEncoder = wpilib.simulation.EncoderSim(self.driveEncoder)
|
||||
self.simTurningEncoder = wpilib.simulation.EncoderSim(self.turningEncoder)
|
||||
self.simDrivingMotor = wpilib.simulation.PWMSim(driveMotorChannel)
|
||||
self.simTurningMotor = wpilib.simulation.PWMSim(turningMotorChannel)
|
||||
self.simDrivingMotor = wpilib.simulation.PWMMotorControllerSim(
|
||||
driveMotorChannel
|
||||
)
|
||||
self.simTurningMotor = wpilib.simulation.PWMMotorControllerSim(
|
||||
turningMotorChannel
|
||||
)
|
||||
self.simDrivingMotorFilter = wpimath.LinearFilter.singlePoleIIR(0.1, 0.02)
|
||||
self.simTurningMotorFilter = wpimath.LinearFilter.singlePoleIIR(0.0001, 0.02)
|
||||
self.simTurningEncoderPos = 0
|
||||
self.simDrivingEncoderPos = 0
|
||||
self.simTurningEncoderPos = 0.0
|
||||
self.simDrivingEncoderPos = 0.0
|
||||
|
||||
def getVelocity(self) -> wpimath.SwerveModuleVelocity:
|
||||
"""Returns the current state of the module.
|
||||
@@ -188,10 +192,12 @@ class SwerveModule:
|
||||
|
||||
def simulationPeriodic(self) -> None:
|
||||
driveVoltage = (
|
||||
self.simDrivingMotor.getSpeed() * wpilib.RobotController.getBatteryVoltage()
|
||||
self.simDrivingMotor.getThrottle()
|
||||
* wpilib.RobotController.getBatteryVoltage()
|
||||
)
|
||||
turnVoltage = (
|
||||
self.simTurningMotor.getSpeed() * wpilib.RobotController.getBatteryVoltage()
|
||||
self.simTurningMotor.getThrottle()
|
||||
* wpilib.RobotController.getBatteryVoltage()
|
||||
)
|
||||
driveSpdRaw = (
|
||||
driveVoltage / 12.0 * self.driveFeedforward.maxAchievableVelocity(12.0, 0)
|
||||
|
||||
@@ -1,4 +0,0 @@
|
||||
"""
|
||||
This test module imports tests that come with pyfrc, and can be used
|
||||
to test basic functionality of just about any robot.
|
||||
"""
|
||||
@@ -0,0 +1,6 @@
|
||||
"""
|
||||
This test module imports tests that come with wpilib, and can be used
|
||||
to test basic functionality of just about any robot.
|
||||
"""
|
||||
|
||||
from wpilib.testing.robot_tests import * # noqa
|
||||
@@ -58,8 +58,8 @@ class Drivetrain:
|
||||
self.debugField = wpilib.Field2d()
|
||||
wpilib.SmartDashboard.putData("Drivetrain Debug", self.debugField)
|
||||
|
||||
self.gyro = wpilib.AnalogGyro(0)
|
||||
self.simGyro = wpilib.simulation.OnboardIMUSim(self.gyro)
|
||||
self.gyro = wpilib.OnboardIMU(wpilib.OnboardIMU.MountOrientation.FLAT)
|
||||
self.simGyro = wpilib.simulation.OnboardIMUSim()
|
||||
self._yaw = 0.0
|
||||
|
||||
self.kinematics = wpimath.SwerveDrive4Kinematics(
|
||||
@@ -78,11 +78,12 @@ class Drivetrain:
|
||||
self.backLeft.getPosition(),
|
||||
self.backRight.getPosition(),
|
||||
),
|
||||
wpimath.Pose2d(),
|
||||
)
|
||||
|
||||
self.targetChassisVelocities = wpimath.ChassisVelocities()
|
||||
|
||||
self.gyro.reset()
|
||||
self.gyro.resetYaw()
|
||||
|
||||
def drive(
|
||||
self,
|
||||
@@ -121,7 +122,7 @@ class Drivetrain:
|
||||
|
||||
def updateOdometry(self) -> None:
|
||||
"""Updates the field relative position of the robot."""
|
||||
self.odometry.update(
|
||||
self.poseEst.update(
|
||||
self.gyro.getRotation2d(),
|
||||
(
|
||||
self.frontLeft.getPosition(),
|
||||
@@ -132,7 +133,7 @@ class Drivetrain:
|
||||
)
|
||||
|
||||
def addVisionPoseEstimate(self, pose: wpimath.Pose3d, timestamp: float) -> None:
|
||||
self.poseEst.addVisionMeasurement(pose, timestamp)
|
||||
self.poseEst.addVisionMeasurement(pose.toPose2d(), timestamp)
|
||||
|
||||
def resetPose(self) -> None:
|
||||
self.poseEst.resetPosition(
|
||||
@@ -146,13 +147,20 @@ class Drivetrain:
|
||||
kInitialPose,
|
||||
)
|
||||
|
||||
def getModuleVelocities(self) -> list[wpimath.SwerveModuleVelocity]:
|
||||
return [
|
||||
def getModuleVelocities(
|
||||
self,
|
||||
) -> tuple[
|
||||
wpimath.SwerveModuleVelocity,
|
||||
wpimath.SwerveModuleVelocity,
|
||||
wpimath.SwerveModuleVelocity,
|
||||
wpimath.SwerveModuleVelocity,
|
||||
]:
|
||||
return (
|
||||
self.frontLeft.getVelocity(),
|
||||
self.frontRight.getVelocity(),
|
||||
self.backLeft.getVelocity(),
|
||||
self.backRight.getVelocity(),
|
||||
]
|
||||
)
|
||||
|
||||
def getModulePoses(self) -> list[wpimath.Pose2d]:
|
||||
p = self.poseEst.getEstimatedPosition()
|
||||
@@ -181,7 +189,7 @@ class Drivetrain:
|
||||
def log(self):
|
||||
table = "Drive/"
|
||||
|
||||
pose = self.odometry.getPose()
|
||||
pose = self.poseEst.getEstimatedPosition()
|
||||
wpilib.SmartDashboard.putNumber(table + "X", pose.X())
|
||||
wpilib.SmartDashboard.putNumber(table + "Y", pose.Y())
|
||||
wpilib.SmartDashboard.putNumber(table + "Heading", pose.rotation().degrees())
|
||||
@@ -208,7 +216,7 @@ class Drivetrain:
|
||||
self.backLeft.log()
|
||||
self.backRight.log()
|
||||
|
||||
self.debugField.getRobotObject().setPose(self.odometry.getPose())
|
||||
self.debugField.getRobotObject().setPose(self.poseEst.getEstimatedPosition())
|
||||
self.debugField.getObject("SwerveModules").setPoses(self.getModulePoses())
|
||||
|
||||
def simulationPeriodic(self):
|
||||
@@ -217,6 +225,6 @@ class Drivetrain:
|
||||
self.backLeft.simulationPeriodic()
|
||||
self.backRight.simulationPeriodic()
|
||||
rate = -1.0 * self.getChassisVelocities().omega_dps
|
||||
self.simGyro.setRate(rate)
|
||||
self.simGyro.setGyroRateZ(rate)
|
||||
self._yaw += rate * 0.02
|
||||
self.simGyro.setYaw(self._yaw)
|
||||
self.simGyro.setYaw(math.radians(self._yaw))
|
||||
|
||||
@@ -55,9 +55,10 @@ class MyRobot(wpilib.TimedRobot):
|
||||
if camEstPose is None:
|
||||
camEstPose = self.camPoseEst.estimateLowestAmbiguityPose(result)
|
||||
|
||||
self.swerve.addVisionPoseEstimate(
|
||||
camEstPose.estimatedPose, camEstPose.timestampSeconds
|
||||
)
|
||||
if camEstPose:
|
||||
self.swerve.addVisionPoseEstimate(
|
||||
camEstPose.estimatedPose, camEstPose.timestampSeconds
|
||||
)
|
||||
|
||||
self.swerve.updateOdometry()
|
||||
self.swerve.log()
|
||||
@@ -69,6 +70,6 @@ class MyRobot(wpilib.TimedRobot):
|
||||
|
||||
self.swerve.drive(xSpeed, ySpeed, rot, True, self.getPeriod())
|
||||
|
||||
def _simulationPeriodic(self) -> None:
|
||||
def simulationPeriodic(self) -> None:
|
||||
self.swerve.simulationPeriodic()
|
||||
return super()._simulationPeriodic()
|
||||
return super().simulationPeriodic()
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
Speeds ###################################################################################
|
||||
###################################################################################
|
||||
# MIT License
|
||||
#
|
||||
# Copyright (c) PhotonVision
|
||||
@@ -95,12 +95,16 @@ class SwerveModule:
|
||||
# Simulation Support
|
||||
self.simDriveEncoder = wpilib.simulation.EncoderSim(self.driveEncoder)
|
||||
self.simTurningEncoder = wpilib.simulation.EncoderSim(self.turningEncoder)
|
||||
self.simDrivingMotor = wpilib.simulation.PWMSim(driveMotorChannel)
|
||||
self.simTurningMotor = wpilib.simulation.PWMSim(turningMotorChannel)
|
||||
self.simDrivingMotor = wpilib.simulation.PWMMotorControllerSim(
|
||||
driveMotorChannel
|
||||
)
|
||||
self.simTurningMotor = wpilib.simulation.PWMMotorControllerSim(
|
||||
turningMotorChannel
|
||||
)
|
||||
self.simDrivingMotorFilter = wpimath.LinearFilter.singlePoleIIR(0.1, 0.02)
|
||||
self.simTurningMotorFilter = wpimath.LinearFilter.singlePoleIIR(0.0001, 0.02)
|
||||
self.simTurningEncoderPos = 0
|
||||
self.simDrivingEncoderPos = 0
|
||||
self.simTurningEncoderPos = 0.0
|
||||
self.simDrivingEncoderPos = 0.0
|
||||
|
||||
def getVelocity(self) -> wpimath.SwerveModuleVelocity:
|
||||
"""Returns the current state of the module.
|
||||
@@ -155,6 +159,10 @@ class SwerveModule:
|
||||
self.turningEncoder.getDistance(), self.desiredVelocity.angle.radians()
|
||||
)
|
||||
|
||||
turnFeedforward = self.turnFeedforward.calculate(
|
||||
self.turningPIDController.getSetpoint()
|
||||
)
|
||||
|
||||
self.driveMotor.setVoltage(driveOutput + driveFeedforward)
|
||||
self.turningMotor.setVoltage(turnOutput + turnFeedforward)
|
||||
|
||||
@@ -188,10 +196,12 @@ class SwerveModule:
|
||||
|
||||
def simulationPeriodic(self) -> None:
|
||||
driveVoltage = (
|
||||
self.simDrivingMotor.getSpeed() * wpilib.RobotController.getBatteryVoltage()
|
||||
self.simDrivingMotor.getThrottle()
|
||||
* wpilib.RobotController.getBatteryVoltage()
|
||||
)
|
||||
turnVoltage = (
|
||||
self.simTurningMotor.getSpeed() * wpilib.RobotController.getBatteryVoltage()
|
||||
self.simTurningMotor.getThrottle()
|
||||
* wpilib.RobotController.getBatteryVoltage()
|
||||
)
|
||||
driveSpdRaw = (
|
||||
driveVoltage / 12.0 * self.driveFeedforward.maxAchievableVelocity(12.0, 0)
|
||||
|
||||
@@ -1,4 +0,0 @@
|
||||
"""
|
||||
This test module imports tests that come with pyfrc, and can be used
|
||||
to test basic functionality of just about any robot.
|
||||
"""
|
||||
6
photonlib-python-examples/poseest/tests/robot_test.py
Normal file
6
photonlib-python-examples/poseest/tests/robot_test.py
Normal file
@@ -0,0 +1,6 @@
|
||||
"""
|
||||
This test module imports tests that come with wpilib, and can be used
|
||||
to test basic functionality of just about any robot.
|
||||
"""
|
||||
|
||||
from wpilib.testing.robot_tests import * # noqa
|
||||
@@ -11,4 +11,4 @@ cd $1
|
||||
|
||||
# Run the example
|
||||
mypy --show-column-numbers --config-file ../../photon-lib/py/pyproject.toml .
|
||||
python3 robot.py sim
|
||||
python3 -m robotpy sim
|
||||
|
||||
14
photonlib-python-examples/test.sh
Executable file
14
photonlib-python-examples/test.sh
Executable file
@@ -0,0 +1,14 @@
|
||||
set -e
|
||||
# Check if the first argument is provided
|
||||
if [ $# -eq 0 ]
|
||||
then
|
||||
echo "Error: No example-to-run provided."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
# Move to the right example folder
|
||||
cd $1
|
||||
|
||||
# Run the example
|
||||
mypy --show-column-numbers --config-file ../../photon-lib/py/pyproject.toml .
|
||||
python3 -m robotpy test
|
||||
Reference in New Issue
Block a user