Our team is using Network table entry, but it looks way too much like copy paste code and I was wondering if there was a better way to do it.
public class ShuffleDisplay {
private ShuffleboardTab shuffleDrivetrainTab = Shuffleboard.getTab("Drivetrain");
private ShuffleboardTab shuffleIntakeTab = Shuffleboard.getTab("Intake");
private ShuffleboardTab shuffleTurretTab = Shuffleboard.getTab("Turret");
ShuffleboardLayout frontLeftWheel = _addLayout(shuffleDrivetrainTab, "Front Left Module", BuiltInLayouts.kList, 2, 2, 0, 0, Map.of());
ShuffleboardLayout frontRightWheel = _addLayout(shuffleDrivetrainTab, "Front Right Module", BuiltInLayouts.kList, 2, 2, 2, 0, Map.of());
ShuffleboardLayout backLeftWheel = _addLayout(shuffleDrivetrainTab, "Back Left Module", BuiltInLayouts.kList, 2, 2, 0, 2, Map.of());
ShuffleboardLayout backRightWheel = _addLayout(shuffleDrivetrainTab, "Back Right Module", BuiltInLayouts.kList, 2, 2, 2, 2, Map.of());
ShuffleboardLayout Important_ball_Info = _addLayout(shuffleIntakeTab, "Important Ballfo", BuiltInLayouts.kList, 2, 2, 3, 4, Map.of());
public NetworkTableEntry drivetrainFrontLeftWheelVelocity;
public NetworkTableEntry drivetrainFrontLeftWheelWheelPosition;
public NetworkTableEntry drivetrainFrontRightWheelVelocity;
public NetworkTableEntry drivetrainFrontRightWheelWheelPosition;
public NetworkTableEntry drivetrainBackLeftWheelVelocity;
public NetworkTableEntry drivetrainBackLeftWheelWheelPosition;
public NetworkTableEntry drivetrainBackRightWheelVelocity;
public NetworkTableEntry drivetrainBackRightWheelWheelPosition;
public NetworkTableEntry calibrateButton;
public NetworkTableEntry calibrateBoolean;
public NetworkTableEntry setDeadband;
public NetworkTableEntry Gyro;
public NetworkTableEntry FieldOrient;
public NetworkTableEntry ChassisSpeed;
public ShuffleDisplay() {
// Front Left Wheel Module Widgets
drivetrainFrontLeftWheelVelocity = _addWidgetToLayout(frontLeftWheel, "Velocity", 0, BuiltInWidgets.kDial, Map.of());
drivetrainFrontLeftWheelWheelPosition = _addWidgetToLayout(frontLeftWheel, "Wheel Angle", 0, BuiltInWidgets.kTextView, Map.of());
// Front Right Wheel Module Widgets
drivetrainFrontRightWheelVelocity = _addWidgetToLayout(frontRightWheel, "Velocity", 0, BuiltInWidgets.kDial, Map.of());
drivetrainFrontRightWheelWheelPosition = _addWidgetToLayout(frontRightWheel, "Wheel Angle", 0, BuiltInWidgets.kTextView, Map.of());
// Back Left Wheel Module Widgets
drivetrainBackLeftWheelVelocity = _addWidgetToLayout(backLeftWheel, "Velocity", 0, BuiltInWidgets.kDial, Map.of());
drivetrainBackLeftWheelWheelPosition = _addWidgetToLayout(backLeftWheel, "Wheel Angle", 0, BuiltInWidgets.kTextView, Map.of());
// Back Right Wheel Module Widgets
drivetrainBackRightWheelVelocity = _addWidgetToLayout(backRightWheel, "Velocity", 0, BuiltInWidgets.kDial, Map.of());
drivetrainBackRightWheelWheelPosition = _addWidgetToLayout(backRightWheel, "Wheel Angle", 0, BuiltInWidgets.kTextView, Map.of());
/*
* Intake Ball info ShuffleboardComponent Boolean_1 = _addWidgetToLayout(Important_ball_Info,
* "1 ball", BuiltInWidgets.kBooleanBox, Map.of()); ShuffleboardComponent Boolean_2 =
* _addWidgetToLayout(Important_ball_Info, "2nd ball", BuiltInWidgets.kBooleanBox, Map.of());
* ShuffleboardComponent Boolean_color = _addWidgetToLayout(Important_ball_Info, "ball color",
* BuiltInWidgets.kBooleanBox, Map.of()); ShuffleboardComponent Swatch =
* _addWidgetToLayout(Important_ball_Info, "Switch", BuiltInWidgets.kToggleSwitch, Map.of());
* ShuffleboardComponent Swatch2 = _addWidgetToLayout(Important_ball_Info, "Switch",
* BuiltInWidgets.kToggleSwitch, Map.of());
*/
// Calibrate button
calibrateButton = _addWidgetToTab(shuffleDrivetrainTab, "Calibrate", false, BuiltInWidgets.kToggleButton, 1, 1, 5, 0, Map.of());
calibrateBoolean = _addWidgetToTab(shuffleDrivetrainTab, "Calibrate 0/I", false, BuiltInWidgets.kBooleanBox, 1, 1, 5, 1, Map.of());
Gyro = _addWidgetToTab(shuffleDrivetrainTab, "Gyro", 0, BuiltInWidgets.kGyro, 2, 2, 4, 2, Map.of());
FieldOrient = _addWidgetToTab(shuffleDrivetrainTab, "Field Orient", true, BuiltInWidgets.kBooleanBox, 1, 1, 4, 0, Map.of());
ChassisSpeed = _addWidgetToTab(shuffleDrivetrainTab, "ChassisSpeed", 0, BuiltInWidgets.kTextView, 1, 1, 4, 1, Map.of());
// Deadband Slider
setDeadband = _addWidgetToTab(shuffleDrivetrainTab, "Deadband", 0.1, BuiltInWidgets.kNumberSlider, 2, 1, 0, 4,
Map.of("min", 0.01, "max", 0.25));
}
private ShuffleboardLayout _addLayout(ShuffleboardTab tab, String name, BuiltInLayouts layout, int sizeX, int sizeY, int posX, int posY,
Map<String, Object> props) {
return tab.getLayout(name, layout).withPosition(posX, posY).withSize(sizeX, sizeY).withProperties(props);
}
private NetworkTableEntry _addWidgetToLayout(ShuffleboardLayout layout, String name, Object defaultValue, BuiltInWidgets Widget,
Map<String, Object> props) {
return layout.add(name, defaultValue).withWidget(Widget).withProperties(props).getEntry();
}
private NetworkTableEntry _addWidgetToTab(ShuffleboardTab tab, String name, Object defaulValue, BuiltInWidgets Widget, int sizeX, int sizeY,
int posX, int posY, Map<String, Object> props) {
return tab.add(name, defaulValue).withWidget(Widget).withPosition(posX, posY).withSize(sizeX, sizeY).withProperties(props).getEntry();
}
}
Incorporate into actual shuffleboard.
RobotConstants.ShuffleDashboard.drivetrainFrontLeftWheelVelocity.setDouble(m_frontLeft.getDriveVelocity());
RobotConstants.ShuffleDashboard.drivetrainFrontRightWheelVelocity.setDouble(m_frontRight.getDriveVelocity());
RobotConstants.ShuffleDashboard.drivetrainBackLeftWheelVelocity.setDouble(m_backLeft.getDriveVelocity());
RobotConstants.ShuffleDashboard.drivetrainBackRightWheelVelocity.setDouble(m_backRight.getDriveVelocity());
// Update wheel angles on Shuffleboard
RobotConstants.ShuffleDashboard.drivetrainFrontLeftWheelWheelPosition.setDouble(m_frontLeft.getTurnEncoder());
RobotConstants.ShuffleDashboard.drivetrainFrontRightWheelWheelPosition.setDouble(m_frontRight.getTurnEncoder());
RobotConstants.ShuffleDashboard.drivetrainBackLeftWheelWheelPosition.setDouble(m_backLeft.getTurnEncoder());
RobotConstants.ShuffleDashboard.drivetrainBackRightWheelWheelPosition.setDouble(m_backRight.getTurnEncoder());
RobotConstants.ShuffleDashboard.Gyro.setDouble(navx.getAngle());
RobotConstants.ShuffleDashboard.FieldOrient.setBoolean(ControllerDrive.fieldOrient);
RobotConstants.ShuffleDashboard.ChassisSpeed
.setDouble(Math.sqrt(Math.pow(getChassisSpeed().vxMetersPerSecond, 2) + Math.pow(getChassisSpeed().vyMetersPerSecond, 2)));
// Show if swerve is disabled on Shuffleboard and update when button is pressed
RobotConstants.ShuffleDashboard.calibrateBoolean.setBoolean(m_swerveDisabled);
m_swerveDisabled = RobotConstants.ShuffleDashboard.calibrateButton.getBoolean(m_swerveDisabled);
RobotConstants.DriveConstants.innerDeadband = RobotConstants.ShuffleDashboard.setDeadband
.getDouble(RobotConstants.DriveConstants.innerDeadband);