, SwerveModuleConfig...)","u":"%3Cinit%3E(edu.wpi.first.math.kinematics.SwerveDriveKinematics,edu.wpi.first.math.Matrix,edu.wpi.first.math.Matrix,common.core.swerve.SwerveModuleConfig...)"},{"p":"common.core.swerve","c":"SwerveConversions","l":"SwerveConversions()","u":"%3Cinit%3E()"},{"p":"common.core.swerve","c":"SwerveModule","l":"SwerveModule(SwerveModuleConfig)","u":"%3Cinit%3E(common.core.swerve.SwerveModuleConfig)"},{"p":"common.core.swerve","c":"SwerveModuleConfig","l":"SwerveModuleConfig(int, SwerveModuleConfig.SwerveMotorConfig, SwerveModuleConfig.SwerveMotorConfig, int, double, boolean, double)","u":"%3Cinit%3E(int,common.core.swerve.SwerveModuleConfig.SwerveMotorConfig,common.core.swerve.SwerveModuleConfig.SwerveMotorConfig,int,double,boolean,double)"},{"p":"common.core.swerve","c":"SwerveModuleConstants","l":"SwerveModuleConstants(int, int, int, double)","u":"%3Cinit%3E(int,int,int,double)"},{"p":"common.core.swerve","c":"SwerveModuleConfig.SwerveMotorConfig","l":"SwerveMotorConfig(int, NAR_Motor.MotorConfig, PIDFFConfig)","u":"%3Cinit%3E(int,common.hardware.motorcontroller.NAR_Motor.MotorConfig,common.core.controllers.PIDFFConfig)"},{"p":"common.hardware.motorcontroller","c":"MotorControllerConstants","l":"TALONSRX_ENCODER_RESOLUTION"},{"p":"common.hardware.camera","c":"NAR_Camera","l":"targetAmbiguity()"},{"p":"common.hardware.camera","c":"NAR_Camera","l":"targetId()"},{"p":"common.hardware.limelight","c":"Limelight","l":"targetWidth"},{"p":"common.utility.tester","c":"Tester.UnitTest","l":"testName"},{"p":"common.utility.tester","c":"Tester.UnitTest","l":"testState"},{"p":"common.hardware.motorcontroller","c":"NAR_Motor","l":"timeConversionFactor"},{"p":"common.hardware.motorcontroller","c":"NAR_Motor.MotorConfig","l":"timeFactor"},{"p":"common.core.swerve","c":"SwerveBase","l":"toggle()"},{"p":"common.hardware.limelight","c":"LimelightData","l":"toString()"},{"p":"common.hardware.limelight","c":"LimelightKey","l":"toString()"},{"p":"common.utility.sysid","c":"PolynomialRegression","l":"toString()"},{"p":"common.core.controllers","c":"TrapController","l":"TrapController(PIDFFConfig, TrapezoidProfile.Constraints)","u":"%3Cinit%3E(common.core.controllers.PIDFFConfig,edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints)"},{"p":"common.core.controllers","c":"TrapController","l":"TrapController(PIDFFConfig, TrapezoidProfile.Constraints, double)","u":"%3Cinit%3E(common.core.controllers.PIDFFConfig,edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints,double)"},{"p":"common.hardware.motorcontroller","c":"NAR_Motor","l":"unitConversionFactor"},{"p":"common.utility.tester","c":"Tester.UnitTest","l":"UnitTest(String, Command)","u":"%3Cinit%3E(java.lang.String,edu.wpi.first.wpilibj2.command.Command)"},{"p":"common.utility.tester","c":"Tester.UnitTest","l":"UnitTest(String, Command, BooleanSupplier)","u":"%3Cinit%3E(java.lang.String,edu.wpi.first.wpilibj2.command.Command,java.util.function.BooleanSupplier)"},{"p":"common.utility","c":"Log","l":"unusual(String, String)","u":"unusual(java.lang.String,java.lang.String)"},{"p":"common.hardware.camera","c":"NAR_Camera","l":"update()"},{"p":"common.utility.shuffleboard","c":"NAR_Shuffleboard","l":"update()"},{"p":"common.hardware.motorcontroller","c":"NAR_Motor","l":"updateIO(NAR_MotorIOAutoLogged)","u":"updateIO(common.hardware.motorcontroller.NAR_MotorIOAutoLogged)"},{"p":"common.core.controllers","c":"ControllerBase","l":"useOutput()"},{"p":"common.core.subsystems","c":"ElevatorTemplate","l":"useOutput(double, double)","u":"useOutput(double,double)"},{"p":"common.core.subsystems","c":"NAR_PIDSubsystem","l":"useOutput(double, double)","u":"useOutput(double,double)"},{"p":"common.core.subsystems","c":"PivotTemplate","l":"useOutput(double, double)","u":"useOutput(double,double)"},{"p":"common.core.subsystems","c":"ShooterTemplate","l":"useOutput(double, double)","u":"useOutput(double,double)"},{"p":"common.hardware.limelight","c":"LimelightKey","l":"VALID_TARGET"},{"p":"common.hardware.limelight","c":"LimelightConstants","l":"VALUE_KEYS"},{"p":"common.hardware.limelight","c":"LimelightConstants","l":"VALUE_KEYS_PNP"},{"p":"common.core.controllers","c":"Controller.Type","l":"valueOf(String)","u":"valueOf(java.lang.String)"},{"p":"common.core.misc","c":"NAR_Robot.LoggingState","l":"valueOf(String)","u":"valueOf(java.lang.String)"},{"p":"common.hardware.input","c":"NAR_XboxController.XboxButton","l":"valueOf(String)","u":"valueOf(java.lang.String)"},{"p":"common.hardware.limelight","c":"LEDMode","l":"valueOf(String)","u":"valueOf(java.lang.String)"},{"p":"common.hardware.limelight","c":"LimelightKey","l":"valueOf(String)","u":"valueOf(java.lang.String)"},{"p":"common.hardware.limelight","c":"Pipeline","l":"valueOf(String)","u":"valueOf(java.lang.String)"},{"p":"common.hardware.limelight","c":"StreamMode","l":"valueOf(String)","u":"valueOf(java.lang.String)"},{"p":"common.hardware.motorcontroller","c":"NAR_CANSparkMax.EncoderType","l":"valueOf(String)","u":"valueOf(java.lang.String)"},{"p":"common.hardware.motorcontroller","c":"NAR_CANSparkMax.SparkMaxConfig","l":"valueOf(String)","u":"valueOf(java.lang.String)"},{"p":"common.hardware.motorcontroller","c":"NAR_Motor.Control","l":"valueOf(String)","u":"valueOf(java.lang.String)"},{"p":"common.hardware.motorcontroller","c":"NAR_Motor.Neutral","l":"valueOf(String)","u":"valueOf(java.lang.String)"},{"p":"common.utility.tester","c":"Tester.TestState","l":"valueOf(String)","u":"valueOf(java.lang.String)"},{"p":"common.core.controllers","c":"Controller.Type","l":"values()"},{"p":"common.core.misc","c":"NAR_Robot.LoggingState","l":"values()"},{"p":"common.hardware.input","c":"NAR_XboxController.XboxButton","l":"values()"},{"p":"common.hardware.limelight","c":"LEDMode","l":"values()"},{"p":"common.hardware.limelight","c":"LimelightKey","l":"values()"},{"p":"common.hardware.limelight","c":"Pipeline","l":"values()"},{"p":"common.hardware.limelight","c":"StreamMode","l":"values()"},{"p":"common.hardware.motorcontroller","c":"NAR_CANSparkMax.EncoderType","l":"values()"},{"p":"common.hardware.motorcontroller","c":"NAR_CANSparkMax.SparkMaxConfig","l":"values()"},{"p":"common.hardware.motorcontroller","c":"NAR_Motor.Control","l":"values()"},{"p":"common.hardware.motorcontroller","c":"NAR_Motor.Neutral","l":"values()"},{"p":"common.utility.tester","c":"Tester.TestState","l":"values()"},{"p":"common.hardware.motorcontroller","c":"NAR_Motor.NAR_MotorIO","l":"velocity"},{"p":"common.hardware.motorcontroller","c":"NAR_Motor.Control","l":"Velocity"},{"p":"common.core.controllers","c":"Controller.Type","l":"VELOCITY"},{"p":"common.hardware.motorcontroller","c":"NAR_CANSparkMax.SparkMaxConfig","l":"VELOCITY"},{"p":"common.hardware.limelight","c":"LimelightConstants","l":"VERTICAL_FOV"},{"p":"common.hardware.limelight","c":"LimelightKey","l":"VERTICAL_OFFSET"},{"p":"common.utility.shuffleboard","c":"NAR_Shuffleboard","l":"WINDOW_HEIGHT"},{"p":"common.utility.shuffleboard","c":"NAR_Shuffleboard","l":"WINDOW_WIDTH"},{"p":"common.core.swerve","c":"SwerveBase","l":"xlock()"},{"p":"common.core.swerve","c":"SwerveModule","l":"xLock(Rotation2d)","u":"xLock(edu.wpi.first.math.geometry.Rotation2d)"},{"p":"common.core.swerve","c":"SwerveBase","l":"zeroGyro(double)"}];updateSearchResults();
\ No newline at end of file
diff --git a/src/main/java/common/core/commands/NAR_PIDCommand.java b/src/main/java/common/core/commands/NAR_PIDCommand.java
index 25155d4..ae02b16 100644
--- a/src/main/java/common/core/commands/NAR_PIDCommand.java
+++ b/src/main/java/common/core/commands/NAR_PIDCommand.java
@@ -9,6 +9,12 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Subsystem;
+/**
+ * Team 3128's PIDCommand that uses a ControllerBase to control an output.
+ *
+ * @since 2024 Crescendo
+ * @author Mason Lam
+ */
public class NAR_PIDCommand extends Command {
/** Controller. */
protected final ControllerBase controller;
@@ -44,7 +50,13 @@ public void execute() {
controller.useOutput();
}
- public void end() {
+ @Override
+ public void end(boolean interrupted) {
controller.reset();
}
+
+ @Override
+ public boolean isFinished() {
+ return controller.atSetpoint();
+ }
}
diff --git a/src/main/java/common/core/controllers/TrapController.java b/src/main/java/common/core/controllers/TrapController.java
index b93aac4..f4627e2 100644
--- a/src/main/java/common/core/controllers/TrapController.java
+++ b/src/main/java/common/core/controllers/TrapController.java
@@ -1,8 +1,11 @@
package common.core.controllers;
import java.util.function.DoubleSupplier;
+
+import common.utility.narwhaldashboard.NarwhalDashboard;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.ProfiledPIDController;
+import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.util.sendable.SendableBuilder;
@@ -13,15 +16,17 @@
* @author Mason Lam
*/
public class TrapController extends ControllerBase {
+ public static boolean shouldLog = false;
+
private DoubleSupplier systemVelocity;
private TrapezoidProfile.State setpoint = new TrapezoidProfile.State();
private TrapezoidProfile.State tempSetpoint = new TrapezoidProfile.State();
private TrapezoidProfile.State prevSetpoint = new TrapezoidProfile.State();
+ private SimpleMotorFeedforward feedforward;
private TrapezoidProfile profile;
private double minimumInput;
private double maximumInput;
-
/**
* Create a new object to control PID + FF logic using a trapezoid profile for a subsystem.
* Sets kP, kI, kD, kS, kV, kA, kG, constraints, period values.
@@ -33,6 +38,7 @@ public class TrapController extends ControllerBase {
public TrapController(PIDFFConfig config, TrapezoidProfile.Constraints constraints, double period) {
super(config, period);
profile = new TrapezoidProfile(constraints);
+ feedforward = new SimpleMotorFeedforward(getkS(), getkV(), getkA());
systemVelocity = ()-> 0;
}
@@ -90,6 +96,7 @@ public double calculate(double measurement) {
setpoint.position = goalMinDistance + measurement;
tempSetpoint.position = setpointMinDistance + measurement;
}
+ if (shouldLog) NarwhalDashboard.getInstance().sendMessage("Position: " + tempSetpoint.position + "Velocity: " + tempSetpoint.velocity);
tempSetpoint = profile.calculate(getPeriod(), tempSetpoint, setpoint);
controller.setSetpoint(tempSetpoint.position);
final double output = super.calculate(measurement);
@@ -115,11 +122,10 @@ public double calculatePID(double measurement) {
*/
@Override
public double calculateFF(double pidOutput) {
- final double staticGain = !atSetpoint() ? Math.copySign(getkS(), pidOutput) : 0;
- final double velocityGain = getkV() * prevSetpoint.velocity;
- final double accelGain = getkA() * (tempSetpoint.velocity - prevSetpoint.velocity) / getPeriod();
+ final double simpleGain = feedforward.calculate(prevSetpoint.velocity, tempSetpoint.velocity, getPeriod());
final double gravityGain = getkG() * kG_Function.getAsDouble();
- return staticGain + velocityGain + accelGain + gravityGain;
+ if (shouldLog) NarwhalDashboard.getInstance().sendMessage("Simple Gain: " + simpleGain + "Gravity Gain: " + gravityGain);
+ return simpleGain + gravityGain;
}
/**
@@ -156,6 +162,8 @@ public boolean atSetpoint() {
*/
public void setSetpoint(TrapezoidProfile.State setpoint) {
this.setpoint = setpoint;
+ feedforward = new SimpleMotorFeedforward(getkS(), getkV(), getkA());
+ reset();
}
/**
diff --git a/src/main/java/common/core/subsystems/ElevatorTemplate.java b/src/main/java/common/core/subsystems/ElevatorTemplate.java
index 7104194..7f1ed8b 100644
--- a/src/main/java/common/core/subsystems/ElevatorTemplate.java
+++ b/src/main/java/common/core/subsystems/ElevatorTemplate.java
@@ -68,7 +68,7 @@ public Command moveElevator(double setpoint){
* @param power Power the motor is run at.
* @return Command setting elevator power.
*/
- public Command setElevator(double power){
+ public Command runElevator(double power){
return runOnce(() -> setPower(power));
}
diff --git a/src/main/java/common/core/subsystems/ManipulatorTemplate.java b/src/main/java/common/core/subsystems/ManipulatorTemplate.java
index 146c2c9..cf27422 100644
--- a/src/main/java/common/core/subsystems/ManipulatorTemplate.java
+++ b/src/main/java/common/core/subsystems/ManipulatorTemplate.java
@@ -71,7 +71,7 @@ public boolean hasObjectPresent(){
* @param power The power of the motor on [-1, 1]
*/
protected void setPower(double power){
- final double output = debug.getAsBoolean() ? powerSetpoint.getAsDouble() : power;
+ final double output = (debug != null && debug.getAsBoolean()) ? powerSetpoint.getAsDouble() : power;
for (final NAR_Motor motor : motors) {
motor.set(output);
}
@@ -113,8 +113,8 @@ public Command outtake() {
public void initShuffleboard() {
NAR_Shuffleboard.addData("Manipulator", "Object Present", ()-> hasObjectPresent(), 0, 0);
NAR_Shuffleboard.addData("Manipulator", "Manip current", () -> getCurrent(), 0, 1);
- var debugEntry = NAR_Shuffleboard.addData(getName(), "TOGGLE", false, 1, 0).withWidget("Toggle Button");
- debug = ()-> debugEntry.getEntry().getBoolean(false);
+ NAR_Shuffleboard.addData(getName(), "TOGGLE", false, 1, 0).withWidget("Toggle Button").getEntry();
+ debug = NAR_Shuffleboard.getBoolean(getName(), "TOGGLE");
NAR_Shuffleboard.addData(getName(), "DEBUG", ()-> debug.getAsBoolean(), 1, 1);
powerSetpoint = NAR_Shuffleboard.debug(getName(), "Debug_Setpoint", 0, 1,2);
}
diff --git a/src/main/java/common/core/subsystems/NAR_PIDSubsystem.java b/src/main/java/common/core/subsystems/NAR_PIDSubsystem.java
index 305b641..e98b135 100644
--- a/src/main/java/common/core/subsystems/NAR_PIDSubsystem.java
+++ b/src/main/java/common/core/subsystems/NAR_PIDSubsystem.java
@@ -128,7 +128,6 @@ public void periodic() {
final double measurement = getMeasurement();
final double velocity = (measurement - prevMeasurement) / updateTimer.get();
final double acceleration = (velocity - prevVelocity) / updateTimer.get();
- NAR_Shuffleboard.addData(getName(), "Measurement", measurement, 1, 1);
NAR_Shuffleboard.addData(getName(), "1stDerivative", velocity, 1, 2);
NAR_Shuffleboard.addData(getName(), "2ndDerivative", acceleration, 1, 3);
prevMeasurement = measurement;
@@ -147,9 +146,10 @@ public void initShuffleboard() {
NAR_Shuffleboard.addData(getName(), "AtSetpoint", ()-> atSetpoint(), 0, 3);
NAR_Shuffleboard.addData(getName(), "Enabled", ()-> isEnabled(), 1, 0);
+ NAR_Shuffleboard.addData(getName(), "Measurement", ()-> getMeasurement(), 1, 1);
- var debugEntry = NAR_Shuffleboard.addData(getName(), "TOGGLE", false, 2, 0).withWidget("Toggle Button").getEntry();
- debug = ()-> debugEntry.getBoolean(false);
+ NAR_Shuffleboard.addData(getName(), "TOGGLE", false, 2, 0).withWidget("Toggle Button");
+ debug = NAR_Shuffleboard.getBoolean(getName(), "TOGGLE");
NAR_Shuffleboard.addData(getName(), "DEBUG", ()-> debug.getAsBoolean(), 2, 1);
setpoint = NAR_Shuffleboard.debug(getName(), "Debug_Setpoint", 0, 2,2);
@@ -218,7 +218,7 @@ public void setkG_Function(DoubleSupplier kG_Function) {
*/
public void startPID(double setpoint) {
enable();
- controller.setSetpoint(MathUtil.clamp(debug.getAsBoolean() ? this.setpoint.getAsDouble() : setpoint, min, max));
+ controller.setSetpoint(MathUtil.clamp((debug != null && debug.getAsBoolean()) ? this.setpoint.getAsDouble() : setpoint, min, max));
}
/**
diff --git a/src/main/java/common/core/subsystems/PivotTemplate.java b/src/main/java/common/core/subsystems/PivotTemplate.java
index c849724..6b93812 100644
--- a/src/main/java/common/core/subsystems/PivotTemplate.java
+++ b/src/main/java/common/core/subsystems/PivotTemplate.java
@@ -18,7 +18,7 @@ public abstract class PivotTemplate extends NAR_PIDSubsystem{
* @param controller Controller to control motor output.
* @param motors Pivot motors.
*/
- public PivotTemplate(ControllerBase controller, double angleOffset, NAR_Motor...motors){
+ public PivotTemplate(ControllerBase controller, NAR_Motor...motors){
super(controller);
this.motors = motors;
configMotors();
@@ -58,7 +58,7 @@ public double getMeasurement() {
* @param setpoint Setpoint the pivot goes to.
* @return Command setting pivot setpoint.
*/
- public Command pivot(double setpoint){
+ public Command pivotTo(double setpoint){
return runOnce(() -> startPID(setpoint));
}
@@ -67,7 +67,7 @@ public Command pivot(double setpoint){
* @param power Power the motor is run at.
* @return Command setting pivot power.
*/
- public Command setPivot(double power){
+ public Command runPivot(double power){
return runOnce(() -> setPower(power));
}
diff --git a/src/main/java/common/core/swerve/SwerveBase.java b/src/main/java/common/core/swerve/SwerveBase.java
index 07a92f8..09afa93 100644
--- a/src/main/java/common/core/swerve/SwerveBase.java
+++ b/src/main/java/common/core/swerve/SwerveBase.java
@@ -30,7 +30,6 @@ public abstract class SwerveBase extends SubsystemBase {
protected SwerveDrivePoseEstimator odometry;
protected final SwerveModule[] modules;
private Pose2d estimatedPose;
- private boolean useShuffleboard = false;
public boolean fieldRelative;
public double maxSpeed;
@@ -56,13 +55,14 @@ public SwerveBase(SwerveDriveKinematics kinematics, Matrix stateStdDevs,
}
public void initShuffleboard() {
- useShuffleboard = true;
- for (SwerveModule module : modules) {
- NAR_Shuffleboard.addData("Swerve", "module " + module.moduleNumber, ()-> module.getCanCoder().getDegrees(), 0, module.moduleNumber);
- NAR_Shuffleboard.addData("Swerve", "Angle " + module.moduleNumber, ()-> module.getAngleMotor().getPosition(), 1, module.moduleNumber);
- NAR_Shuffleboard.addData("Swerve", "Drive " + module.moduleNumber, ()-> module.getDriveMotor().getVelocity(), 2, module.moduleNumber);
+ for (final SwerveModule module : modules) {
+ NAR_Shuffleboard.addData("Swerve", "CANcoder " + module.moduleNumber, ()-> module.getCanCoder().getDegrees(), 0, module.moduleNumber);
+ NAR_Shuffleboard.addData("Swerve", "Angle Motor " + module.moduleNumber, ()-> module.getState().angle.getDegrees(), 1, module.moduleNumber);
+ NAR_Shuffleboard.addData("Swerve", "Drive Motor" + module.moduleNumber, ()-> module.getState().speedMetersPerSecond, 2, module.moduleNumber);
}
NAR_Shuffleboard.addData("Swerve", "Pose", ()-> estimatedPose.toString(), 3, 0, 4, 1);
+ NAR_Shuffleboard.addData("Swerve", "Robot Velocity", getRobotVelocity().toString(), 3, 1, 4, 1);
+ NAR_Shuffleboard.addData("Swerve", "Velocity", getVelocity(), 3, 3, 1, 1);
NAR_Shuffleboard.addData("Swerve", "Field Velocity", ()-> getFieldVelocity().toString(), 3, 2, 4, 1);
NAR_Shuffleboard.addData("Swerve", "Gyro", ()-> getYaw(), 7, 0, 2, 2).withWidget("Gyro");
}
@@ -185,11 +185,6 @@ public void periodic() {
estimatedPose = odometry.getEstimatedPosition();
Logger.recordOutput("Swerve/ActualModuleStates", getStates());
Logger.recordOutput("Swerve/RobotRotation", getGyroRotation2d());
- if (useShuffleboard) {
- final ChassisSpeeds robotVelocity = getRobotVelocity();
- NAR_Shuffleboard.addData("Swerve", "Robot Velocity", robotVelocity.toString(), 3, 1, 4, 1);
- NAR_Shuffleboard.addData("Swerve", "Velocity", Math.hypot(robotVelocity.vxMetersPerSecond, robotVelocity.vyMetersPerSecond), 3, 3, 1, 1);
- }
}
public void resetAll() {
diff --git a/src/main/java/common/utility/shuffleboard/NAR_Shuffleboard.java b/src/main/java/common/utility/shuffleboard/NAR_Shuffleboard.java
index 5a98207..595dee5 100644
--- a/src/main/java/common/utility/shuffleboard/NAR_Shuffleboard.java
+++ b/src/main/java/common/utility/shuffleboard/NAR_Shuffleboard.java
@@ -2,7 +2,9 @@
import java.util.HashMap;
import java.util.Map;
+import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;
+import java.util.function.LongSupplier;
import java.util.function.Supplier;
import com.ctre.phoenix.sensors.WPI_PigeonIMU;
@@ -10,6 +12,7 @@
import common.core.misc.NAR_Robot;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.networktables.GenericEntry;
+import edu.wpi.first.networktables.NetworkTableValue;
import edu.wpi.first.util.sendable.Sendable;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
@@ -24,6 +27,7 @@
* @since 2022 Rapid React
* @author Mason Lam, Arav Chadha, Peter Ma
*/
+@SuppressWarnings("unused")
public class NAR_Shuffleboard {
static {
@@ -232,6 +236,7 @@ public static ComplexWidget addSendable(String tabName, String name, Sendable da
return Shuffleboard.getTab(tabName).add(name, data).withPosition(x,y).withSize(width, height);
}
catch(Exception e) {
+ e.printStackTrace();
return null;
}
}
@@ -264,6 +269,7 @@ public static ComplexWidget addVideoStream(String tabName, String name, String c
return videoStream;
}
catch(Exception e) {
+ e.printStackTrace();
return null;
}
}
@@ -331,22 +337,80 @@ public static String getSelectedAutoName() {
* @return DoubleSupplier containing the value in the widget
*/
public static DoubleSupplier debug(String tabName, String name, double Default, int x, int y) {
- if(!tabs.containsKey(tabName)){
- create_tab(tabName);
- }
- SimpleWidget tab = addData(tabName, name, Default, x, y);
- return ()-> tab.getEntry().getDouble(Default);
+ final GenericEntry tab = addData(tabName, name, Default, x, y).getEntry();
+ return ()-> tab.getDouble(Default);
+ }
+
+ /**
+ * Get the network table reference of a widget.
+ *
+ * @param tabName the title of the tab to select
+ * @param name the name of the widget.
+ * @return NetworkTableValue of the widget
+ */
+ public static NetworkTableValue getValue(String tabName, String name){
+ final NetworkTableValue entry = tabs.get(tabName).get(name).m_entry.get();
+ return entry;
+ }
+
+ /**
+ * Get the value reference of a widget storing objects.
+ *
+ * @param tabName the title of the tab to select
+ * @param name the name of the widget
+ * @return ObjectSupplier referencing the widget
+ */
+ public static Supplier