From cd92e5f28f84dbe3e9eb04c0ccb46e58270a9fff Mon Sep 17 00:00:00 2001 From: Matt Date: Sat, 21 Sep 2024 14:42:55 -0700 Subject: [PATCH] Hack in time sync --- .github/workflows/lint-format.yml | 2 +- .../networktables/NTDataPublisher.java | 13 ++-- .../networktables/NetworkTablesManager.java | 6 ++ .../common/util/math/MathUtils.java | 4 +- .../frame/provider/USBFrameProvider.java | 1 + photon-lib/build.gradle | 25 +++++++ .../org/photonvision/PhotonCameraTest.java | 70 +++++++++++++++++++ .../src/main/java/org/photonvision/Main.java | 16 ++++- ...der.java => PhotonTargetingJniLoader.java} | 15 ++-- .../org/photonvision/jni/TimeSyncClient.java | 18 +++++ .../targeting/PhotonPipelineResult.java | 6 +- .../native/cpp/net/TimeSyncClientServer.cpp | 40 +++++------ .../proto/MultiTargetPNPResultProto.cpp | 2 + .../src/main/native/jni/TimeSyncClientJNI.cpp | 1 + .../src/test/java/net/TimeSyncTest.java | 4 +- .../src/test/native/cpp/PacketTest.cpp | 1 + .../src/test/native/cpp/net/TimeSyncTest.cpp | 18 ++--- .../aimandrange/robot.py | 2 - .../aimandrange/tests/pyfrc_test.py | 2 - .../aimattarget/tests/pyfrc_test.py | 2 - .../poseest/tests/pyfrc_test.py | 2 - 21 files changed, 190 insertions(+), 60 deletions(-) rename photon-targeting/src/main/java/org/photonvision/jni/{TimeSyncJNILoader.java => PhotonTargetingJniLoader.java} (80%) diff --git a/.github/workflows/lint-format.yml b/.github/workflows/lint-format.yml index fb97eb77af..09f86fc6c6 100644 --- a/.github/workflows/lint-format.yml +++ b/.github/workflows/lint-format.yml @@ -37,7 +37,7 @@ jobs: with: python-version: 3.11 - name: Install wpiformat - run: pip3 install wpiformat==2024.37 + run: pip3 install wpiformat==2024.41 - name: Run run: wpiformat - name: Check output diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java index 11aa38852b..0d64eb5cb8 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java @@ -19,7 +19,7 @@ import edu.wpi.first.networktables.NetworkTable; import edu.wpi.first.networktables.NetworkTableEvent; -import edu.wpi.first.util.WPIUtilJNI; +import edu.wpi.first.networktables.NetworkTablesJNI; import java.util.function.BooleanSupplier; import java.util.function.Consumer; import java.util.function.Supplier; @@ -129,16 +129,21 @@ public void updateCameraNickname(String newCameraNickname) { @Override public void accept(CVPipelineResult result) { - var now = WPIUtilJNI.now(); + var now = NetworkTablesJNI.now(); + + var offset = NetworkTablesManager.getInstance().m_timeSyncClient.getOffset(); + var captureMicros = MathUtils.nanosToMicros(result.getImageCaptureTimestampNanos()); var simplified = new PhotonPipelineResult( result.sequenceID, - captureMicros, - now, + captureMicros + offset, + now + offset, TrackedTarget.simpleFromTrackedTargets(result.targets), result.multiTagResult); + // System.out.println(simplified.metadata); + // random guess at size of the array ts.resultPublisher.set(simplified, 1024); if (ConfigManager.getInstance().getConfig().getNetworkConfig().shouldPublishProto) { diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java index 4cd2d1e0bd..2769c9aa27 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java @@ -39,6 +39,7 @@ import org.photonvision.common.scripting.ScriptManager; import org.photonvision.common.util.TimedTaskManager; import org.photonvision.common.util.file.JacksonUtils; +import org.photonvision.jni.TimeSyncClient; public class NetworkTablesManager { private final NetworkTableInstance ntInstance = NetworkTableInstance.getDefault(); @@ -53,7 +54,12 @@ public class NetworkTablesManager { private StringSubscriber m_fieldLayoutSubscriber = kRootTable.getStringTopic(kFieldLayoutName).subscribe(""); + public TimeSyncClient m_timeSyncClient; + private NetworkTablesManager() { + m_timeSyncClient = new TimeSyncClient("127.0.0.1", 5812, 1.0); + m_timeSyncClient.start(); + ntInstance.addLogger(255, 255, (event) -> {}); // to hide error messages ntInstance.addConnectionListener(true, m_ntLogger); // to hide error messages diff --git a/photon-core/src/main/java/org/photonvision/common/util/math/MathUtils.java b/photon-core/src/main/java/org/photonvision/common/util/math/MathUtils.java index 5efb81ef24..167effaea5 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/math/MathUtils.java +++ b/photon-core/src/main/java/org/photonvision/common/util/math/MathUtils.java @@ -25,7 +25,7 @@ import edu.wpi.first.math.geometry.Transform3d; import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.math.util.Units; -import edu.wpi.first.util.WPIUtilJNI; +import edu.wpi.first.networktables.NetworkTablesJNI; import java.util.Arrays; import java.util.List; import org.opencv.core.Core; @@ -98,7 +98,7 @@ public static int map(int value, int inMin, int inMax, int outMin, int outMax) { } public static long wpiNanoTime() { - return microsToNanos(WPIUtilJNI.now()); + return microsToNanos(NetworkTablesJNI.now()); } /** diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java index 5cc5e3cbaf..7198f264c5 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java @@ -45,6 +45,7 @@ public CapturedFrame getInputMat() { long time = cvSink.grabFrame(mat.getMat()) * 1000; // Units are microseconds, epoch is the same as the Unix epoch + // this -should- be the same timebase as nt::now? if (time == 0) { var error = cvSink.getError(); diff --git a/photon-lib/build.gradle b/photon-lib/build.gradle index 455bde947d..6b9d1f04e3 100644 --- a/photon-lib/build.gradle +++ b/photon-lib/build.gradle @@ -1,3 +1,7 @@ +plugins { + id 'edu.wpi.first.WpilibTools' version '1.3.0' +} + import java.nio.file.Path ext { @@ -314,3 +318,24 @@ publishing { } } } + +// setup wpilib bundled native libs +wpilibTools.deps.wpilibVersion = wpi.versions.wpilibVersion.get() + +def nativeConfigName = 'wpilibNatives' +def nativeConfig = configurations.create(nativeConfigName) + +def nativeTasks = wpilibTools.createExtractionTasks { + configurationName = nativeConfigName +} + +nativeTasks.addToSourceSetResources(sourceSets.test) + +nativeConfig.dependencies.add wpilibTools.deps.wpilib("wpimath") +nativeConfig.dependencies.add wpilibTools.deps.wpilib("wpinet") +nativeConfig.dependencies.add wpilibTools.deps.wpilib("wpiutil") +nativeConfig.dependencies.add wpilibTools.deps.wpilib("ntcore") +nativeConfig.dependencies.add wpilibTools.deps.wpilib("cscore") +nativeConfig.dependencies.add wpilibTools.deps.wpilib("apriltag") +nativeConfig.dependencies.add wpilibTools.deps.wpilib("hal") +nativeConfig.dependencies.add wpilibTools.deps.wpilibOpenCv("frc" + wpi.frcYear.get(), wpi.versions.opencvVersion.get()) diff --git a/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java b/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java index 4b02a8d76b..a0ab071352 100644 --- a/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java +++ b/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java @@ -24,12 +24,56 @@ package org.photonvision; +import static org.junit.jupiter.api.Assertions.assertTrue; + +import edu.wpi.first.apriltag.jni.AprilTagJNI; +import edu.wpi.first.cscore.CameraServerCvJNI; +import edu.wpi.first.cscore.CameraServerJNI; +import edu.wpi.first.hal.HAL; +import edu.wpi.first.hal.JNIWrapper; +import edu.wpi.first.math.WPIMathJNI; +import edu.wpi.first.net.WPINetJNI; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.networktables.NetworkTablesJNI; +import edu.wpi.first.util.CombinedRuntimeLoader; +import edu.wpi.first.util.WPIUtilJNI; +import edu.wpi.first.wpilibj.Timer; +import java.io.IOException; import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.Test; +import org.opencv.core.Core; import org.photonvision.common.dataflow.structures.Packet; +import org.photonvision.jni.PhotonTargetingJniLoader; +import org.photonvision.jni.TimeSyncServer; import org.photonvision.targeting.PhotonPipelineResult; class PhotonCameraTest { + public static void load_wpilib() { + NetworkTablesJNI.Helper.setExtractOnStaticLoad(false); + WPIUtilJNI.Helper.setExtractOnStaticLoad(false); + WPIMathJNI.Helper.setExtractOnStaticLoad(false); + CameraServerJNI.Helper.setExtractOnStaticLoad(false); + CameraServerCvJNI.Helper.setExtractOnStaticLoad(false); + JNIWrapper.Helper.setExtractOnStaticLoad(false); + WPINetJNI.Helper.setExtractOnStaticLoad(false); + AprilTagJNI.Helper.setExtractOnStaticLoad(false); + + try { + CombinedRuntimeLoader.loadLibraries( + PhotonCameraTest.class, + "wpiutiljni", + "wpimathjni", + "ntcorejni", + "wpinetjni", + "wpiHaljni", + Core.NATIVE_LIBRARY_NAME, + "cscorejni", + "apriltagjni"); + } catch (IOException e) { + e.printStackTrace(); + } + } + @Test public void testEmpty() { Assertions.assertDoesNotThrow( @@ -40,4 +84,30 @@ public void testEmpty() { PhotonPipelineResult.photonStruct.pack(packet, ret); }); } + + @Test + public void testMeme() throws InterruptedException, IOException { + load_wpilib(); + PhotonTargetingJniLoader.load(); + + HAL.initialize(500, 0); + + NetworkTableInstance.getDefault().stopClient(); + NetworkTableInstance.getDefault().startServer(); + + var server = new TimeSyncServer(5812); + server.start(); + + var camera = new PhotonCamera("Microsoft_LifeCam_HD-3000"); + PhotonCamera.setVersionCheckEnabled(false); + + for (int i = 0; i < 100; i++) { + Thread.sleep(100); + + var captureTime = camera.getLatestResult().getTimestampSeconds(); + var now = Timer.getFPGATimestamp(); + + assertTrue(captureTime < now); + } + } } diff --git a/photon-server/src/main/java/org/photonvision/Main.java b/photon-server/src/main/java/org/photonvision/Main.java index 9dd5e7ad70..b6b278615a 100644 --- a/photon-server/src/main/java/org/photonvision/Main.java +++ b/photon-server/src/main/java/org/photonvision/Main.java @@ -39,6 +39,7 @@ import org.photonvision.common.networking.NetworkManager; import org.photonvision.common.util.TestUtils; import org.photonvision.common.util.numbers.IntegerCouple; +import org.photonvision.jni.PhotonTargetingJniLoader; import org.photonvision.jni.RknnDetectorJNI; import org.photonvision.mrcal.MrCalJNILoader; import org.photonvision.raspi.LibCameraJNILoader; @@ -379,7 +380,20 @@ public static void main(String[] args) { logger.error("Failed to load native libraries!", e); System.exit(1); } - logger.info("Native libraries loaded."); + logger.info("WPI JNI libraries loaded."); + + try { + boolean success = PhotonTargetingJniLoader.load(); + + if (!success) { + logger.error("Failed to load PhotonTargetingJni"); + System.exit(1); + } + } catch (Exception e) { + logger.error("Failed to load native libraries!", e); + System.exit(1); + } + logger.info("PhotonTargeting JNI loaded"); try { if (Platform.isRaspberryPi()) { diff --git a/photon-targeting/src/main/java/org/photonvision/jni/TimeSyncJNILoader.java b/photon-targeting/src/main/java/org/photonvision/jni/PhotonTargetingJniLoader.java similarity index 80% rename from photon-targeting/src/main/java/org/photonvision/jni/TimeSyncJNILoader.java rename to photon-targeting/src/main/java/org/photonvision/jni/PhotonTargetingJniLoader.java index 7877a41a65..943ee1d5a4 100644 --- a/photon-targeting/src/main/java/org/photonvision/jni/TimeSyncJNILoader.java +++ b/photon-targeting/src/main/java/org/photonvision/jni/PhotonTargetingJniLoader.java @@ -20,27 +20,30 @@ import java.io.File; import java.io.FileOutputStream; import java.io.IOException; +import java.nio.file.Files; import java.util.List; import org.photonvision.common.hardware.Platform; -public class TimeSyncJNILoader { - public static void load() throws IOException { +public class PhotonTargetingJniLoader { + public static boolean load() throws IOException { // We always extract the shared object (we could hash each so, but that's a lot // of work) String arch_name = Platform.getNativeLibraryFolderName(); - var clazz = TimeSyncJNILoader.class; + var clazz = PhotonTargetingJniLoader.class; for (var libraryName : List.of("photontargeting", "photontargetingJNI")) { var nativeLibName = System.mapLibraryName(libraryName); var in = clazz.getResourceAsStream("/nativelibraries/" + arch_name + "/" + nativeLibName); if (in == null) { - return; + return false; } // It's important that we don't mangle the names of these files on Windows at // least - File temp = new File(System.getProperty("java.io.tmpdir"), nativeLibName); + var tempfolder = Files.createTempDirectory("nativeextract"); + File temp = new File(tempfolder.toAbsolutePath().toString(), nativeLibName); + System.out.println(temp.getAbsolutePath().toString()); FileOutputStream fos = new FileOutputStream(temp); int read = -1; @@ -55,5 +58,7 @@ public static void load() throws IOException { System.out.println("Successfully loaded shared object " + temp.getName()); } + + return true; } } diff --git a/photon-targeting/src/main/java/org/photonvision/jni/TimeSyncClient.java b/photon-targeting/src/main/java/org/photonvision/jni/TimeSyncClient.java index 06f355a3fa..4dbf46efe5 100644 --- a/photon-targeting/src/main/java/org/photonvision/jni/TimeSyncClient.java +++ b/photon-targeting/src/main/java/org/photonvision/jni/TimeSyncClient.java @@ -17,6 +17,9 @@ package org.photonvision.jni; +import edu.wpi.first.networktables.NetworkTablesJNI; + +/** Send ping-pongs to estimate server time, relative to nt::now */ public class TimeSyncClient { public static class PingMetadata { long offset; @@ -39,10 +42,25 @@ public void stop() { TimeSyncClient.stop(handle); } + /** + * This offset, when added to the current value of nt::now(), yields the timestamp in the timebase + * of the TSP Server + * + * @return + */ public long getOffset() { return TimeSyncClient.getOffset(handle); } + /** + * Best estimate of the current timestamp at the TSP server + * + * @return + */ + public long currentServerTimestamp() { + return NetworkTablesJNI.now() + getOffset(); + } + private static native long create(String serverIP, int serverPort, double pingIntervalSeconds); private static native void start(long handle); diff --git a/photon-targeting/src/main/java/org/photonvision/targeting/PhotonPipelineResult.java b/photon-targeting/src/main/java/org/photonvision/targeting/PhotonPipelineResult.java index 75a4882291..3936e1470d 100644 --- a/photon-targeting/src/main/java/org/photonvision/targeting/PhotonPipelineResult.java +++ b/photon-targeting/src/main/java/org/photonvision/targeting/PhotonPipelineResult.java @@ -169,12 +169,10 @@ public Optional getMultiTagResult() { * @return The timestamp in seconds */ public double getTimestampSeconds() { - return (ntReceiveTimestampMicros - - (metadata.publishTimestampMicros - metadata.captureTimestampMicros)) - / 1e6; + return metadata.captureTimestampMicros / 1e6; } - /** The time that the robot Received this result, in the FPGA timebase. */ + /** The time that the robot received this result, in the FPGA timebase. */ public long getNtReceiveTimestampMicros() { return ntReceiveTimestampMicros; } diff --git a/photon-targeting/src/main/native/cpp/net/TimeSyncClientServer.cpp b/photon-targeting/src/main/native/cpp/net/TimeSyncClientServer.cpp index 749af13e94..6c5d286e55 100644 --- a/photon-targeting/src/main/native/cpp/net/TimeSyncClientServer.cpp +++ b/photon-targeting/src/main/native/cpp/net/TimeSyncClientServer.cpp @@ -174,24 +174,21 @@ wpi::TimeSyncServer::TimeSyncServer(int port, : m_logger{::ServerLoggerFunc}, m_timeProvider{timeProvider}, m_udp{wpi::uv::Udp::Create(m_loopRunner.GetLoop(), AF_INET)} { - m_udp->Bind("0.0.0.0", port); + m_loopRunner.ExecSync( + [this, port](uv::Loop&) { m_udp->Bind("0.0.0.0", port); }); } void wpi::TimeSyncServer::Start() { - m_udp->received.connect(&wpi::TimeSyncServer::UdpCallback, this); - m_udp->StartRecv(); + m_loopRunner.ExecSync([this](uv::Loop&) { + m_udp->received.connect(&wpi::TimeSyncServer::UdpCallback, this); + m_udp->StartRecv(); + }); } void wpi::TimeSyncServer::Stop() { m_loopRunner.Stop(); } void wpi::TimeSyncClient::Tick() { fmt::println("wpi::TimeSyncClient::Tick"); - - if (!m_udp) { - fmt::println("m_udp is null"); - return; - } - // Regardless of if we've gotten a pong back yet, we'll ping again. this is // pretty naive but should be "fine" for now? @@ -205,17 +202,10 @@ void wpi::TimeSyncClient::Tick() { // Wrap our buffer - pingData should free itself wpi::uv::Buffer pingBuf{pingData}; - - int sent = 0; - try { - sent = m_udp->TrySend(wpi::SmallVector{pingBuf}); - } catch (std::exception& e) { - fmt::println("????: {}", e.what()); - return; - } + int sent = m_udp->TrySend(wpi::SmallVector{pingBuf}); if (static_cast(sent) != wpi::Struct::GetSize()) { - WPI_ERROR(m_logger, "Didn't send the whole ping out?"); + WPI_ERROR(m_logger, "Didn't send the whole ping out? sent {} bytes", sent); return; } @@ -292,16 +282,22 @@ wpi::TimeSyncClient::TimeSyncClient(std::string_view server, int remote_port, m_serverIP{server}, m_serverPort{remote_port}, m_loopDelay(ping_delay) { - fmt::println("Connecting to server at {}:{}", m_serverIP, m_serverPort); struct sockaddr_in serverAddr; uv::NameToAddr(m_serverIP, m_serverPort, &serverAddr); - m_udp->Connect(serverAddr); + + m_loopRunner.ExecSync( + [this, serverAddr](uv::Loop&) { m_udp->Connect(serverAddr); }); + + fmt::println("Starting client for {}:{}", server, remote_port); } void wpi::TimeSyncClient::Start() { fmt::println("Connecting recieved"); - m_udp->received.connect(&wpi::TimeSyncClient::UdpCallback, this); - m_udp->StartRecv(); + + m_loopRunner.ExecSync([this](uv::Loop&) { + m_udp->received.connect(&wpi::TimeSyncClient::UdpCallback, this); + m_udp->StartRecv(); + }); fmt::println("Starting pinger"); using namespace std::chrono_literals; diff --git a/photon-targeting/src/main/native/cpp/photon/targeting/proto/MultiTargetPNPResultProto.cpp b/photon-targeting/src/main/native/cpp/photon/targeting/proto/MultiTargetPNPResultProto.cpp index 0bd08c1cee..cc67ec213f 100644 --- a/photon-targeting/src/main/native/cpp/photon/targeting/proto/MultiTargetPNPResultProto.cpp +++ b/photon-targeting/src/main/native/cpp/photon/targeting/proto/MultiTargetPNPResultProto.cpp @@ -17,6 +17,8 @@ #include "photon/targeting/proto/MultiTargetPNPResultProto.h" +#include + #include "photon.pb.h" #include "photon/targeting/proto/PNPResultProto.h" diff --git a/photon-targeting/src/main/native/jni/TimeSyncClientJNI.cpp b/photon-targeting/src/main/native/jni/TimeSyncClientJNI.cpp index 7c0ae559e0..0d126727a8 100644 --- a/photon-targeting/src/main/native/jni/TimeSyncClientJNI.cpp +++ b/photon-targeting/src/main/native/jni/TimeSyncClientJNI.cpp @@ -18,6 +18,7 @@ #include #include +#include #include #include diff --git a/photon-targeting/src/test/java/net/TimeSyncTest.java b/photon-targeting/src/test/java/net/TimeSyncTest.java index 1cdbacc2f0..4fda9d7afd 100644 --- a/photon-targeting/src/test/java/net/TimeSyncTest.java +++ b/photon-targeting/src/test/java/net/TimeSyncTest.java @@ -32,8 +32,8 @@ import java.io.IOException; import org.junit.jupiter.api.Test; import org.opencv.core.Core; +import org.photonvision.jni.PhotonTargetingJniLoader; import org.photonvision.jni.TimeSyncClient; -import org.photonvision.jni.TimeSyncJNILoader; import org.photonvision.jni.TimeSyncServer; public class TimeSyncTest { @@ -67,7 +67,7 @@ public static void load_wpilib() { public void smoketest() throws InterruptedException { try { load_wpilib(); - TimeSyncJNILoader.load(); + PhotonTargetingJniLoader.load(); } catch (IOException e) { assertTrue(false); } diff --git a/photon-targeting/src/test/native/cpp/PacketTest.cpp b/photon-targeting/src/test/native/cpp/PacketTest.cpp index 0fb5697029..5398fae4c1 100644 --- a/photon-targeting/src/test/native/cpp/PacketTest.cpp +++ b/photon-targeting/src/test/native/cpp/PacketTest.cpp @@ -16,6 +16,7 @@ */ #include +#include #include diff --git a/photon-targeting/src/test/native/cpp/net/TimeSyncTest.cpp b/photon-targeting/src/test/native/cpp/net/TimeSyncTest.cpp index 8faa4f1b45..e85c63bbcc 100644 --- a/photon-targeting/src/test/native/cpp/net/TimeSyncTest.cpp +++ b/photon-targeting/src/test/native/cpp/net/TimeSyncTest.cpp @@ -16,27 +16,23 @@ */ #include +#include #include TEST(TimeSyncProtocolTest, TestClient) { using namespace wpi; using namespace std::chrono_literals; - static auto server_bogus_offset = -nt::Now(); - TimeSyncServer server{5810, []() { return nt::Now() + server_bogus_offset; }}; - TimeSyncClient client{"127.0.0.1", 5810, 1s}; + HAL_Initialize(500, 0); + + TimeSyncServer server{5812}; server.Start(); - std::this_thread::sleep_for(0.5s); - client.Start(); - for (int i = 0; i < 5; i++) { - auto off = client.GetOffset(); - fmt::println("Unit Test: current offset = {} uS, error = {} uS", off, - off - static_cast(server_bogus_offset)); - std::this_thread::sleep_for(1s); + while (true) { + std::this_thread::sleep_for(1000ms); + // busywait } server.Stop(); - client.Stop(); } diff --git a/photonlib-python-examples/aimandrange/robot.py b/photonlib-python-examples/aimandrange/robot.py index 617f0ccbad..9afa3b3551 100644 --- a/photonlib-python-examples/aimandrange/robot.py +++ b/photonlib-python-examples/aimandrange/robot.py @@ -25,8 +25,6 @@ import math import wpilib -import wpimath -import wpimath.geometry import drivetrain from photonlibpy import PhotonCamera diff --git a/photonlib-python-examples/aimandrange/tests/pyfrc_test.py b/photonlib-python-examples/aimandrange/tests/pyfrc_test.py index e195147143..235b61fa34 100644 --- a/photonlib-python-examples/aimandrange/tests/pyfrc_test.py +++ b/photonlib-python-examples/aimandrange/tests/pyfrc_test.py @@ -2,5 +2,3 @@ This test module imports tests that come with pyfrc, and can be used to test basic functionality of just about any robot. """ - -from pyfrc.tests import * diff --git a/photonlib-python-examples/aimattarget/tests/pyfrc_test.py b/photonlib-python-examples/aimattarget/tests/pyfrc_test.py index e195147143..235b61fa34 100644 --- a/photonlib-python-examples/aimattarget/tests/pyfrc_test.py +++ b/photonlib-python-examples/aimattarget/tests/pyfrc_test.py @@ -2,5 +2,3 @@ This test module imports tests that come with pyfrc, and can be used to test basic functionality of just about any robot. """ - -from pyfrc.tests import * diff --git a/photonlib-python-examples/poseest/tests/pyfrc_test.py b/photonlib-python-examples/poseest/tests/pyfrc_test.py index e195147143..235b61fa34 100644 --- a/photonlib-python-examples/poseest/tests/pyfrc_test.py +++ b/photonlib-python-examples/poseest/tests/pyfrc_test.py @@ -2,5 +2,3 @@ This test module imports tests that come with pyfrc, and can be used to test basic functionality of just about any robot. """ - -from pyfrc.tests import *