Skip to content

Commit

Permalink
Clean up Java style (wpilibsuite#5990)
Browse files Browse the repository at this point in the history
Also make equivalent changes in C++ where applicable.

Co-authored-by: Sriman Achanta <68172138+srimanachanta@users.noreply.github.com>
  • Loading branch information
calcmogul and srimanachanta authored Dec 4, 2023
1 parent 66172ab commit 2bb1409
Show file tree
Hide file tree
Showing 113 changed files with 428 additions and 619 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.util.Units;
import java.io.IOException;
import java.util.Optional;
import org.junit.jupiter.api.Assertions;
import org.junit.jupiter.api.Test;
Expand All @@ -28,7 +27,7 @@ void testLoad(AprilTagFields field) {
}

@Test
void test2022RapidReact() throws IOException {
void test2022RapidReact() {
AprilTagFieldLayout layout = AprilTagFields.k2022RapidReact.loadAprilTagLayoutField();

// Blue Hangar Truss - Hub
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ public static boolean readConfig() {
// parse file
JsonElement top;
try {
top = new JsonParser().parse(Files.newBufferedReader(Paths.get(configFile)));
top = JsonParser.parseReader(Files.newBufferedReader(Paths.get(configFile)));
} catch (IOException ex) {
System.err.println("could not open '" + configFile + "': " + ex);
return false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ void update(VideoEvent event) {
}

@Override
public void close() throws Exception {
public void close() {
if (m_booleanValueEntry != null) {
m_booleanValueEntry.close();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ private static void startThread() {
listener.accept(event);
} catch (Throwable throwable) {
System.err.println(
"Unhandled exception during listener callback: " + throwable.toString());
"Unhandled exception during listener callback: " + throwable);
throwable.printStackTrace();
}
}
Expand Down
3 changes: 1 addition & 2 deletions hal/src/main/java/edu/wpi/first/hal/DMAJNISample.java
Original file line number Diff line number Diff line change
Expand Up @@ -131,8 +131,7 @@ public int getAnalogInputAveraged(int analogInputHandle) {
}

// + 2 Hack, but needed to not have to call into JNI
int value = readValue(data.m_valueType + 2, data.m_index);
return value;
return readValue(data.m_valueType + 2, data.m_index);
}

public void getAnalogAccumulator(int analogInputHandle, AccumulatorResult result) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -574,7 +574,7 @@ public int addSubTableListener(SubTableListener listener) {
return m_inst.addListener(
new String[] {m_pathWithSep},
EnumSet.of(NetworkTableEvent.Kind.kPublish, NetworkTableEvent.Kind.kImmediate),
new Consumer<NetworkTableEvent>() {
new Consumer<>() {
final Set<String> m_notifiedTables = new HashSet<>();

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -190,14 +190,14 @@ private T fromRaw(byte[] raw, T defaultValue) {

private TimestampedObject<T> fromRaw(TimestampedRaw raw, T defaultValue) {
if (raw.value.length == 0) {
return new TimestampedObject<T>(0, 0, defaultValue);
return new TimestampedObject<>(0, 0, defaultValue);
}
try {
synchronized (m_buf) {
return new TimestampedObject<T>(raw.timestamp, raw.serverTime, m_buf.read(raw.value));
return new TimestampedObject<>(raw.timestamp, raw.serverTime, m_buf.read(raw.value));
}
} catch (IOException e) {
return new TimestampedObject<T>(0, 0, defaultValue);
return new TimestampedObject<>(0, 0, defaultValue);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ private ProtobufTopic(NetworkTableInstance inst, int handle, Protobuf<T, ?> prot
* @return ProtobufTopic for value class
*/
public static <T> ProtobufTopic<T> wrap(Topic topic, Protobuf<T, ?> proto) {
return new ProtobufTopic<T>(topic, proto);
return new ProtobufTopic<>(topic, proto);
}

/**
Expand All @@ -47,7 +47,7 @@ public static <T> ProtobufTopic<T> wrap(Topic topic, Protobuf<T, ?> proto) {
*/
public static <T> ProtobufTopic<T> wrap(
NetworkTableInstance inst, int handle, Protobuf<T, ?> proto) {
return new ProtobufTopic<T>(inst, handle, proto);
return new ProtobufTopic<>(inst, handle, proto);
}

/**
Expand All @@ -63,7 +63,7 @@ public static <T> ProtobufTopic<T> wrap(
* @return subscriber
*/
public ProtobufSubscriber<T> subscribe(T defaultValue, PubSubOption... options) {
return new ProtobufEntryImpl<T>(
return new ProtobufEntryImpl<>(
this,
ProtobufBuffer.create(m_proto),
NetworkTablesJNI.subscribe(
Expand All @@ -87,7 +87,7 @@ public ProtobufSubscriber<T> subscribe(T defaultValue, PubSubOption... options)
*/
public ProtobufPublisher<T> publish(PubSubOption... options) {
m_inst.addSchema(m_proto);
return new ProtobufEntryImpl<T>(
return new ProtobufEntryImpl<>(
this,
ProtobufBuffer.create(m_proto),
NetworkTablesJNI.publish(
Expand All @@ -113,7 +113,7 @@ public ProtobufPublisher<T> publish(PubSubOption... options) {
*/
public ProtobufPublisher<T> publishEx(String properties, PubSubOption... options) {
m_inst.addSchema(m_proto);
return new ProtobufEntryImpl<T>(
return new ProtobufEntryImpl<>(
this,
ProtobufBuffer.create(m_proto),
NetworkTablesJNI.publishEx(
Expand Down Expand Up @@ -144,7 +144,7 @@ public ProtobufPublisher<T> publishEx(String properties, PubSubOption... options
* @return entry
*/
public ProtobufEntry<T> getEntry(T defaultValue, PubSubOption... options) {
return new ProtobufEntryImpl<T>(
return new ProtobufEntryImpl<>(
this,
ProtobufBuffer.create(m_proto),
NetworkTablesJNI.getEntry(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -177,15 +177,14 @@ private T[] fromRaw(byte[] raw, T[] defaultValue) {
@SuppressWarnings("PMD.AvoidCatchingGenericException")
private TimestampedObject<T[]> fromRaw(TimestampedRaw raw, T[] defaultValue) {
if (raw.value.length == 0) {
return new TimestampedObject<T[]>(0, 0, defaultValue);
return new TimestampedObject<>(0, 0, defaultValue);
}
try {
synchronized (m_buf) {
return new TimestampedObject<T[]>(
raw.timestamp, raw.serverTime, m_buf.readArray(raw.value));
return new TimestampedObject<>(raw.timestamp, raw.serverTime, m_buf.readArray(raw.value));
}
} catch (RuntimeException e) {
return new TimestampedObject<T[]>(0, 0, defaultValue);
return new TimestampedObject<>(0, 0, defaultValue);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ private StructArrayTopic(NetworkTableInstance inst, int handle, Struct<T> struct
* @return StructArrayTopic for value class
*/
public static <T> StructArrayTopic<T> wrap(Topic topic, Struct<T> struct) {
return new StructArrayTopic<T>(topic, struct);
return new StructArrayTopic<>(topic, struct);
}

/**
Expand All @@ -47,7 +47,7 @@ public static <T> StructArrayTopic<T> wrap(Topic topic, Struct<T> struct) {
*/
public static <T> StructArrayTopic<T> wrap(
NetworkTableInstance inst, int handle, Struct<T> struct) {
return new StructArrayTopic<T>(inst, handle, struct);
return new StructArrayTopic<>(inst, handle, struct);
}

/**
Expand All @@ -63,7 +63,7 @@ public static <T> StructArrayTopic<T> wrap(
* @return subscriber
*/
public StructArraySubscriber<T> subscribe(T[] defaultValue, PubSubOption... options) {
return new StructArrayEntryImpl<T>(
return new StructArrayEntryImpl<>(
this,
StructBuffer.create(m_struct),
NetworkTablesJNI.subscribe(
Expand All @@ -87,7 +87,7 @@ public StructArraySubscriber<T> subscribe(T[] defaultValue, PubSubOption... opti
*/
public StructArrayPublisher<T> publish(PubSubOption... options) {
m_inst.addSchema(m_struct);
return new StructArrayEntryImpl<T>(
return new StructArrayEntryImpl<>(
this,
StructBuffer.create(m_struct),
NetworkTablesJNI.publish(
Expand All @@ -113,7 +113,7 @@ public StructArrayPublisher<T> publish(PubSubOption... options) {
*/
public StructArrayPublisher<T> publishEx(String properties, PubSubOption... options) {
m_inst.addSchema(m_struct);
return new StructArrayEntryImpl<T>(
return new StructArrayEntryImpl<>(
this,
StructBuffer.create(m_struct),
NetworkTablesJNI.publishEx(
Expand Down Expand Up @@ -144,7 +144,7 @@ public StructArrayPublisher<T> publishEx(String properties, PubSubOption... opti
* @return entry
*/
public StructArrayEntry<T> getEntry(T[] defaultValue, PubSubOption... options) {
return new StructArrayEntryImpl<T>(
return new StructArrayEntryImpl<>(
this,
StructBuffer.create(m_struct),
NetworkTablesJNI.getEntry(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -188,14 +188,14 @@ private T fromRaw(byte[] raw, T defaultValue) {
@SuppressWarnings("PMD.AvoidCatchingGenericException")
private TimestampedObject<T> fromRaw(TimestampedRaw raw, T defaultValue) {
if (raw.value.length == 0) {
return new TimestampedObject<T>(0, 0, defaultValue);
return new TimestampedObject<>(0, 0, defaultValue);
}
try {
synchronized (m_buf) {
return new TimestampedObject<T>(raw.timestamp, raw.serverTime, m_buf.read(raw.value));
return new TimestampedObject<>(raw.timestamp, raw.serverTime, m_buf.read(raw.value));
}
} catch (RuntimeException e) {
return new TimestampedObject<T>(0, 0, defaultValue);
return new TimestampedObject<>(0, 0, defaultValue);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ private StructTopic(NetworkTableInstance inst, int handle, Struct<T> struct) {
* @return StructTopic for value class
*/
public static <T> StructTopic<T> wrap(Topic topic, Struct<T> struct) {
return new StructTopic<T>(topic, struct);
return new StructTopic<>(topic, struct);
}

/**
Expand All @@ -46,7 +46,7 @@ public static <T> StructTopic<T> wrap(Topic topic, Struct<T> struct) {
* @return StructTopic for value class
*/
public static <T> StructTopic<T> wrap(NetworkTableInstance inst, int handle, Struct<T> struct) {
return new StructTopic<T>(inst, handle, struct);
return new StructTopic<>(inst, handle, struct);
}

/**
Expand All @@ -62,7 +62,7 @@ public static <T> StructTopic<T> wrap(NetworkTableInstance inst, int handle, Str
* @return subscriber
*/
public StructSubscriber<T> subscribe(T defaultValue, PubSubOption... options) {
return new StructEntryImpl<T>(
return new StructEntryImpl<>(
this,
StructBuffer.create(m_struct),
NetworkTablesJNI.subscribe(
Expand All @@ -86,7 +86,7 @@ public StructSubscriber<T> subscribe(T defaultValue, PubSubOption... options) {
*/
public StructPublisher<T> publish(PubSubOption... options) {
m_inst.addSchema(m_struct);
return new StructEntryImpl<T>(
return new StructEntryImpl<>(
this,
StructBuffer.create(m_struct),
NetworkTablesJNI.publish(
Expand All @@ -112,7 +112,7 @@ public StructPublisher<T> publish(PubSubOption... options) {
*/
public StructPublisher<T> publishEx(String properties, PubSubOption... options) {
m_inst.addSchema(m_struct);
return new StructEntryImpl<T>(
return new StructEntryImpl<>(
this,
StructBuffer.create(m_struct),
NetworkTablesJNI.publishEx(
Expand Down Expand Up @@ -143,7 +143,7 @@ public StructPublisher<T> publishEx(String properties, PubSubOption... options)
* @return entry
*/
public StructEntry<T> getEntry(T defaultValue, PubSubOption... options) {
return new StructEntryImpl<T>(
return new StructEntryImpl<>(
this,
StructBuffer.create(m_struct),
NetworkTablesJNI.getEntry(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@

import static org.junit.jupiter.api.Assertions.assertEquals;

import java.util.Arrays;
import java.util.Collections;
import java.util.List;
import java.util.stream.Stream;
Expand Down Expand Up @@ -61,8 +60,8 @@ private static Stream<Arguments> getHierarchyArguments() {
return Stream.of(
Arguments.of(Collections.singletonList("/"), ""),
Arguments.of(Collections.singletonList("/"), "/"),
Arguments.of(Arrays.asList("/", "/foo", "/foo/bar", "/foo/bar/baz"), "/foo/bar/baz"),
Arguments.of(Arrays.asList("/", "/foo", "/foo/bar", "/foo/bar/"), "/foo/bar/"));
Arguments.of(List.of("/", "/foo", "/foo/bar", "/foo/bar/baz"), "/foo/bar/baz"),
Arguments.of(List.of("/", "/foo", "/foo/bar", "/foo/bar/"), "/foo/bar/"));
}

@ParameterizedTest
Expand Down
Loading

0 comments on commit 2bb1409

Please sign in to comment.