Skip to content

Commit

Permalink
Merge pull request #16 from AnotherUser12/master
Browse files Browse the repository at this point in the history
Add Field2d Annotation
  • Loading branch information
Oblarg authored Nov 13, 2022
2 parents a2cb135 + 264c4ed commit 540c46b
Show file tree
Hide file tree
Showing 4 changed files with 93 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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 =
Expand Down Expand Up @@ -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)));
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -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.
*/
Expand Down
16 changes: 16 additions & 0 deletions lib/src/main/java/io/github/oblarg/oblog/Logger.java
Original file line number Diff line number Diff line change
Expand Up @@ -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. */
Expand Down
64 changes: 64 additions & 0 deletions lib/src/main/java/io/github/oblarg/oblog/annotations/Log.java
Original file line number Diff line number Diff line change
Expand Up @@ -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. <br>
* Supported types:
*
* <ul>
* <li>{@link edu.wpi.first.wpilibj.smartdashboard.Field2d}
* </ul>
*
* <br>
*/
@Repeatable(Field2ds.class)
@Retention(RetentionPolicy.RUNTIME)
@Target({ElementType.FIELD, ElementType.METHOD})
@interface Field2d {
/** @return The name of the value on Shuffleboard; defaults to field or method name. */
String name() default "NO_NAME";

/**
* @return The name of the tab in which to place this widget, if the default inferred tab/layout
* is not desired. Users should be careful to avoid namespace collisions if the default tab
* is not used. Note that Log and config annotations can be repeated to place widgets on
* multiple tabs.
*/
String tabName() default "DEFAULT";

/**
* @return Optional name of a method to call on the field (or return value of the method) to
* obtain the actual value that will be logged. Useful if one does not desire to make an
* entire object Loggable, but still wants to log a value from it.
*/
String methodName() default "DEFAULT";

/**
* @return The row in which this widget should be placed. WARNING: If position/size is specified
* for one widget in an object, it should be specified for all widgets in that object to
* avoid overlaps.
*/
int rowIndex() default -1;

/**
* @return The column in which this widget should be placed. WARNING: If position/size is
* specified for one widget in an object, it should be specified for all widgets in that
* object to avoid overlaps.
*/
int columnIndex() default -1;

/**
* @return The width of this widget. WARNING: If position/size is specified for one widget in an
* object, it should be specified for all widgets in that object to avoid overlaps.
*/
int width() default -1;

/**
* @return The height of this widget. WARNING: If position/size is specified for one widget in
* an object, it should be specified for all widgets in that object to avoid overlaps.
*/
int height() default -1;
}

@Retention(RetentionPolicy.RUNTIME)
@Target({ElementType.FIELD, ElementType.METHOD})
@interface Field2ds {
Field2d[] value();
}
}

0 comments on commit 540c46b

Please sign in to comment.