Class Logger

java.lang.Object
org.littletonrobotics.junction.Logger

public class Logger extends Object
Central class for recording and replaying log data.
  • Nested Class Summary

    Nested Classes
    Modifier and Type
    Class
    Description
    static class 
    Advanced hooks for highly custom integration with the Logger class, including use of custom robot base classes.
  • Method Summary

    Modifier and Type
    Method
    Description
    static void
    Adds a new data receiver to process real or replayed data.
    static void
    Disables automatic console capture.
    static void
    end()
    Ends the logging system, including any data receivers or the replay source.
    static boolean
    Returns the state of the receiver queue fault.
    static long
    Returns the current timestamp or replayed time based on the current log entry (microseconds).
    static boolean
    Returns whether a replay source is currently being used.
    static void
    Processes a set of inputs, logging them on the real robot or updating them in the simulator.
    static void
    Records a metadata value.
    static void
    recordOutput(String key, boolean value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, boolean[] value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, boolean[][] value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, byte[] value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, byte[][] value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, double value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, double[] value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, double[][] value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, double value, Unit unit)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, double value, String unit)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, float value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, float[] value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, float[][] value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, float value, Unit unit)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, float value, String unit)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, int value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, int[] value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, int[][] value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, long value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, long[] value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, long[][] value)
    Records a single output field for easy access when viewing the log.
    static <E extends Enum<E>>
    void
    recordOutput(String key, E value)
    Records a single output field for easy access when viewing the log.
    static <E extends Enum<E>>
    void
    recordOutput(String key, E[] value)
    Records a single output field for easy access when viewing the log.
    static <E extends Enum<E>>
    void
    recordOutput(String key, E[][] value)
    Records a single output field for easy access when viewing the log.
    static <U extends Unit>
    void
    recordOutput(String key, Measure<U> value)
    Records a single output field for easy access when viewing the log.
    static <T, MessageType extends us.hebi.quickbuf.ProtoMessage<?>>
    void
    recordOutput(String key, Protobuf<T,MessageType> proto, T value)
    Records a single output field for easy access when viewing the log.
    static <T> void
    recordOutput(String key, Struct<T> struct, T value)
    Records a single output field for easy access when viewing the log.
    static <T> void
    recordOutput(String key, Struct<T> struct, T... value)
    Records a single output field for easy access when viewing the log.
    static <T> void
    recordOutput(String key, Struct<T> struct, T[][] value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, Color value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, String value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, String[] value)
    Records a single output field for easy access when viewing the log.
    static void
    recordOutput(String key, String[][] value)
    Records a single output field for easy access when viewing the log.
    static void
    Records a single output field for easy access when viewing the log.
    static void
    Records a single output field for easy access when viewing the log.
    static void
    Records a single output field for easy access when viewing the log.
    static void
    Records a single output field for easy access when viewing the log.
    static void
    Records a single output field for easy access when viewing the log.
    static <R extends Record>
    void
    recordOutput(String key, R value)
    Records a single output field for easy access when viewing the log.
    static <R extends Record>
    void
    recordOutput(String key, R... value)
    Records a single output field for easy access when viewing the log.
    static <R extends Record>
    void
    recordOutput(String key, R[][] value)
    Records a single output field for easy access when viewing the log.
    static <T extends WPISerializable>
    void
    recordOutput(String key, T value)
    Records a single output field for easy access when viewing the log.
    static <T extends StructSerializable>
    void
    recordOutput(String key, T... value)
    Records a single output field for easy access when viewing the log.
    static <T extends StructSerializable>
    void
    recordOutput(String key, T[][] value)
    Records a single output field for easy access when viewing the log.
    static void
    Registers a new dashboard input to be included in the periodic loop.
    static void
    Registers a log supplier for URCL (Unofficial REV-Compatible Logger).
    static void
    runEveryN(int n, Runnable function)
    Runs the provided callback function every N loop cycles.
    static void
    Sets the source to use for replaying data.
    static void
    Starts running the logging system, including any data receivers or the replay source.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Method Details

    • setReplaySource

      public static void setReplaySource(LogReplaySource replaySource)
      Sets the source to use for replaying data. Use null to disable replay. This method only works during setup before starting to log.
      Parameters:
      replaySource - The supplier for incoming replay data.
    • addDataReceiver

      public static void addDataReceiver(LogDataReceiver dataReceiver)
      Adds a new data receiver to process real or replayed data. This method only works during setup before starting to log.
      Parameters:
      dataReceiver - The target for outgoing data.
    • registerDashboardInput

      public static void registerDashboardInput(LoggedNetworkInput dashboardInput)
      Registers a new dashboard input to be included in the periodic loop. This function should not be called by the user.
      Parameters:
      dashboardInput - The input to register.
    • registerURCL

      public static void registerURCL(Supplier<ByteBuffer[]> logSupplier)
      Registers a log supplier for URCL (Unofficial REV-Compatible Logger). This method should be called during setup before starting to log. Example usage shown below.
       Logger.registerURCL(URCL.startExternal());
       
      Parameters:
      logSupplier - The supplier returned from the URCL.startExternal() method.
    • recordMetadata

      public static void recordMetadata(String key, String value)
      Records a metadata value. This method only works during setup before starting to log, then data will be recorded during the first cycle.
      Parameters:
      key - The name used to identify this metadata field.
      value - The value of the metadata field.
    • disableConsoleCapture

      public static void disableConsoleCapture()
      Disables automatic console capture.
    • hasReplaySource

      public static boolean hasReplaySource()
      Returns whether a replay source is currently being used.
      Returns:
      True if a replay source is being used, false otherwise.
    • start

      public static void start()
      Starts running the logging system, including any data receivers or the replay source.
    • end

      public static void end()
      Ends the logging system, including any data receivers or the replay source.
    • getReceiverQueueFault

      public static boolean getReceiverQueueFault()
      Returns the state of the receiver queue fault. This is tripped when the receiver queue fills up, meaning that data is no longer being saved.
      Returns:
      Whether the receiver queue is full.
    • getTimestamp

      public static long getTimestamp()
      Returns the current timestamp or replayed time based on the current log entry (microseconds).
      Returns:
      The timestamp.
    • runEveryN

      public static void runEveryN(int n, Runnable function)
      Runs the provided callback function every N loop cycles. This method can be used to update inputs or log outputs at a lower rate than the standard loop cycle.

      Note that this method must be called periodically to continue running the callback function.

      Parameters:
      n - The number of loop cycles between runs.
      function - The function to run.
    • processInputs

      public static void processInputs(String key, LoggableInputs inputs)
      Processes a set of inputs, logging them on the real robot or updating them in the simulator. This should be called every loop cycle after updating the inputs from the hardware (if applicable).

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name used to identify this set of inputs.
      inputs - The inputs to log or update.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      public static void recordOutput(String key, BooleanSupplier 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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      public static void recordOutput(String key, IntSupplier 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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      public static void recordOutput(String key, LongSupplier 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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      public static void recordOutput(String key, float value, Unit unit)
      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      This method saves the float value with unit metadata that is compatible with AdvantageScope. The raw value preserves the user-specified unit.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
      unit - The unit to save as metadata.
    • recordOutput

      public static void recordOutput(String key, float value, String unit)
      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      This method saves the float value with unit metadata that is compatible with AdvantageScope. The raw value preserves the user-specified unit.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
      unit - The unit to save as metadata.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      public static void recordOutput(String key, double value, Unit unit)
      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      This method saves the double value with unit metadata that is compatible with AdvantageScope. The raw value preserves the user-specified unit.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
      unit - The unit to save as metadata.
    • recordOutput

      public static void recordOutput(String key, double value, String unit)
      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      This method saves the double value with unit metadata that is compatible with AdvantageScope. The raw value preserves the user-specified unit.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
      unit - The unit to save as metadata.
    • recordOutput

      public static void recordOutput(String key, DoubleSupplier 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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Type Parameters:
      E - The enum type.
      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Type Parameters:
      E - The enum type.
      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Type Parameters:
      E - The enum type.
      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      public static <U extends Unit> 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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      This method saves the unit value with metadata that is compatible with AdvantageScope. The raw value uses the user-specified unit, not the base unit.

      Type Parameters:
      U - The unit type.
      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      public static <T> void recordOutput(String key, Struct<T> struct, T 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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      This method serializes a single object as a struct. Example usage: recordOutput("MyPose", Pose2d.struct, new Pose2d())

      Type Parameters:
      T - The struct type.
      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      struct - The struct serialization object.
      value - The value of the field.
    • recordOutput

      public static <T> void recordOutput(String key, Struct<T> struct, T... 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.

      This method serializes an array of objects as a struct. Example usage: recordOutput("MyPoses", Pose2d.struct, new Pose2d(), new Pose2d()); recordOutput("MyPoses", Pose2d.struct, new Pose2d[] {new Pose2d(), new Pose2d()});

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Type Parameters:
      T - The struct type.
      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      struct - The struct serialization object.
      value - The value of the field.
    • recordOutput

      public static <T> void recordOutput(String key, Struct<T> struct, T[][] 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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Type Parameters:
      T - The struct type.
      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      struct - The struct serialization object.
      value - The value of the field.
    • recordOutput

      public static <T, MessageType extends us.hebi.quickbuf.ProtoMessage<?>> void recordOutput(String key, Protobuf<T,MessageType> proto, T 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.

      This method serializes a single object as a protobuf. Protobuf should only be used for objects that do not support struct serialization. Example usage: recordOutput("MyPose", Pose2d.proto, new Pose2d())

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Type Parameters:
      T - The value type.
      MessageType - The protobuf message type.
      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      proto - The protobuf serialization object.
      value - The value of the field.
    • recordOutput

      public static <T extends WPISerializable> void recordOutput(String key, T 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.

      This method serializes a single object as a struct or protobuf automatically. Struct is preferred if both methods are supported.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Type Parameters:
      T - The object type.
      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      public static <T extends StructSerializable> void recordOutput(String key, T... 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.

      This method serializes an array of objects as a struct automatically. Top-level protobuf arrays are not supported.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Type Parameters:
      T - The object type.
      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      public static <T extends StructSerializable> void recordOutput(String key, T[][] 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.

      This method serializes an array of objects as a struct automatically. Top-level protobuf arrays are not supported.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Type Parameters:
      T - The object type.
      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      public static <R extends Record> void recordOutput(String key, R 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.

      This method serializes a single object as a struct or protobuf automatically. Struct is preferred if both methods are supported.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Type Parameters:
      R - The record type.
      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      public static <R extends Record> void recordOutput(String key, R... 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.

      This method serializes an array of objects as a struct automatically. Top-level protobuf arrays are not supported.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Type Parameters:
      R - The record type.
      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      public static <R extends Record> void recordOutput(String key, R[][] 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.

      This method serializes an array of objects as a struct automatically. Top-level protobuf arrays are not supported.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Type Parameters:
      R - The record type.
      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      public static void recordOutput(String key, LoggedMechanism2d 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.

      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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.
    • recordOutput

      public static void recordOutput(String key, Color 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.

      This method is not thread-safe and should only be called from the main thread. Check the documentation for details.

      Parameters:
      key - The name of the field to record. It will be stored under "/RealOutputs" or "/ReplayOutputs"
      value - The value of the field.