diff --git a/examples/src/main/java/io/github/oblarg/logexample/subsystems/DriveSubsystem.java b/examples/src/main/java/io/github/oblarg/logexample/subsystems/DriveSubsystem.java
index 63893f3..790ce70 100644
--- a/examples/src/main/java/io/github/oblarg/logexample/subsystems/DriveSubsystem.java
+++ b/examples/src/main/java/io/github/oblarg/logexample/subsystems/DriveSubsystem.java
@@ -7,10 +7,13 @@
package io.github.oblarg.logexample.subsystems;
+import edu.wpi.first.math.geometry.Pose2d;
+import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.motorcontrol.PWMVictorSPX;
+import edu.wpi.first.wpilibj.smartdashboard.Field2d;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import io.github.oblarg.logexample.Constants.DriveConstants;
@@ -19,6 +22,10 @@
import io.github.oblarg.oblog.annotations.Log;
public class DriveSubsystem extends SubsystemBase implements Loggable {
+
+ @Log.Field2d(name = "Field")
+ Field2d m_field = new Field2d();
+
// The motors on the left side of the drive.
@Log.MotorController(name = "Left Motors")
private final MotorControllerGroup m_leftMotors =
@@ -111,4 +118,9 @@ public Encoder getRightEncoder() {
public void setMaxOutput(double maxOutput) {
m_drive.setMaxOutput(maxOutput);
}
+
+ @Override
+ public void periodic(){
+ m_field.setRobotPose(new Pose2d(0,0,new Rotation2d(0)));
+ }
}
diff --git a/examples/src/main/java/io/github/oblarg/logexample/subsystems/ShooterSubsystem.java b/examples/src/main/java/io/github/oblarg/logexample/subsystems/ShooterSubsystem.java
index 89ba827..13d2543 100644
--- a/examples/src/main/java/io/github/oblarg/logexample/subsystems/ShooterSubsystem.java
+++ b/examples/src/main/java/io/github/oblarg/logexample/subsystems/ShooterSubsystem.java
@@ -32,7 +32,7 @@ public class ShooterSubsystem extends PIDSubsystem implements Loggable {
private final SimpleMotorFeedforward m_shooterFeedforward =
new SimpleMotorFeedforward(ShooterConstants.kSVolts,
ShooterConstants.kVVoltSecondsPerRotation);
-
+
/**
* The shooter subsystem for the robot.
*/
diff --git a/lib/src/main/java/io/github/oblarg/oblog/Logger.java b/lib/src/main/java/io/github/oblarg/oblog/Logger.java
index 215be6d..bd725db 100644
--- a/lib/src/main/java/io/github/oblarg/oblog/Logger.java
+++ b/lib/src/main/java/io/github/oblarg/oblog/Logger.java
@@ -864,6 +864,22 @@ void processSetter(
.withSize(params.width(), params.height())
.getEntry(),
() -> getFromMethod(supplierFinal, params.methodName()).get().toString());
+ }),
+ entry(
+ Log.Field2d.class,
+ (supplier, rawParams, bin, name) -> {
+ Log.Field2d params = (Log.Field2d) rawParams;
+ bin =
+ params.tabName().equals("DEFAULT")
+ ? bin
+ : new WrappedShuffleboardContainer(Shuffleboard.getTab(params.tabName()));
+ supplier = getFromMethod(supplier, params.methodName());
+ bin.add(
+ (params.name().equals("NO_NAME")) ? name : params.name(),
+ (Sendable) supplier.get())
+ .withWidget(BuiltInWidgets.kField.getWidgetName())
+ .withPosition(params.columnIndex(), params.rowIndex())
+ .withSize(params.width(), params.height());
}));
/** Maps various classes to the correct method for casting to that class. */
diff --git a/lib/src/main/java/io/github/oblarg/oblog/annotations/Log.java b/lib/src/main/java/io/github/oblarg/oblog/annotations/Log.java
index 817674e..02ba2ea 100644
--- a/lib/src/main/java/io/github/oblarg/oblog/annotations/Log.java
+++ b/lib/src/main/java/io/github/oblarg/oblog/annotations/Log.java
@@ -1330,4 +1330,68 @@ edu.wpi.first.wpilibj.interfaces.Accelerometer.Range range() default
@Retention(RetentionPolicy.RUNTIME)
@Target({ElementType.FIELD})
@interface Include {}
+ /**
+ * Displays the position of robot on the playing field.
+ * Supported types:
+ *
+ *