From c04e13ef936ba65ec758903530e57f07dbecab3e Mon Sep 17 00:00:00 2001 From: Matt Date: Thu, 14 Nov 2024 01:52:23 -0500 Subject: [PATCH] Fix roborio duplicate .so's on deploy (#1571) --- .../networktables/TimeSyncManager.java | 7 ++++-- photon-targeting/build.gradle | 23 +++++++++++++++++-- .../org/photonvision/jni/TimeSyncClient.java | 6 ++--- .../org/photonvision/jni/TimeSyncServer.java | 4 ++-- .../main/native/cpp/net/TimeSyncClient.cpp | 22 +++++++++--------- .../main/native/cpp/net/TimeSyncServer.cpp | 6 ++--- .../main/native/include/net/TimeSyncClient.h | 2 +- .../main/native/include/net/TimeSyncServer.h | 2 +- .../main/native/jni/FileLoggerExtrasJNI.cpp | 4 ++-- .../src/main/native/jni/jni_utils.h | 6 +++-- .../src/test/native/cpp/PacketTest.cpp | 3 ++- .../src/test/native/cpp/net/TimeSyncTest.cpp | 2 +- shared/config.gradle | 2 +- 13 files changed, 57 insertions(+), 32 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/TimeSyncManager.java b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/TimeSyncManager.java index 83431a3f3..050a28e50 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/TimeSyncManager.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/TimeSyncManager.java @@ -129,8 +129,11 @@ public class TimeSyncManager { var conns = ntInstance.getConnections(); if (conns.length > 0) { - logger.debug("Changing TimeSyncClient server to " + conns[0].remote_ip); - m_client.setServer(conns[0].remote_ip); + var newServer = conns[0].remote_ip; + if (!m_client.getServer().equals(newServer)) { + logger.debug("Changing TimeSyncClient server to " + newServer); + m_client.setServer(newServer); + } } if (m_client != null) { diff --git a/photon-targeting/build.gradle b/photon-targeting/build.gradle index 240c205b2..8c0bc49e3 100644 --- a/photon-targeting/build.gradle +++ b/photon-targeting/build.gradle @@ -106,8 +106,6 @@ model { } if (binary.targetPlatform.name == platName) { - - // only include release binaries (hard coded for now) def isDebug = binary.buildType.name.contains('debug') if (!isDebug) { @@ -191,6 +189,27 @@ model { apply from: "${rootDir}/shared/javacpp/publish.gradle" +// quickly hack our raw jar into publishing +def rawjavaJar = tasks.register("rawjavaJar", Jar) { + dependsOn classes + includeEmptyDirs = false + from sourceSets.main.output + archiveClassifier = 'raw' +} + +publishing { + publications { + rawjava(MavenPublication) { + artifact (rawjavaJar) { + classifier = null + } + artifactId = "${nativeName}-rawjava" + groupId artifactGroupId + version pubVersion + } + } +} + // Add photon serde headers to our published sources cppHeadersZip { from('src/generated/main/native/include') { 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 02a05f370..2151797cd 100644 --- a/photon-targeting/src/main/java/org/photonvision/jni/TimeSyncClient.java +++ b/photon-targeting/src/main/java/org/photonvision/jni/TimeSyncClient.java @@ -104,7 +104,7 @@ public class TimeSyncClient { public void stop() { synchronized (mutex) { - if (handle > 0) { + if (handle != 0) { TimeSyncClient.stop(handle); handle = 0; } @@ -119,7 +119,7 @@ public class TimeSyncClient { */ public long getOffset() { synchronized (mutex) { - if (handle > 0) { + if (handle != 0) { return TimeSyncClient.getOffset(handle); } @@ -139,7 +139,7 @@ public class TimeSyncClient { public PingMetadata getPingMetadata() { synchronized (mutex) { - if (handle > 0) { + if (handle != 0) { return TimeSyncClient.getLatestMetadata(handle); } diff --git a/photon-targeting/src/main/java/org/photonvision/jni/TimeSyncServer.java b/photon-targeting/src/main/java/org/photonvision/jni/TimeSyncServer.java index b660a439c..3cdf11d7d 100644 --- a/photon-targeting/src/main/java/org/photonvision/jni/TimeSyncServer.java +++ b/photon-targeting/src/main/java/org/photonvision/jni/TimeSyncServer.java @@ -27,7 +27,7 @@ public class TimeSyncServer { public void start() { synchronized (mutex) { - if (handle > 0) { + if (handle != 0) { TimeSyncServer.start(handle); } else { System.err.println("TimeSyncServer: use after free?"); @@ -36,7 +36,7 @@ public class TimeSyncServer { } public void stop() { - if (handle > 0) { + if (handle != 0) { TimeSyncServer.stop(handle); handle = 0; } diff --git a/photon-targeting/src/main/native/cpp/net/TimeSyncClient.cpp b/photon-targeting/src/main/native/cpp/net/TimeSyncClient.cpp index 26b64ca18..0640c90b1 100644 --- a/photon-targeting/src/main/native/cpp/net/TimeSyncClient.cpp +++ b/photon-targeting/src/main/native/cpp/net/TimeSyncClient.cpp @@ -17,7 +17,6 @@ #include "net/TimeSyncClient.h" -#include #include #include @@ -32,6 +31,7 @@ #include #include +#include #include #include "ntcore_cpp.h" @@ -58,7 +58,7 @@ static void ClientLoggerFunc(unsigned int level, const char* file, } void wpi::tsp::TimeSyncClient::Tick() { - // fmt::println("wpi::tsp::TimeSyncClient::Tick"); + // wpi::println("wpi::tsp::TimeSyncClient::Tick"); // Regardless of if we've gotten a pong back yet, we'll ping again. this is // pretty naive but should be "fine" for now? @@ -101,15 +101,15 @@ void wpi::tsp::TimeSyncClient::UdpCallback(uv::Buffer& buf, size_t nbytes, wpi::UnpackStruct(buf.bytes()), }; - // fmt::println("->[client] Got pong: {} {} {} {}", pong.version, + // wpi::println("->[client] Got pong: {} {} {} {}", pong.version, // pong.message_id, pong.client_time, pong.server_time); if (pong.version != 1) { - fmt::println("Bad version from server?"); + wpi::println("Bad version from server?"); return; } if (pong.message_id != 2) { - fmt::println("Bad message id from server?"); + wpi::println("Bad message id from server?"); return; } @@ -131,7 +131,7 @@ void wpi::tsp::TimeSyncClient::UdpCallback(uv::Buffer& buf, size_t nbytes, auto filtered = m_lastOffsets.Calculate(serverTimeOffsetUs); - // fmt::println("Ping-ponged! RTT2 {} uS, offset {}/filtered offset {} uS", + // wpi::println("Ping-ponged! RTT2 {} uS, offset {}/filtered offset {} uS", // rtt2, // serverTimeOffsetUs, filtered); @@ -144,9 +144,9 @@ void wpi::tsp::TimeSyncClient::UdpCallback(uv::Buffer& buf, size_t nbytes, } using std::cout; - // fmt::println("Ping-ponged! RTT2 {} uS, offset {} uS", rtt2, + // wpi::println("Ping-ponged! RTT2 {} uS, offset {} uS", rtt2, // serverTimeOffsetUs); - // fmt::println("Estimated server time {} s", + // wpi::println("Estimated server time {} s", // (m_timeProvider() + serverTimeOffsetUs) / 1000000.0); } @@ -161,12 +161,12 @@ wpi::tsp::TimeSyncClient::TimeSyncClient(std::string_view server, m_serverIP{server}, m_serverPort{remote_port}, m_loopDelay(ping_delay) { - // fmt::println("Starting client (with server address {}:{})", server, + // wpi::println("Starting client (with server address {}:{})", server, // remote_port); } void wpi::tsp::TimeSyncClient::Start() { - // fmt::println("Connecting received"); + // wpi::println("Connecting received"); m_loopRunner.ExecSync([this](uv::Loop&) { struct sockaddr_in serverAddr; @@ -180,7 +180,7 @@ void wpi::tsp::TimeSyncClient::Start() { m_udp->StartRecv(); }); - // fmt::println("Starting pinger"); + // wpi::println("Starting pinger"); using namespace std::chrono_literals; m_pingTimer->timeout.connect(&wpi::tsp::TimeSyncClient::Tick, this); diff --git a/photon-targeting/src/main/native/cpp/net/TimeSyncServer.cpp b/photon-targeting/src/main/native/cpp/net/TimeSyncServer.cpp index 2bf7f8f19..ddda5982e 100644 --- a/photon-targeting/src/main/native/cpp/net/TimeSyncServer.cpp +++ b/photon-targeting/src/main/native/cpp/net/TimeSyncServer.cpp @@ -17,7 +17,6 @@ #include "net/TimeSyncServer.h" -#include #include #include @@ -31,6 +30,7 @@ #include #include +#include #include #include "ntcore_cpp.h" @@ -59,7 +59,7 @@ static void ServerLoggerFunc(unsigned int level, const char* file, void wpi::tsp::TimeSyncServer::UdpCallback(uv::Buffer& data, size_t n, const sockaddr& sender, unsigned flags) { - // fmt::println("TimeSyncServer got ping!"); + // wpi::println("TimeSyncServer got ping!"); TspPing ping{wpi::UnpackStruct(data.bytes())}; @@ -85,7 +85,7 @@ void wpi::tsp::TimeSyncServer::UdpCallback(uv::Buffer& data, size_t n, wpi::uv::Buffer pongBuf{pongData}; int sent = m_udp->TrySend(sender, wpi::SmallVector{pongBuf}); - // fmt::println("Pong ret: {}", sent); + // wpi::println("Pong ret: {}", sent); if (static_cast(sent) != wpi::Struct::GetSize()) { WPI_ERROR(m_logger, "Didn't send the whole pong back?"); return; diff --git a/photon-targeting/src/main/native/include/net/TimeSyncClient.h b/photon-targeting/src/main/native/include/net/TimeSyncClient.h index d8bdce372..946b749c9 100644 --- a/photon-targeting/src/main/native/include/net/TimeSyncClient.h +++ b/photon-targeting/src/main/native/include/net/TimeSyncClient.h @@ -17,7 +17,6 @@ #pragma once -#include #include #include #include @@ -38,6 +37,7 @@ #include #include +#include #include #include diff --git a/photon-targeting/src/main/native/include/net/TimeSyncServer.h b/photon-targeting/src/main/native/include/net/TimeSyncServer.h index 4a250da63..4d47f1469 100644 --- a/photon-targeting/src/main/native/include/net/TimeSyncServer.h +++ b/photon-targeting/src/main/native/include/net/TimeSyncServer.h @@ -17,7 +17,6 @@ #pragma once -#include #include #include #include @@ -37,6 +36,7 @@ #include #include +#include #include #include "TimeSyncStructs.h" diff --git a/photon-targeting/src/main/native/jni/FileLoggerExtrasJNI.cpp b/photon-targeting/src/main/native/jni/FileLoggerExtrasJNI.cpp index c7a45e2de..f65d08977 100644 --- a/photon-targeting/src/main/native/jni/FileLoggerExtrasJNI.cpp +++ b/photon-targeting/src/main/native/jni/FileLoggerExtrasJNI.cpp @@ -35,12 +35,12 @@ struct QueuedFileLogger { explicit QueuedFileLogger(std::string_view file) : logger{file, std::bind(&QueuedFileLogger::callback, this, std::placeholders::_1)} { - // fmt::println("Watching {}", file); + // wpi::println("Watching {}", file); } void callback(std::string_view newline) { std::lock_guard lock{m_mutex}; - // fmt::println("FileLogger got: {}", newline); + // wpi::println("FileLogger got: {}", newline); m_data.insert(m_data.end(), newline.begin(), newline.end()); } diff --git a/photon-targeting/src/main/native/jni/jni_utils.h b/photon-targeting/src/main/native/jni/jni_utils.h index 036af2519..d94477fa4 100644 --- a/photon-targeting/src/main/native/jni/jni_utils.h +++ b/photon-targeting/src/main/native/jni/jni_utils.h @@ -17,13 +17,15 @@ #pragma once +#include + #define CHECK_PTR(ptr) \ if (!ptr) { \ - fmt::println("Got invalid pointer?? {}:{}", __FILE__, __LINE__); \ + wpi::println("Got invalid pointer?? {}:{}", __FILE__, __LINE__); \ return; \ } #define CHECK_PTR_RETURN(ptr, default) \ if (!ptr) { \ - fmt::println("Got invalid pointer?? {}:{}", __FILE__, __LINE__); \ + wpi::println("Got invalid pointer?? {}:{}", __FILE__, __LINE__); \ return default; \ } diff --git a/photon-targeting/src/test/native/cpp/PacketTest.cpp b/photon-targeting/src/test/native/cpp/PacketTest.cpp index 153f1c96a..96033446e 100644 --- a/photon-targeting/src/test/native/cpp/PacketTest.cpp +++ b/photon-targeting/src/test/native/cpp/PacketTest.cpp @@ -19,6 +19,7 @@ #include #include +#include #include "gtest/gtest.h" #include "photon/dataflow/structures/Packet.h" @@ -141,7 +142,7 @@ TEST(PacketTest, PhotonPipelineResult) { auto t3 = std::chrono::steady_clock::now(); EXPECT_EQ(result2, b2); - fmt::println( + wpi::println( "Pack {} unpack {} packet length {}", std::chrono::duration_cast(t2 - t1).count(), std::chrono::duration_cast(t3 - t2).count(), diff --git a/photon-targeting/src/test/native/cpp/net/TimeSyncTest.cpp b/photon-targeting/src/test/native/cpp/net/TimeSyncTest.cpp index 9e23fd600..0c2364444 100644 --- a/photon-targeting/src/test/native/cpp/net/TimeSyncTest.cpp +++ b/photon-targeting/src/test/native/cpp/net/TimeSyncTest.cpp @@ -33,7 +33,7 @@ TEST(TimeSyncProtocolTest, Smoketest) { for (int i = 0; i < 10; i++) { std::this_thread::sleep_for(100ms); TimeSyncClient::Metadata m = client.GetMetadata(); - fmt::println("Offset={} rtt={}", m.offset, m.rtt2); + wpi::println("Offset={} rtt={}", m.offset, m.rtt2); } server.Stop(); diff --git a/shared/config.gradle b/shared/config.gradle index 4f984871b..bc7107c19 100644 --- a/shared/config.gradle +++ b/shared/config.gradle @@ -12,7 +12,7 @@ nativeUtils.wpi.configureDependencies { opencvVersion = openCVversion googleTestYear = "frc2024" googleTestVersion = "1.14.0-1" - niLibVersion = "2024.2.1" + niLibVersion = "2025.0.0" } // Configure warnings and errors