From 583397782387d8230dba51b2c571ba0635ab6a40 Mon Sep 17 00:00:00 2001 From: Doug Wegscheid Date: Mon, 23 Feb 2026 18:56:29 -0500 Subject: [PATCH 1/2] Allow specification of timestamp. --- lib/src/main/java/dev/doglog/DogLog.java | 202 +++++++++++++----- .../src/main/java/frc/robot/Robot.java | 37 ++++ 2 files changed, 180 insertions(+), 59 deletions(-) diff --git a/lib/src/main/java/dev/doglog/DogLog.java b/lib/src/main/java/dev/doglog/DogLog.java index e9814a4b..2a161f53 100644 --- a/lib/src/main/java/dev/doglog/DogLog.java +++ b/lib/src/main/java/dev/doglog/DogLog.java @@ -137,76 +137,99 @@ public static boolean isEnabled() { /** Log a boolean array. */ public static void log(String key, boolean @Nullable [] value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, boolean @Nullable [] value) { if (!enabled || value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a boolean. */ public static void log(String key, boolean value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, boolean value) { if (!enabled) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a double array. */ public static void log(String key, double @Nullable [] value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, double @Nullable [] value) { if (!enabled || value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a double array with unit metadata. */ public static void log(String key, double @Nullable [] value, @Nullable String unit) { + log(0, key, value, unit); + } + + public static void log(long timestamp, String key, double @Nullable [] value, @Nullable String unit) { if (!enabled) { return; } if (unit == null) { - log(key, value); + log(timestamp, key, value); return; } if (value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value, unit); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value, unit); } /** Log a double array with unit metadata. */ public static void log(String key, double @Nullable [] value, @Nullable Unit unit) { + log(0, key, value, unit); + } + + public static void log(long timestamp, String key, double @Nullable [] value, @Nullable Unit unit) { if (!enabled) { return; } if (unit == null) { - log(key, value); + log(timestamp, key, value); return; } - log(key, value, unit.name()); + log(timestamp, key, value, unit.name()); } /** Log a double. */ public static void log(String key, double value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, double value) { if (!enabled) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a double with unit metadata. */ public static void log(String key, double value, @Nullable String unit) { + log(0, key, value, unit); + } + + public static void log(long timestamp, String key, double value, @Nullable String unit) { if (!enabled) { return; } @@ -215,239 +238,300 @@ public static void log(String key, double value, @Nullable String unit) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value, unit); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value, unit); } /** Log a double with unit metadata. */ public static void log(String key, double value, @Nullable Unit unit) { + log(0, key, value, unit); + } + + public static void log(long timestamp, String key, double value, @Nullable Unit unit) { if (!enabled) { return; } if (unit == null) { - log(key, value); + log(timestamp, key, value); return; } - log(key, value, unit.name()); + log(timestamp, key, value, unit.name()); } /** Log a measure, preserving the user-specified unit. */ public static void log(String key, @Nullable Measure value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, @Nullable Measure value) { if (!enabled || value == null) { return; } - log(key, value.magnitude(), value.unit().name()); + log(timestamp, key, value.magnitude(), value.unit().name()); } /** Log a float array. */ public static void log(String key, float @Nullable [] value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, float @Nullable [] value) { if (!enabled || value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a float array with unit metadata. */ public static void log(String key, float @Nullable [] value, @Nullable String unit) { + log(0, key, value, unit); + } + + public static void log(long timestamp, String key, float @Nullable [] value, @Nullable String unit) { if (!enabled) { return; } if (unit == null) { - log(key, value); + log(timestamp, key, value); return; } if (value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value, unit); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value, unit); } /** Log a float. */ public static void log(String key, float value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, float value) { if (!enabled) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a float with unit metadata. */ public static void log(String key, float value, @Nullable String unit) { + log(0, key, value, unit); + } + + public static void log(long timestamp, String key, float value, @Nullable String unit) { if (!enabled) { return; } if (unit == null) { - log(key, value); + log(timestamp, key, value); return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value, unit); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value, unit); } /** Log an int array. */ public static void log(String key, int @Nullable [] value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, int @Nullable [] value) { if (!enabled || value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a long array. */ public static void log(String key, long @Nullable [] value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, long @Nullable [] value) { if (!enabled || value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a long array with unit metadata. */ public static void log(String key, long @Nullable [] value, @Nullable String unit) { + log(0, key, value, unit); + } + + public static void log(long timestamp, String key, long @Nullable [] value, @Nullable String unit) { if (!enabled) { return; } if (unit == null) { - log(key, value); + log(timestamp, key, value); return; } if (value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value, unit); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value, unit); } /** Log a long. */ public static void log(String key, long value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, long value) { if (!enabled) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a long with unit metadata. */ public static void log(String key, long value, @Nullable String unit) { + log(0, key, value, unit); + } + + public static void log(long timestamp, String key, long value, @Nullable String unit) { if (!enabled) { return; } if (unit == null) { - log(key, value); + log(timestamp, key, value); return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value, unit); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value, unit); } // TODO: Raw logs /** Log a string array. */ public static void log(String key, @Nullable String[] value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, @Nullable String[] value) { if (!enabled || value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log an enum array. */ public static > void log(String key, @Nullable E[] value) { + log(0, key, value); + } + + public static > void log(long timestamp, String key, @Nullable E[] value) { if (!enabled || value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a string. */ public static void log(String key, @Nullable String value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, @Nullable String value) { if (!enabled || value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a string with a custom type string. */ public static void log(String key, @Nullable String value, @Nullable String customTypeString) { + log(0, key, value, customTypeString); + } + + public static void log(long timestamp, String key, @Nullable String value, @Nullable String customTypeString) { if (!enabled || value == null) { return; } if (customTypeString == null) { - log(key, value); + log(timestamp, key, value); return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value, customTypeString); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value, customTypeString); } /** Log an enum. */ public static > void log(String key, @Nullable E value) { + log(0, key, value); + } + + public static > void log(long timestamp, String key, @Nullable E value) { if (!enabled || value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a struct array. */ public static void log(String key, @Nullable T[] value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, @Nullable T[] value) { if (!enabled || value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a struct. */ public static void log(String key, @Nullable T value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, @Nullable T value) { if (!enabled || value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a record. */ public static void log(String key, @Nullable Record value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, @Nullable Record value) { if (!enabled || value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** Log a record array. */ public static void log(String key, @Nullable Record[] value) { + log(0, key, value); + } + + public static void log(long timestamp, String key, @Nullable Record[] value) { if (!enabled || value == null) { return; } - var now = HALUtil.getFPGATime(); - logger.log(now, key, false, value); + logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value); } /** diff --git a/test-project/src/main/java/frc/robot/Robot.java b/test-project/src/main/java/frc/robot/Robot.java index 225ab6bb..06445b72 100644 --- a/test-project/src/main/java/frc/robot/Robot.java +++ b/test-project/src/main/java/frc/robot/Robot.java @@ -9,6 +9,7 @@ import com.ctre.phoenix6.hardware.TalonFX; import dev.doglog.DogLog; +import edu.wpi.first.hal.HALUtil; import edu.wpi.first.math.kinematics.SwerveModuleState; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog; @@ -69,6 +70,42 @@ public void robotPeriodic() { // An enum that can't be converted to a struct DogLog.log("BrokenEnumStruct", SysIdRoutineLog.State.kDynamicForward); + + DogLog.log("Random/RandomLater", Math.random()); + + + // these should all have the same timestamp + long timestamp = HALUtil.getFPGATime(); + DogLog.log(timestamp, "ts/Debug/SwerveState", new SwerveModuleState()); + DogLog.log(timestamp, + "ts/Debug/SwerveStates", + new SwerveModuleState[] { + new SwerveModuleState(), + new SwerveModuleState(), + new SwerveModuleState(), + new SwerveModuleState() + }); + DogLog.log(timestamp, "ts/Debug/Position", motor.getPosition().getValueAsDouble()); + DogLog.log(timestamp, "ts/Debug/Json", "{\"test\": \"json\"}", "json"); + + DogLog.log(timestamp, "ts/Tunable/SupplierValue", tunableSupplier.getAsDouble()); + + DogLog.log(timestamp, "ts/Random/Random", Math.random()); + + DogLog.log(timestamp, "ts/Units/Height1", 123, "inches"); + DogLog.log(timestamp, "ts/Units/Height2", 123, Meters); + DogLog.log(timestamp, "ts/Units/Height3", Centimeters.of(123)); + DogLog.log(timestamp, "ts/Units/Height4", 123, "Meter"); + DogLog.log(timestamp, "ts/Units/Height5", 123, "meter"); + DogLog.log(timestamp, "ts/Units/Height7", motor.getPosition().getValue()); + + // An enum that can't be converted to a struct + DogLog.log(timestamp, "ts/BrokenEnumStruct", SysIdRoutineLog.State.kDynamicForward); + + DogLog.log(timestamp, "ts/Random/RandomLater", Math.random()); + DogLog.log(timestamp, "ts/ts", timestamp); + + DogLog.log(timestamp - 1000000, "ts/ts-1", timestamp); } @Override From c20f48e8bf05d5bebd655f6ce7d0fff1a9279441 Mon Sep 17 00:00:00 2001 From: "autofix-ci[bot]" <114827586+autofix-ci[bot]@users.noreply.github.com> Date: Tue, 24 Feb 2026 16:01:22 +0000 Subject: [PATCH 2/2] style: run autofix.ci --- lib/src/main/java/dev/doglog/DogLog.java | 24 ++++++++++++------- .../src/main/java/frc/robot/Robot.java | 4 ++-- 2 files changed, 18 insertions(+), 10 deletions(-) diff --git a/lib/src/main/java/dev/doglog/DogLog.java b/lib/src/main/java/dev/doglog/DogLog.java index 2a161f53..91b9f6d5 100644 --- a/lib/src/main/java/dev/doglog/DogLog.java +++ b/lib/src/main/java/dev/doglog/DogLog.java @@ -179,7 +179,8 @@ public static void log(String key, double @Nullable [] value, @Nullable String u log(0, key, value, unit); } - public static void log(long timestamp, String key, double @Nullable [] value, @Nullable String unit) { + public static void log( + long timestamp, String key, double @Nullable [] value, @Nullable String unit) { if (!enabled) { return; } @@ -199,7 +200,8 @@ public static void log(String key, double @Nullable [] value, @Nullable Unit uni log(0, key, value, unit); } - public static void log(long timestamp, String key, double @Nullable [] value, @Nullable Unit unit) { + public static void log( + long timestamp, String key, double @Nullable [] value, @Nullable Unit unit) { if (!enabled) { return; } @@ -289,7 +291,8 @@ public static void log(String key, float @Nullable [] value, @Nullable String un log(0, key, value, unit); } - public static void log(long timestamp, String key, float @Nullable [] value, @Nullable String unit) { + public static void log( + long timestamp, String key, float @Nullable [] value, @Nullable String unit) { if (!enabled) { return; } @@ -365,7 +368,8 @@ public static void log(String key, long @Nullable [] value, @Nullable String uni log(0, key, value, unit); } - public static void log(long timestamp, String key, long @Nullable [] value, @Nullable String unit) { + public static void log( + long timestamp, String key, long @Nullable [] value, @Nullable String unit) { if (!enabled) { return; } @@ -456,7 +460,8 @@ public static void log(String key, @Nullable String value, @Nullable String cust log(0, key, value, customTypeString); } - public static void log(long timestamp, String key, @Nullable String value, @Nullable String customTypeString) { + public static void log( + long timestamp, String key, @Nullable String value, @Nullable String customTypeString) { if (!enabled || value == null) { return; } @@ -466,7 +471,8 @@ public static void log(long timestamp, String key, @Nullable String value, @Null return; } - logger.log(timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value, customTypeString); + logger.log( + timestamp == 0 ? HALUtil.getFPGATime() : timestamp, key, false, value, customTypeString); } /** Log an enum. */ @@ -487,7 +493,8 @@ public static void log(String key, @Nullable T[] log(0, key, value); } - public static void log(long timestamp, String key, @Nullable T[] value) { + public static void log( + long timestamp, String key, @Nullable T[] value) { if (!enabled || value == null) { return; } @@ -500,7 +507,8 @@ public static void log(String key, @Nullable T va log(0, key, value); } - public static void log(long timestamp, String key, @Nullable T value) { + public static void log( + long timestamp, String key, @Nullable T value) { if (!enabled || value == null) { return; } diff --git a/test-project/src/main/java/frc/robot/Robot.java b/test-project/src/main/java/frc/robot/Robot.java index 06445b72..c38123aa 100644 --- a/test-project/src/main/java/frc/robot/Robot.java +++ b/test-project/src/main/java/frc/robot/Robot.java @@ -73,11 +73,11 @@ public void robotPeriodic() { DogLog.log("Random/RandomLater", Math.random()); - // these should all have the same timestamp long timestamp = HALUtil.getFPGATime(); DogLog.log(timestamp, "ts/Debug/SwerveState", new SwerveModuleState()); - DogLog.log(timestamp, + DogLog.log( + timestamp, "ts/Debug/SwerveStates", new SwerveModuleState[] { new SwerveModuleState(),