mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpilib] Remove Shuffleboard API (#7730)
This commit is contained in:
@@ -68,7 +68,6 @@
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Joystick",
|
||||
"Shuffleboard",
|
||||
"Pneumatics"
|
||||
],
|
||||
"foldername": "solenoid",
|
||||
@@ -108,8 +107,7 @@
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Ultrasonic",
|
||||
"SmartDashboard",
|
||||
"Shuffleboard"
|
||||
"SmartDashboard"
|
||||
],
|
||||
"foldername": "ultrasonic",
|
||||
"gradlebase": "java",
|
||||
@@ -308,22 +306,6 @@
|
||||
"mainclass": "Main",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Shuffleboard",
|
||||
"description": "Present various data via the Shuffleboard API.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Differential Drive",
|
||||
"Elevator",
|
||||
"Analog",
|
||||
"Encoder",
|
||||
"Shuffleboard"
|
||||
],
|
||||
"foldername": "shuffleboard",
|
||||
"gradlebase": "java",
|
||||
"mainclass": "Main",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "'Traditional' Hatchbot",
|
||||
"description": "A fully-functional command-based hatchbot for the 2019 game, written in the 'traditional' style, i.e. commands are given their own classes.",
|
||||
@@ -333,7 +315,6 @@
|
||||
"Differential Drive",
|
||||
"Encoder",
|
||||
"Pneumatics",
|
||||
"Shuffleboard",
|
||||
"Sendable",
|
||||
"DataLog",
|
||||
"XboxController"
|
||||
@@ -352,7 +333,6 @@
|
||||
"Differential Drive",
|
||||
"Encoder",
|
||||
"Pneumatics",
|
||||
"Shuffleboard",
|
||||
"Sendable",
|
||||
"DataLog",
|
||||
"PS4Controller"
|
||||
|
||||
@@ -9,11 +9,9 @@ import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbotinlined.commands.Autos;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems.HatchSubsystem;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.EventImportance;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandPS4Controller;
|
||||
|
||||
@@ -64,28 +62,11 @@ public class RobotContainer {
|
||||
m_chooser.addOption("Complex Auto", m_complexAuto);
|
||||
|
||||
// Put the chooser on the dashboard
|
||||
Shuffleboard.getTab("Autonomous").add(m_chooser);
|
||||
SmartDashboard.putData("Autonomous", m_chooser);
|
||||
|
||||
// Put subsystems to dashboard.
|
||||
Shuffleboard.getTab("Drivetrain").add(m_robotDrive);
|
||||
Shuffleboard.getTab("HatchSubsystem").add(m_hatchSubsystem);
|
||||
|
||||
// Set the scheduler to log Shuffleboard events for command initialize, interrupt, finish
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandInitialize(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command initialized", command.getName(), EventImportance.kNormal));
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandInterrupt(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command interrupted", command.getName(), EventImportance.kNormal));
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandFinish(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command finished", command.getName(), EventImportance.kNormal));
|
||||
SmartDashboard.putData("Drivetrain", m_robotDrive);
|
||||
SmartDashboard.putData("HatchSubsystem", m_hatchSubsystem);
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -17,11 +17,9 @@ import edu.wpi.first.wpilibj.examples.hatchbottraditional.commands.HalveDriveSpe
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.commands.ReleaseHatch;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems.HatchSubsystem;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.EventImportance;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
||||
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
|
||||
|
||||
/**
|
||||
@@ -71,32 +69,10 @@ public class RobotContainer {
|
||||
m_chooser.addOption("Complex Auto", m_complexAuto);
|
||||
|
||||
// Put the chooser on the dashboard
|
||||
Shuffleboard.getTab("Autonomous").add(m_chooser);
|
||||
SmartDashboard.putData("Autonomous", m_chooser);
|
||||
// Put subsystems to dashboard.
|
||||
Shuffleboard.getTab("Drivetrain").add(m_robotDrive);
|
||||
Shuffleboard.getTab("HatchSubsystem").add(m_hatchSubsystem);
|
||||
|
||||
// Log Shuffleboard events for command initialize, execute, finish, interrupt
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandInitialize(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command initialized", command.getName(), EventImportance.kNormal));
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandExecute(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command executed", command.getName(), EventImportance.kNormal));
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandFinish(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command finished", command.getName(), EventImportance.kNormal));
|
||||
CommandScheduler.getInstance()
|
||||
.onCommandInterrupt(
|
||||
command ->
|
||||
Shuffleboard.addEventMarker(
|
||||
"Command interrupted", command.getName(), EventImportance.kNormal));
|
||||
SmartDashboard.putData("Drivetrain", m_robotDrive);
|
||||
SmartDashboard.putData("HatchSubsystem", m_hatchSubsystem);
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -1,25 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.shuffleboard;
|
||||
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
*
|
||||
* <p>If you change your main robot class, change the parameter type.
|
||||
*/
|
||||
public static void main(String... args) {
|
||||
RobotBase.startRobot(Robot::new);
|
||||
}
|
||||
}
|
||||
@@ -1,66 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.shuffleboard;
|
||||
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.util.sendable.SendableRegistry;
|
||||
import edu.wpi.first.wpilibj.AnalogPotentiometer;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
|
||||
public class Robot extends TimedRobot {
|
||||
private final PWMSparkMax m_leftDriveMotor = new PWMSparkMax(0);
|
||||
private final PWMSparkMax m_rightDriveMotor = new PWMSparkMax(1);
|
||||
private final DifferentialDrive m_tankDrive =
|
||||
new DifferentialDrive(m_leftDriveMotor::set, m_rightDriveMotor::set);
|
||||
private final Encoder m_leftEncoder = new Encoder(0, 1);
|
||||
private final Encoder m_rightEncoder = new Encoder(2, 3);
|
||||
|
||||
private final PWMSparkMax m_elevatorMotor = new PWMSparkMax(2);
|
||||
private final AnalogPotentiometer m_elevatorPot = new AnalogPotentiometer(0);
|
||||
private final GenericEntry m_maxSpeed;
|
||||
|
||||
/** Called once at the beginning of the robot program. */
|
||||
public Robot() {
|
||||
SendableRegistry.addChild(m_tankDrive, m_leftDriveMotor);
|
||||
SendableRegistry.addChild(m_tankDrive, m_rightDriveMotor);
|
||||
|
||||
// Add a 'max speed' widget to a tab named 'Configuration', using a number slider
|
||||
// The widget will be placed in the second column and row and will be TWO columns wide
|
||||
m_maxSpeed =
|
||||
Shuffleboard.getTab("Configuration")
|
||||
.add("Max Speed", 1)
|
||||
.withWidget("Number Slider")
|
||||
.withPosition(1, 1)
|
||||
.withSize(2, 1)
|
||||
.getEntry();
|
||||
|
||||
// Add the tank drive and encoders to a 'Drivebase' tab
|
||||
ShuffleboardTab driveBaseTab = Shuffleboard.getTab("Drivebase");
|
||||
driveBaseTab.add("Tank Drive", m_tankDrive);
|
||||
// Put both encoders in a list layout
|
||||
ShuffleboardLayout encoders =
|
||||
driveBaseTab.getLayout("Encoders", BuiltInLayouts.kList).withPosition(0, 0).withSize(2, 2);
|
||||
encoders.add("Left Encoder", m_leftEncoder);
|
||||
encoders.add("Right Encoder", m_rightEncoder);
|
||||
|
||||
// Add the elevator motor and potentiometer to an 'Elevator' tab
|
||||
ShuffleboardTab elevatorTab = Shuffleboard.getTab("Elevator");
|
||||
elevatorTab.add("Motor", m_elevatorMotor);
|
||||
elevatorTab.add("Potentiometer", m_elevatorPot);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void autonomousInit() {
|
||||
// Read the value of the 'max speed' widget from the dashboard
|
||||
m_tankDrive.setMaxOutput(m_maxSpeed.getDouble(1.0));
|
||||
}
|
||||
}
|
||||
@@ -10,8 +10,7 @@ import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.Solenoid;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
|
||||
/**
|
||||
* This is a sample program showing the use of the solenoid classes during operator control. Three
|
||||
@@ -46,29 +45,28 @@ public class Robot extends TimedRobot {
|
||||
|
||||
/** Called once at the beginning of the robot program. */
|
||||
public Robot() {
|
||||
// Publish elements to shuffleboard.
|
||||
ShuffleboardTab tab = Shuffleboard.getTab("Pneumatics");
|
||||
tab.add("Single Solenoid", m_solenoid);
|
||||
tab.add("Double Solenoid", m_doubleSolenoid);
|
||||
tab.add("Compressor", m_compressor);
|
||||
|
||||
// Also publish some raw data
|
||||
// Get the pressure (in PSI) from the analog sensor connected to the PH.
|
||||
// This function is supported only on the PH!
|
||||
// On a PCM, this function will return 0.
|
||||
tab.addDouble("PH Pressure [PSI]", m_compressor::getPressure);
|
||||
// Get compressor current draw.
|
||||
tab.addDouble("Compressor Current", m_compressor::getCurrent);
|
||||
// Get whether the compressor is active.
|
||||
tab.addBoolean("Compressor Active", m_compressor::isEnabled);
|
||||
// Get the digital pressure switch connected to the PCM/PH.
|
||||
// The switch is open when the pressure is over ~120 PSI.
|
||||
tab.addBoolean("Pressure Switch", m_compressor::getPressureSwitchValue);
|
||||
// Publish elements to dashboard.
|
||||
SmartDashboard.putData("Single Solenoid", m_solenoid);
|
||||
SmartDashboard.putData("Double Solenoid", m_doubleSolenoid);
|
||||
SmartDashboard.putData("Compressor", m_compressor);
|
||||
}
|
||||
|
||||
@SuppressWarnings("PMD.UnconditionalIfStatement")
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
// Publish some raw data
|
||||
// Get the pressure (in PSI) from the analog sensor connected to the PH.
|
||||
// This function is supported only on the PH!
|
||||
// On a PCM, this function will return 0.
|
||||
SmartDashboard.putNumber("PH Pressure [PSI]", m_compressor.getPressure());
|
||||
// Get compressor current draw.
|
||||
SmartDashboard.putNumber("Compressor Current", m_compressor.getCurrent());
|
||||
// Get whether the compressor is active.
|
||||
SmartDashboard.putBoolean("Compressor Active", m_compressor.isEnabled());
|
||||
// Get the digital pressure switch connected to the PCM/PH.
|
||||
// The switch is open when the pressure is over ~120 PSI.
|
||||
SmartDashboard.putBoolean("Pressure Switch", m_compressor.getPressureSwitchValue());
|
||||
|
||||
/*
|
||||
* The output of GetRawButton is true/false depending on whether
|
||||
* the button is pressed; Set takes a boolean for whether
|
||||
|
||||
@@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.examples.ultrasonic;
|
||||
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.Ultrasonic;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
|
||||
/**
|
||||
@@ -21,7 +20,7 @@ public class Robot extends TimedRobot {
|
||||
public Robot() {
|
||||
// Add the ultrasonic on the "Sensors" tab of the dashboard
|
||||
// Data will update automatically
|
||||
Shuffleboard.getTab("Sensors").add(m_rangeFinder);
|
||||
SmartDashboard.putData("Sensors", m_rangeFinder);
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
Reference in New Issue
Block a user