From 80d82c1a9b8eb02868f43d8d25cb26ed328beee1 Mon Sep 17 00:00:00 2001 From: Matt Morley Date: Tue, 12 Nov 2024 23:41:00 -0800 Subject: [PATCH] oops --- .github/workflows/build.yml | 15 ++++++++++++++- .../src/main/java/frc/robot/Robot.java | 14 +++++++------- 2 files changed, 21 insertions(+), 8 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index c9358ba9a3..428d789e41 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -39,7 +39,20 @@ jobs: name: built-client path: photon-client/dist/ build-examples: - name: "Build Examples" + + strategy: + fail-fast: false + matrix: + include: + - os: windows-2022 + architecture: x64 + - os: macos-14 + architecture: aarch64 + - os: ubuntu-22.04 + + name: "Photonlib - Build Examples - ${{ matrix.os }}" + runs-on: ${{ matrix.os }} + runs-on: ubuntu-22.04 steps: - name: Checkout code diff --git a/photonlib-java-examples/aimattarget/src/main/java/frc/robot/Robot.java b/photonlib-java-examples/aimattarget/src/main/java/frc/robot/Robot.java index a003ca849a..d48b79039a 100644 --- a/photonlib-java-examples/aimattarget/src/main/java/frc/robot/Robot.java +++ b/photonlib-java-examples/aimattarget/src/main/java/frc/robot/Robot.java @@ -39,7 +39,7 @@ public class Robot extends TimedRobot { private SwerveDrive drivetrain; - // private VisionSim visionSim; + private VisionSim visionSim; private PhotonCamera camera; private final double VISION_TURN_kP = 0.01; @@ -54,7 +54,7 @@ public void robotInit() { if (!TimeSyncSingleton.load()) { System.exit(-111); } - // visionSim = new VisionSim(camera); + visionSim = new VisionSim(camera); controller = new XboxController(0); } @@ -126,11 +126,11 @@ public void simulationPeriodic() { drivetrain.simulationPeriodic(); // Update camera simulation - // visionSim.simulationPeriodic(drivetrain.getSimPose()); + visionSim.simulationPeriodic(drivetrain.getSimPose()); - // var debugField = visionSim.getSimDebugField(); - // debugField.getObject("EstimatedRobot").setPose(drivetrain.getPose()); - // debugField.getObject("EstimatedRobotModules").setPoses(drivetrain.getModulePoses()); + var debugField = visionSim.getSimDebugField(); + debugField.getObject("EstimatedRobot").setPose(drivetrain.getPose()); + debugField.getObject("EstimatedRobotModules").setPoses(drivetrain.getModulePoses()); // Calculate battery voltage sag due to current draw RoboRioSim.setVInVoltage( @@ -143,6 +143,6 @@ public void resetPose() { // The first pose in an autonomous path is often a good choice. var startPose = new Pose2d(1, 1, new Rotation2d()); drivetrain.resetPose(startPose, true); - // visionSim.resetSimPose(startPose); + visionSim.resetSimPose(startPose); } }