Skip to content

Commit

Permalink
Add thread safety warnings to Javadoc for common methods (#80)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwbonner committed Mar 12, 2024
1 parent ffa1e7b commit 399edde
Showing 1 changed file with 66 additions and 0 deletions.
66 changes: 66 additions & 0 deletions junction/core/src/org/littletonrobotics/junction/Logger.java
Original file line number Diff line number Diff line change
Expand Up @@ -451,6 +451,9 @@ public static void runEveryN(int n, Runnable function) {
* the simulator. This should be called every loop cycle after updating the
* inputs from the hardware (if applicable).
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name used to identify this set of inputs.
* @param inputs The inputs to log or update.
*/
Expand All @@ -468,6 +471,9 @@ public static void processInputs(String key, LoggableInputs inputs) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -482,6 +488,9 @@ public static void recordOutput(String key, byte[] value) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -496,6 +505,9 @@ public static void recordOutput(String key, boolean value) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -510,6 +522,9 @@ public static void recordOutput(String key, int value) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -524,6 +539,9 @@ public static void recordOutput(String key, long value) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -538,6 +556,9 @@ public static void recordOutput(String key, float value) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -552,6 +573,9 @@ public static void recordOutput(String key, double value) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -566,6 +590,9 @@ public static void recordOutput(String key, String value) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -580,6 +607,9 @@ public static <E extends Enum<E>> void recordOutput(String key, E value) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -594,6 +624,9 @@ public static <U extends Unit<U>> void recordOutput(String key, Measure<U> value
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -608,6 +641,9 @@ public static void recordOutput(String key, boolean[] value) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -622,6 +658,9 @@ public static void recordOutput(String key, int[] value) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -636,6 +675,9 @@ public static void recordOutput(String key, long[] value) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -650,6 +692,9 @@ public static void recordOutput(String key, float[] value) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -664,6 +709,9 @@ public static void recordOutput(String key, double[] value) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -678,6 +726,9 @@ public static void recordOutput(String key, String[] value) {
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* <p>
* This method serializes a single object as a struct. Example usage:
* {@code recordOutput("MyPose", Pose2d.struct, new Pose2d())}
Expand All @@ -704,6 +755,9 @@ public static <T> void recordOutput(String key, Struct<T> struct, T value) {
* Pose2d()});
* }
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -724,6 +778,9 @@ public static <T> void recordOutput(String key, Struct<T> struct, T... value) {
* used for objects that do not support struct serialization. Example usage:
* {@code recordOutput("MyPose", Pose2d.proto, new Pose2d())}
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand All @@ -744,6 +801,9 @@ public static <T, MessageType extends ProtoMessage<?>> void recordOutput(String
* This method serializes a single object as a struct or protobuf automatically.
* Struct is preferred if both methods are supported.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param T The type
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
Expand All @@ -764,6 +824,9 @@ public static <T extends WPISerializable> void recordOutput(String key, T value)
* This method serializes an array of objects as a struct automatically.
* Top-level protobuf arrays are not supported.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param T The type
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
Expand All @@ -784,6 +847,9 @@ public static <T extends StructSerializable> void recordOutput(String key, T...
* The current position of the Mechanism2d is logged once as a set of nested
* fields. If the position is updated, this method must be called again.
*
* <p>This method is <b>not thread-safe</b> and should only be called from the
* main thread. See the "Common Issues" page in the documentation for more details.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
Expand Down

0 comments on commit 399edde

Please sign in to comment.