Skip to content

Commit

Permalink
Update documentation
Browse files Browse the repository at this point in the history
  • Loading branch information
jwbonner committed Oct 23, 2023
1 parent 97a3133 commit b18ceaa
Show file tree
Hide file tree
Showing 5 changed files with 139 additions and 51 deletions.
7 changes: 1 addition & 6 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ AdvantageKit is a logging, telemetry, and replay framework developed by Team 632
- [Installing AdvantageKit](/docs/INSTALLATION.md)
- [Understanding Data Flow](/docs/DATA-FLOW.md)
- [Code Structure & IO Layers](/docs/CODE-STRUCTURE.md)
- [Common Issues (And How To Avoid Them)](/docs/COMMON-ISSUES.md)
- [Developing AdvantageKit](/docs/DEVELOPING.md)

## Example Projects
Expand All @@ -25,19 +26,13 @@ Looking to get started quickly? Here are some example projects to check out:
### Logging

- [junction](/junction) - Primary component of logging, manages the flow of data between user code, WPILib, log files, network clients, etc. _Written in Java._

- [junction/core](/junction/core) - Central system for managing data, including reading and writing from log files and user code.

- [junction/shims](/junction/shims) - Replaces components of other libraries (WPILib) to interact directly with `junction`.

- [junction/shims/wpilib](/junction/shims/wpilib) - Replaces WPILib components to read data from `junction` instead of the HAL.

- [junction/autolog](/junction/autolog) - Annotation procesor for creating log input classes.

- [conduit](/conduit) - Transfers data between `junction` and the WPILib HAL efficiently. _Written in C++ and Java._

### General

- [build_tools](/build_tools) - Utilities to assist with building in Bazel and interfacing with WPILib and the roboRIO.

- [third_party](/third_party) - Tools for integrating third party libraries like WPILib.
72 changes: 35 additions & 37 deletions docs/CODE-STRUCTURE.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ Data logging of inputs should occur between the control logic and hardware inter

![Diagram of restructured subsystem](resources/subsystem-2.png)

> Note: You can refer to the [AdvantageKit command-based example](INSTALLATION.md#new-projects) or [6328's 2022 robot code](https://github.com/Mechanical-Advantage/RobotCode2022/tree/main/src/main/java/frc/robot/subsystems) for some example IO interfaces and implementations.
> Note: You can refer to the [AdvantageKit examples](INSTALLATION.md#new-projects) or [6328's 2022 robot code](https://github.com/Mechanical-Advantage/RobotCode2022/tree/main/src/main/java/frc/robot/subsystems) for some reference IO interfaces and implementations.
Outputs (setting voltage, setpoint, PID constants, etc.) make use of simple methods for each command. Input data is more controlled such that it can be logged and replayed. Each IO interface defines a class with public attributes for all input data, along with methods for saving and replaying that data from a log (`toLog` and `fromLog`). We recommend using the [`@AutoLog`](#autolog-annotation) annotation to generate these methods automatically.

Expand All @@ -30,7 +30,6 @@ Logger.processInputs("ExampleSubsystem", inputs); // Send input data to the logg
The rest of the subsystem then reads data from this inputs object rather than directly from the IO layer. This structure ensures that:

- The logging framework has access to all of the data being logged and can insert data from the log during replay.

- Throughout each cycle, all code making use of the input data reads the same values - the cache is never updated _during a cycle_. This means that the data replayed from the log appears identical to the data read on the real robot.

All of the IO methods include a default implementation which is used during simulation. We suggest setting up each subsystem accept the IO object as a constructor argument, so that the central robot class (like `RobotContainer`) can decide whether or not to use real hardware:
Expand All @@ -53,6 +52,38 @@ public RobotContainer() {

> Note: We suggest the use of an IO layer to minimize the chance of interacting with hardware that doesn't exist. However, any structure will work where all input data flows through an inputs object implementing `LoggableInputs` and the two methods `fromLog` and `toLog`. Feel free to make use of whatever structure best fits your own requirements.
## `AutoLog` Annotation & Data Types

By adding the `@AutoLog` annotation to your inputs class, AdvantageKit will automatically generate implementations of `toLog` and `fromLog` for your inputs. All simple data types (including single values and arrays) are supported. [Structured data types](DATA-FLOW.md#structured-data-types) are also supported, so geometry objects like `Rotation2d` and `Pose3d` can be directly used as inputs.

For example:

```java
@AutoLog
public class MyInputs {
public double myNumber = 0.0;
public Pose2d myPose = new Pose2d();
}
```

This will generate the following class:

```java
class MyInputsAutoLogged extends MyInputs implements LoggableInputs {
public void toLog(LogTable table) {
table.put("MyNumber", myField);
table.put("MyPose", myPose);
}

public void fromLog(LogTable table) {
myNumber = table.get("MyNumber", myNumber);
myPose = table.get("MyPose", myPose);
}
}
```

Note that you should use the `<className>AutoLogged` class, rather than your annotated class. The [AdvantageKit examples projects](INSTALLATION.md#new-projects) are a useful reference for how to use `@AutoLog` in a full project.

## Dashboard Options & NetworkTables Inputs

Like the robot's hardware, **data retrieved from NetworkTables must be isolated and treated as input data.** For example, the following call will NOT function correctly in replay:
Expand Down Expand Up @@ -93,16 +124,12 @@ public Command getAutonomousCommand() {
Output data consists of any calculated values which could be recreated in the simulator, including...

- Odometry pose

- Motor voltages

- Pneumatics commands

- Status data for drivers

- Internal object state

The logging framework supports recording this output data on the real robot and during replay. Essential data like the odometry pose are recorded on the real robot for convenience; even if it can be recreated in a simulator, that's often not a viable option in the rush to fix a problem between matches. During replay, recording extra output data is the primary method of debugging the code - logging calls can be added anywhere as they don't interfere with the replayed control logic. Any loggable data type [(see here)](DATA-FLOW.md) can be saved as an output like so:
The logging framework supports recording this output data on the real robot and during replay. Essential data like the odometry pose are recorded on the real robot for convenience; even if it can be recreated in a simulator, that's often not a viable option in the rush to fix a problem between matches. During replay, recording extra output data is the primary method of debugging the code - logging calls can be added anywhere as they don't interfere with the replayed control logic. Any loggable data type ([see here](DATA-FLOW.md#simple-data-types)) can be saved as an output like so:

```java
Logger.recordOutput("Flywheel/Setpoint", setpointSpeed);
Expand All @@ -112,7 +139,7 @@ Logger.recordOutput("Drive/CalculatedLeftVolts", leftVolts);

> Note: This data is automatically saved to the `RealOutputs` or `ReplayOutputs` table, and it can be divided further into subtables using slashes (as seen above).
Logging geometry objects like `Pose2d`, `Trajectory`, etc. is common in robot code. AdvantageKit includes the following functions to easily log these objects in the formats expected by AdvantageScope:
Logging geometry objects like `Pose2d`, `Trajectory`, etc. is common in robot code. Many WPILib classes can be serialized to binary data using [structs](https://github.com/wpilibsuite/allwpilib/blob/main/wpiutil/doc/struct.adoc) or [protobufs](https://protobuf.dev). These objects can be logged as single values or arrays:

```java
// Pose2d
Expand Down Expand Up @@ -143,32 +170,3 @@ AdvantageKit can also log [`Mechanism2d`](https://docs.wpilib.org/en/stable/docs
Mechanism2d mechanism = new Mechanism2d(3, 3);
Logger.recordOutput("MyMechanism", mechanism);
```

## `@AutoLog` Annotation

As of version 1.8, a new `@AutoLog` annotation was added. By adding this annotation to your inputs class, AdvantageKit will automatically generate implementations of `toLog` and `fromLog` for your inputs.

For example:

```java
@AutoLog
public class MyInputs {
public double myField = 0;
}
```

This will generate the following class:

```java
class MyInputsAutoLogged extends MyInputs implements LoggableInputs {
public void toLog(LogTable table) {
table.put("MyField", myField);
}

public void fromLog(LogTable table) {
myField = table.getDouble("MyField", myField);
}
}
```

Note that you should use the `<className>AutoLogged` class, rather than your annotated class. The [AdvantageKit command-based project](INSTALLATION.md#new-projects) is a good example of the `@AutoLog` annotation in a full project.
72 changes: 72 additions & 0 deletions docs/COMMON-ISSUES.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
# Common Issues (And How To Avoid Them)

## Non-Deterministic Data Sources

AdvantageKit replay relies on all data sources being deterministic and synchronized. IO interfaces ensure this is the case for subsystems, and AdvantageKit automatically handles replay for core WPILib classes (`DriverStation`, `RobotController`, and `PowerDistribution`). However, it's easy to accidentally use data from sources that are not properly logged. **We recommend regularly testing out log replay during development to confirm that the replay outputs match the real outputs.** Spotting mistakes like this early is the key to fixing them before it becomes a critical issue at an event.

Some common non-deterministic data sources to watch out for include:

- NetworkTables data as inputs, including from driver dashboards. See [here](CODE-STRUCTURE.md#dashboard-options--networktables-inputs).
- Large hardware libraries like [YAGSL](https://github.com/BroncBotz3481/YAGSL) or [Phoenix 6 swerve](https://v6.docs.ctr-electronics.com/en/latest/docs/tuner/tuner-swerve/index.html), which interact with hardware directly instead of through an IO layer. Try using the AdvantageKit [swerve template project](INSTALLATION.md#new-projects) instead.
- Interactions with the RIO filesystem. Files can be saved and read by the robot code, but incoming data still needs to be treated as an input.
- Random number generation, which cannot be recreated in a simulator.

## Multithreading

The main robot code logic must be single threaded to work with log replay. This is because the timing of extra threads cannot be recreated in simulation; threads will not execute at the same rate consistently, especially on different hardware.

There are two solutions to this issue:

- Threads are rarely required in FRC code, so start by considering alternatives. Control loop can often run great at 50Hz in the main robot thread, or consider using the closed-loop features of your preferred motor controller instead.
- If a thread is truly required, it must be isolated to an IO implementation. Since the inputs to the rest of the robot code are logged periodically, long-running tasks or high frequency control loops are possible (but as part of an IO implementation, they cannot be recreated during log replay).

> Note: PathPlanner includes a replanning feature that makes use of threads. The default implementation must be replaced with an AdvantageKit-compatible version as seen below. This class is included in AdvantageKit's [swerve template project](INSTALLATION.md#new-projects).
```java
Pathfinding.setPathfinder(new LocalADStarAK());
```

## Uninitialized Inputs

Typically, inputs from subsystems are only updated during calls to `periodic`. Note that this means updated (non-default) input data is not available in the constructor. The solution is to either wait for the first `periodic` call or call `periodic` from within the constructor.

```java
public class Example extends SubsystemBase {
private final ExampleIO io;
private final ExampleIOInputs inputs = new ExampleIOInputs();

public Example(ExampleIO io) {
this.io = io;

// Inputs are not updated yet
inputs.position;
}

@Override
public void periodic() {
io.updateInputs(inputs);
Logger.processInputs("Example", inputs);

// Inputs are now updated
inputs.position;
}
}
```

## Deterministic Timestamps

AdvantageKit's deterministic timestamps don't have significant effect on almost all FRC code. However, they may cause unexpected behavior for very advanced use cases. See [here](DATA-FLOW.md#deterministic-timestamps) for details.

## Unit Testing

Many units tests are unaffected by AdvantageKit's WPILib shims, but those which rely on data from `DriverStation` or `RobotController` (such as battery voltage) may not function as expected. This is because simulated inputs (as set by classes like `RoboRioSim`) are not updated outside of the periodic functions of `LoggedRobot`. To fix this, manually capture data and update the logging objects through a method like this:

```java
private void refreshAkitData() {
ConduitApi.getInstance().captureData();
LoggedDriverStation.getInstance().periodic();
LoggedSystemStats.getInstance().periodic();
}
```

`refreshAkitData()` should be called after any updates to the simulated values managed by AdvantageKit.
24 changes: 21 additions & 3 deletions docs/DATA-FLOW.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@
- **Real robot/simulator** - When running on a real robot (or a physics simulation, Romi, etc.), `Logger` reads data from the user program and built-in sources, then saves it to one or more targets (usually a log file).
- **Replay** - During this mode, which runs in the simulator, `Logger` reads data from an external source like a log file and writes it out to the user program. It then records the original data (plus any outputs from the user program) to a separate log file.

## Components

![Diagram of data flow](resources/data-flow.png)

Below are definitions of each component:
Expand All @@ -17,20 +19,36 @@ Below are definitions of each component:
- **LoggedSystemStats** _(Built-in input)_ - Internal class for recording and replaying data from the roboRIO (battery voltage, rail status, CAN status).
- **LoggedPowerDistribution** _(Built-in input)_ - Internal class for recording and replaying data from the PDP or PDH (channel currents, faults, etc).

Data is stored using string keys where slashes are used to denote subtables (similar to NetworkTables). Each subsystem stores data in a separate subtable. Like NetworkTables, **all logged values are persistent (they will continue to appear on subsequent cycles until updated**). The following data types are currently supported:
## Simple Data Types

Data is stored using string keys where slashes are used to denote subtables (similar to NetworkTables). Each subsystem stores data in a separate subtable. Like NetworkTables, **all logged values are persistent (they will continue to appear on subsequent cycles until updated**). The following simple data types are currently supported:

`boolean, long, float, double, String, boolean[], long[], float[], double[], String[], byte[]`

## Structured Data Types

Many WPILib classes can be serialized to binary data using [structs](https://github.com/wpilibsuite/allwpilib/blob/main/wpiutil/doc/struct.adoc) or [protobufs](https://protobuf.dev). Supported classes include `Translation2d`, `Pose3d`, and `SwerveModuleState` with more coming soon. These classes can be logged as single values or arrays just like any simple type, and used as input or output fields.

AdvantageKit also supports logging the state of a `Mechanism2d` object as an output. For details, see [here](CODE-STRUCTURE.md#logging-outputs).

## Deterministic Timestamps

### The Problem

To guarantee accurate replay, all of the data used by the robot code must be included in the log file and replayed in simulation. This includes the current timestamp, which may be used for calculations in control loops. WPILib's default behavior is to read the timestamp directly from the FPGA every time a method like `Timer.getFPGATimestamp()` is called. Every return value will be slightly different as the timestamp continues increasing throughout each loop cycle. This behavior is problematic for AdvantageKit replay, because the return values from those method calls are not logged and **cannot be accurately replayed in simulation**.

AdvantageKit's solution is to use _synchronized timestamps_. The timestamp is read once from the FPGA at the start of the loop cycle and injected into WPILib. By default, all calls to `Timer.getFPGATimestamp()` or similar return the synchronized timestamp from AdvantageKit instead of the "real" FPGA time. During replay, the logged timestamp is used for each loop cycle. The result is that all of the control logic is _deterministic_ and will **exactly match the behavior of the real robot**.

Optionally, AdvantageKit allows you to disable these deterministic timestamps. This reverts to the default WPILib behavior of reading from the FPGA for every method call, making the behavior of the robot code non-deterministic. The "output" values seen in simulation may be slightly different than they were on the real robot. This alternative mode should only be used when _all_ of the following are true:
### Solution #1

Where precise timestamps are required, the best solution is to record measurement timestamps as part of the input data for each subsystem. For example, [NetworkTables](https://docs.wpilib.org/en/stable/docs/software/networktables/publish-and-subscribe.html#subscribing-to-a-topic) and [Phoenix 6](https://api.ctr-electronics.com/phoenix6/release/java/com/ctre/phoenix6/StatusSignal.SignalMeasurement.html#timestamp) include methods to read the timestamp of each update, which can be used in calculations for wheel odometry, vision localization, or other precise controls alongside AdvantageKit's deterministic timestamps. For most use cases, measuring the timestamp of the original sample is more desirable than measuring the precise timestamp on the robot.

### Solution #2

Optionally, AdvantageKit allows you to disable deterministic timestamps. This reverts to the default WPILib behavior of reading from the FPGA for every method call, making the behavior of the robot code non-deterministic. The "output" values seen in simulation may be slightly different than they were on the real robot. This alternative mode should only be used when _all_ of the following are true:

1. The control logic depends on the exact timestamp _within_ a single loop cycle, like a high precision control loop that is significantly affected by the precise time that it is executed within each (usually 20ms) loop cycle.
2. The sensor values used in the loop cannot be associated with timestamps in an IO implementation. For example, vision data from a coprocessor is usually transmitted over the network with an exact timestamp (read in an IO implementation). That timestamp can be passed as an input to the main control logic and used alongside AdvantageKit's standard deterministic timestamps.
2. The sensor values used in the loop cannot be associated with timestamps in an IO implementation. See the solution #1.
3. The IO (sensors, actuators, etc) involved in the loop are sufficiently low-latency that the exact timestamp on the RIO is significant. For example, CAN motor controllers are limited by the rate of their CAN frames, so the extra precision on the RIO is insignificant in most cases.

Note that `Logger.getRealTimestamp()` can always be used to access the "real" FPGA timestamp where necessary, like within IO implementations or for analyzing performance. AdvantageKit shims WPILib classes like `Watchdog` to use this method because they use the timestamp for analyzing performance and are not part of the robot's control logic.
Expand Down
Loading

0 comments on commit b18ceaa

Please sign in to comment.