Skip to content

Commit

Permalink
Add AutoLogOutput annotation
Browse files Browse the repository at this point in the history
  • Loading branch information
jwbonner committed Nov 11, 2023
1 parent 8c873c9 commit 9581f67
Show file tree
Hide file tree
Showing 9 changed files with 422 additions and 37 deletions.
30 changes: 27 additions & 3 deletions docs/CODE-STRUCTURE.md
Original file line number Diff line number Diff line change
Expand Up @@ -177,9 +177,33 @@ Logger.recordOutput("MySwerveModuleStates", stateA, stateB, stateC, stateD);
Logger.recordOutput("MySwerveModuleStates", new SwerveModuleState[] { stateA, stateB, stateC, stateD });
```

AdvantageKit can also log [`Mechanism2d`](https://docs.wpilib.org/en/stable/docs/software/dashboards/glass/mech2d-widget.html) objects as outputs, which can be viewed using AdvantageScope. Note that the call below only records the current state of the `Mechanism2d`, so it must be called every loop cycle after the object is updated.
The `@AutoLogOutput` annotation can also be used to automatically log the value of a field or getter method as an output periodically (including private fields and methods). The key will be selected automatically, or it can be overriden using the `key` parameter. All data types are supported, including arrays and structured data types.

```java
Mechanism2d mechanism = new Mechanism2d(3, 3);
Logger.recordOutput("MyMechanism", mechanism);
public class Example {
@AutoLogOutput // Logged as "Example/MyPose"
private Pose2d myPose = new Pose2d();

@AutoLogOutput(key = "Custom/Speeds")
public double[] getSpeeds() {
...
}
}
```

> Note: The parent class where `@AutoLogOutput` is used must be instantiated within the first loop cycle, be accessible by a recursive search of the fields of `Robot`, and be within the same package as `Robot` (or a subpackage). This feature is primarily intended to log outputs from subsystems and other similar classes. For classes that do not fit the criteria above, call `Logger.recordOutput` periodically to record outputs.
AdvantageKit can also log [`Mechanism2d`](https://docs.wpilib.org/en/stable/docs/software/dashboards/glass/mech2d-widget.html) objects as outputs, which can be viewed using AdvantageScope. If not using `@AutoLogOutput`, note that the logging call only records the current state of the `Mechanism2d` and so it must be called periodically.

```java
public class Example {
@AutoLogOutput // Auto logged as "Example/Mechanism"
private Mechanism2d mechanism = new Mechanism2d(3, 3);

public void periodic() {
// Alternative approach if not using @AutoLogOutput
// (Must be called periodically)
Logger.recordOutput("Example/Mechanism", mechanism);
}
}
```
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;

public class Drive extends SubsystemBase {
Expand All @@ -39,9 +40,8 @@ public void periodic() {
io.updateInputs(inputs);
Logger.processInputs("Drive", inputs);

// Update odometry and log the new pose
// Update odometry
odometry.update(inputs.gyroYaw, getLeftPositionMeters(), getRightPositionMeters());
Logger.recordOutput("Odometry", getPose());
}

/** Run open loop at the specified percentage. */
Expand All @@ -61,6 +61,7 @@ public void stop() {
}

/** Returns the current odometry pose in meters. */
@AutoLogOutput
public Pose2d getPose() {
return odometry.getPoseMeters();
}
Expand All @@ -71,21 +72,25 @@ public void setPose(Pose2d pose) {
}

/** Returns the position of the left wheels in meters. */
@AutoLogOutput
public double getLeftPositionMeters() {
return inputs.leftPositionRad * WHEEL_RADIUS;
}

/** Returns the position of the right wheels in meters. */
@AutoLogOutput
public double getRightPositionMeters() {
return inputs.rightPositionRad * WHEEL_RADIUS;
}

/** Returns the velocity of the left wheels in meters/second. */
@AutoLogOutput
public double getLeftVelocityMeters() {
return inputs.leftVelocityRadPerSec * WHEEL_RADIUS;
}

/** Returns the velocity of the right wheels in meters/second. */
@AutoLogOutput
public double getRightVelocityMeters() {
return inputs.rightVelocityRadPerSec * WHEEL_RADIUS;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;

public class Flywheel extends SubsystemBase {
Expand Down Expand Up @@ -50,9 +51,6 @@ public Flywheel(FlywheelIO io) {
public void periodic() {
io.updateInputs(inputs);
Logger.processInputs("Flywheel", inputs);

// Log flywheel speed in RPM
Logger.recordOutput("FlywheelSpeedRPM", getVelocityRPM());
}

/** Run closed loop at the specified velocity. */
Expand All @@ -61,7 +59,7 @@ public void runVelocity(double velocityRPM) {
io.setVelocity(velocityRadPerSec, ffModel.calculate(velocityRadPerSec));

// Log flywheel setpoint
Logger.recordOutput("FlywheelSetpointRPM", velocityRPM);
Logger.recordOutput("Flywheel/SetpointRPM", velocityRPM);
}

/** Stops the flywheel. */
Expand All @@ -70,6 +68,7 @@ public void stop() {
}

/** Returns the current velocity in RPM. */
@AutoLogOutput
public double getVelocityRPM() {
return Units.radiansPerSecondToRotationsPerMinute(inputs.velocityRadPerSec);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.util.LocalADStarAK;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;

public class Drive extends SubsystemBase {
Expand Down Expand Up @@ -94,10 +95,6 @@ public void periodic() {
module.stop();
}
}

// Log measured states
Logger.recordOutput("SwerveStates/Measured", getModuleStates());

// Log empty setpoint states when disabled
if (DriverStation.isDisabled()) {
Logger.recordOutput("SwerveStates/Setpoints", new SwerveModuleState[] {});
Expand All @@ -123,7 +120,6 @@ public void periodic() {
}
// Apply the twist (change since last loop cycle) to the current pose
pose = pose.exp(twist);
Logger.recordOutput("Odometry/Robot", getPose());
}

/**
Expand Down Expand Up @@ -184,6 +180,7 @@ public double getCharacterizationVelocity() {
}

/** Returns the module states (turn angles and drive velocitoes) for all of the modules. */
@AutoLogOutput(key = "SwerveStates/Measured")
private SwerveModuleState[] getModuleStates() {
SwerveModuleState[] states = new SwerveModuleState[4];
for (int i = 0; i < 4; i++) {
Expand All @@ -193,6 +190,7 @@ private SwerveModuleState[] getModuleStates() {
}

/** Returns the current odometry pose. */
@AutoLogOutput(key = "Odometry/Robot")
public Pose2d getPose() {
return pose;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;

public class Flywheel extends SubsystemBase {
Expand Down Expand Up @@ -50,9 +51,6 @@ public Flywheel(FlywheelIO io) {
public void periodic() {
io.updateInputs(inputs);
Logger.processInputs("Flywheel", inputs);

// Log flywheel speed in RPM
Logger.recordOutput("FlywheelSpeedRPM", getVelocityRPM());
}

/** Run closed loop at the specified velocity. */
Expand All @@ -61,7 +59,7 @@ public void runVelocity(double velocityRPM) {
io.setVelocity(velocityRadPerSec, ffModel.calculate(velocityRadPerSec));

// Log flywheel setpoint
Logger.recordOutput("FlywheelSetpointRPM", velocityRPM);
Logger.recordOutput("Flywheel/SetpointRPM", velocityRPM);
}

/** Stops the flywheel. */
Expand All @@ -70,6 +68,7 @@ public void stop() {
}

/** Returns the current velocity in RPM. */
@AutoLogOutput
public double getVelocityRPM() {
return Units.radiansPerSecondToRotationsPerMinute(inputs.velocityRadPerSec);
}
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
// Copyright 2021-2023 FRC 6328
// http://github.com/Mechanical-Advantage
//
// This program is free software; you can redistribute it and/or
// modify it under the terms of the GNU General Public License
// version 3 as published by the Free Software Foundation or
// available in the root directory of this project.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package org.littletonrobotics.junction;

import java.lang.annotation.ElementType;
import java.lang.annotation.Retention;
import java.lang.annotation.RetentionPolicy;
import java.lang.annotation.Target;

@Retention(RetentionPolicy.RUNTIME)
@Target({ ElementType.FIELD, ElementType.METHOD })
public @interface AutoLogOutput {
public String key() default "";
}
Loading

0 comments on commit 9581f67

Please sign in to comment.