Skip to content

Commit

Permalink
paranoia stuff
Browse files Browse the repository at this point in the history
  • Loading branch information
mcm001 committed Nov 2, 2024
1 parent 4f73d1a commit 47b8426
Show file tree
Hide file tree
Showing 5 changed files with 50 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -190,7 +190,6 @@ public void testRestartingRobotAndCoproc(

if (i == robotStart || i == robotRestart) {
robotNt.startServer("networktables_random.json", "", 5941, 5940);
robotNt.startClient4("testClient");
}

Thread.sleep(100);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,10 +87,8 @@ public TimeSyncClient(String server, int port, double interval) {
this.port = port;
this.interval = interval;

synchronized (mutex) {
this.handle = TimeSyncClient.create(server, port, interval);
TimeSyncClient.start(handle);
}
this.handle = TimeSyncClient.create(server, port, interval);
TimeSyncClient.start(handle);
}

public void setServer(String newServer) {
Expand Down Expand Up @@ -121,7 +119,12 @@ public void stop() {
*/
public long getOffset() {
synchronized (mutex) {
return TimeSyncClient.getOffset(handle);
if (handle > 0) {
return TimeSyncClient.getOffset(handle);
}

System.err.println("TimeSyncClient: use after free?");
return 0;
}
}

Expand All @@ -136,7 +139,12 @@ public long currentServerTimestamp() {

public PingMetadata getPingMetadata() {
synchronized (mutex) {
return TimeSyncClient.getLatestMetadata(handle);
if (handle > 0) {
return TimeSyncClient.getLatestMetadata(handle);
}

System.err.println("TimeSyncClient: use after free?");
return new PingMetadata(0, 0, 0, 0, 0);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,14 +18,21 @@
package org.photonvision.jni;

public class TimeSyncServer {
private final Object mutex = new Object();
private long handle;

public TimeSyncServer(int port) {
this.handle = TimeSyncServer.create(port);
}

public void start() {
TimeSyncServer.start(handle);
synchronized (mutex) {
if (handle > 0) {
TimeSyncServer.start(handle);
} else {
System.err.println("TimeSyncServer: use after free?");
}
}
}

public void stop() {
Expand Down
15 changes: 15 additions & 0 deletions photon-targeting/src/main/native/jni/TimeSyncClientJNI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,17 @@

using namespace wpi::tsp;

#define CHECK_PTR(ptr) \
if (!ptr) { \
fmt::println("Got invalid pointer?? {}:{}", __FILE__, __LINE__); \
return; \
}
#define CHECK_PTR_RETURN(ptr, default) \
if (!ptr) { \
fmt::println("Got invalid pointer?? {}:{}", __FILE__, __LINE__); \
return default; \
}

/**
* Finds a class and keeps it as a global reference.
*
Expand Down Expand Up @@ -117,6 +128,7 @@ JNIEXPORT void JNICALL
Java_org_photonvision_jni_TimeSyncClient_start
(JNIEnv*, jclass, jlong ptr)
{
CHECK_PTR(ptr);
TimeSyncClient* client = reinterpret_cast<TimeSyncClient*>(ptr);
client->Start();
}
Expand All @@ -130,6 +142,7 @@ JNIEXPORT void JNICALL
Java_org_photonvision_jni_TimeSyncClient_stop
(JNIEnv*, jclass, jlong ptr)
{
CHECK_PTR(ptr);
TimeSyncClient* client = reinterpret_cast<TimeSyncClient*>(ptr);
client->Stop();
delete client;
Expand All @@ -144,6 +157,7 @@ JNIEXPORT jlong JNICALL
Java_org_photonvision_jni_TimeSyncClient_getOffset
(JNIEnv*, jclass, jlong ptr)
{
CHECK_PTR_RETURN(ptr, 0);
TimeSyncClient* client = reinterpret_cast<TimeSyncClient*>(ptr);
return client->GetOffset();
}
Expand All @@ -157,6 +171,7 @@ JNIEXPORT jobject JNICALL
Java_org_photonvision_jni_TimeSyncClient_getLatestMetadata
(JNIEnv* env, jclass, jlong ptr)
{
CHECK_PTR_RETURN(ptr, nullptr);
TimeSyncClient* client = reinterpret_cast<TimeSyncClient*>(ptr);
auto m{client->GetMetadata()};
auto ret = env->NewObject(metadataClass, metadataCtor, m.offset, m.pingsSent,
Expand Down
13 changes: 13 additions & 0 deletions photon-targeting/src/main/native/jni/TimeSyncServerJNI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,17 @@

using namespace wpi::tsp;

#define CHECK_PTR(ptr) \
if (!ptr) { \
fmt::println("Got invalid pointer?? {}:{}", __FILE__, __LINE__); \
return; \
}
#define CHECK_PTR_RETURN(ptr, default) \
if (!ptr) { \
fmt::println("Got invalid pointer?? {}:{}", __FILE__, __LINE__); \
return default; \
}

extern "C" {

/*
Expand All @@ -47,6 +58,7 @@ JNIEXPORT void JNICALL
Java_org_photonvision_jni_TimeSyncServer_start
(JNIEnv*, jclass, jlong ptr)
{
CHECK_PTR(ptr);
TimeSyncServer* server = reinterpret_cast<TimeSyncServer*>(ptr);
server->Start();
}
Expand All @@ -60,6 +72,7 @@ JNIEXPORT void JNICALL
Java_org_photonvision_jni_TimeSyncServer_stop
(JNIEnv*, jclass, jlong ptr)
{
CHECK_PTR(ptr);
TimeSyncServer* server = reinterpret_cast<TimeSyncServer*>(ptr);
server->Stop();
delete server;
Expand Down

0 comments on commit 47b8426

Please sign in to comment.