[wpilib] Split DriverStation into smaller classes (#8628)

This commit is contained in:
Thad House
2026-04-18 19:56:45 -07:00
committed by GitHub
parent 58ad633ae2
commit ab2aef2c29
108 changed files with 4406 additions and 3211 deletions

View File

@@ -0,0 +1,13 @@
// 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 org.wpilib.driverstation;
/** The robot alliance that the robot is a part of. */
public enum Alliance {
/** Red alliance. */
RED,
/** Blue alliance. */
BLUE
}

View File

@@ -4,6 +4,8 @@
package org.wpilib.driverstation;
import org.wpilib.driverstation.internal.DriverStationBackend;
/**
* A default implementation of UserControls that provides Gamepad instances for each of the 6
* joystick ports provided by the DS.
@@ -13,7 +15,7 @@ public class DefaultUserControls implements UserControls {
/** Constructs a DefaultUserControls instance with Gamepads for each port. */
public DefaultUserControls() {
m_gamepads = new Gamepad[DriverStation.kJoystickPorts];
m_gamepads = new Gamepad[DriverStationBackend.JOYSTICK_PORTS];
for (int i = 0; i < m_gamepads.length; i++) {
m_gamepads[i] = new Gamepad(i);
}

View File

@@ -0,0 +1,52 @@
// 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 org.wpilib.driverstation;
import org.wpilib.driverstation.internal.DriverStationBackend;
/** Provides access to error and warning reporting functionality to the Driver Station. */
public final class DriverStationErrors {
private DriverStationErrors() {}
/**
* Report error to Driver Station. Optionally appends Stack trace to error message.
*
* @param error The error to report.
* @param printTrace If true, append stack trace to error string
*/
public static void reportError(String error, boolean printTrace) {
DriverStationBackend.reportError(error, printTrace);
}
/**
* Report error to Driver Station. Appends provided stack trace to error message.
*
* @param error The error to report.
* @param stackTrace The stack trace to append
*/
public static void reportError(String error, StackTraceElement[] stackTrace) {
DriverStationBackend.reportError(error, stackTrace);
}
/**
* Report warning to Driver Station. Optionally appends Stack trace to warning message.
*
* @param warning The warning to report.
* @param printTrace If true, append stack trace to warning string
*/
public static void reportWarning(String warning, boolean printTrace) {
DriverStationBackend.reportWarning(warning, printTrace);
}
/**
* Report warning to Driver Station. Appends provided stack trace to warning message.
*
* @param warning The warning to report.
* @param stackTrace The stack trace to append
*/
public static void reportWarning(String warning, StackTraceElement[] stackTrace) {
DriverStationBackend.reportWarning(warning, stackTrace);
}
}

View File

@@ -4,6 +4,7 @@
package org.wpilib.driverstation;
import org.wpilib.driverstation.internal.DriverStationBackend;
import org.wpilib.event.BooleanEvent;
import org.wpilib.event.EventLoop;
import org.wpilib.hardware.hal.HAL;
@@ -1334,11 +1335,11 @@ public class Gamepad extends GenericHID implements Sendable {
}
private double getAxisForSendable(Axis axis) {
return DriverStation.getStickAxisIfAvailable(getPort(), axis.value).orElse(0.0);
return DriverStationBackend.getStickAxisIfAvailable(getPort(), axis.value).orElse(0.0);
}
private boolean getButtonForSendable(Button button) {
return DriverStation.getStickButtonIfAvailable(getPort(), button.value).orElse(false);
return DriverStationBackend.getStickButtonIfAvailable(getPort(), button.value).orElse(false);
}
@Override

View File

@@ -7,8 +7,7 @@ package org.wpilib.driverstation;
import java.util.EnumSet;
import java.util.HashMap;
import java.util.Map;
import org.wpilib.driverstation.DriverStation.POVDirection;
import org.wpilib.driverstation.DriverStation.TouchpadFinger;
import org.wpilib.driverstation.internal.DriverStationBackend;
import org.wpilib.event.BooleanEvent;
import org.wpilib.event.EventLoop;
import org.wpilib.hardware.hal.DriverStationJNI;
@@ -150,7 +149,7 @@ public class GenericHID {
* @return The state of the button.
*/
public boolean getRawButton(int button) {
return DriverStation.getStickButton(m_port, (byte) button);
return DriverStationBackend.getStickButton(m_port, (byte) button);
}
/**
@@ -164,7 +163,7 @@ public class GenericHID {
* @return Whether the button was pressed since the last check.
*/
public boolean getRawButtonPressed(int button) {
return DriverStation.getStickButtonPressed(m_port, (byte) button);
return DriverStationBackend.getStickButtonPressed(m_port, (byte) button);
}
/**
@@ -178,7 +177,7 @@ public class GenericHID {
* @return Whether the button was released since the last check.
*/
public boolean getRawButtonReleased(int button) {
return DriverStation.getStickButtonReleased(m_port, button);
return DriverStationBackend.getStickButtonReleased(m_port, button);
}
/**
@@ -202,7 +201,7 @@ public class GenericHID {
* @return The value of the axis.
*/
public double getRawAxis(int axis) {
return DriverStation.getStickAxis(m_port, axis);
return DriverStationBackend.getStickAxis(m_port, axis);
}
/**
@@ -212,7 +211,7 @@ public class GenericHID {
* @return the angle of the POV.
*/
public POVDirection getPOV(int pov) {
return DriverStation.getStickPOV(m_port, pov);
return DriverStationBackend.getStickPOV(m_port, pov);
}
/**
@@ -394,7 +393,7 @@ public class GenericHID {
* @return the maximum axis index for the joystick
*/
public int getAxesMaximumIndex() {
return DriverStation.getStickAxesMaximumIndex(m_port);
return DriverStationBackend.getStickAxesMaximumIndex(m_port);
}
/**
@@ -403,7 +402,7 @@ public class GenericHID {
* @return the number of axis for the current HID
*/
public int getAxesAvailable() {
return DriverStation.getStickAxesAvailable(m_port);
return DriverStationBackend.getStickAxesAvailable(m_port);
}
/**
@@ -412,7 +411,7 @@ public class GenericHID {
* @return the maximum POV index for the joystick
*/
public int getPOVsMaximumIndex() {
return DriverStation.getStickPOVsMaximumIndex(m_port);
return DriverStationBackend.getStickPOVsMaximumIndex(m_port);
}
/**
@@ -421,7 +420,7 @@ public class GenericHID {
* @return the number of POVs for the current HID
*/
public int getPOVsAvailable() {
return DriverStation.getStickPOVsAvailable(m_port);
return DriverStationBackend.getStickPOVsAvailable(m_port);
}
/**
@@ -430,7 +429,7 @@ public class GenericHID {
* @return the maximum button index for the joystick
*/
public int getButtonsMaximumIndex() {
return DriverStation.getStickButtonsMaximumIndex(m_port);
return DriverStationBackend.getStickButtonsMaximumIndex(m_port);
}
/**
@@ -439,7 +438,7 @@ public class GenericHID {
* @return the number of buttons for the current HID
*/
public long getButtonsAvailable() {
return DriverStation.getStickButtonsAvailable(m_port);
return DriverStationBackend.getStickButtonsAvailable(m_port);
}
/**
@@ -448,7 +447,7 @@ public class GenericHID {
* @return true if the HID is connected
*/
public boolean isConnected() {
return DriverStation.isJoystickConnected(m_port);
return DriverStationBackend.isJoystickConnected(m_port);
}
/**
@@ -457,7 +456,7 @@ public class GenericHID {
* @return the type of the HID.
*/
public HIDType getGamepadType() {
return HIDType.of(DriverStation.getJoystickGamepadType(m_port));
return HIDType.of(DriverStationBackend.getJoystickGamepadType(m_port));
}
/**
@@ -466,7 +465,7 @@ public class GenericHID {
* @return the supported outputs for the HID.
*/
public EnumSet<SupportedOutput> getSupportedOutputs() {
int supported = DriverStation.getJoystickSupportedOutputs(m_port);
int supported = DriverStationBackend.getJoystickSupportedOutputs(m_port);
EnumSet<SupportedOutput> outputs = EnumSet.noneOf(SupportedOutput.class);
for (SupportedOutput output : SupportedOutput.values()) {
if ((supported & output.getValue()) != 0) {
@@ -482,7 +481,7 @@ public class GenericHID {
* @return the name of the HID.
*/
public String getName() {
return DriverStation.getJoystickName(m_port);
return DriverStationBackend.getJoystickName(m_port);
}
/**
@@ -543,7 +542,7 @@ public class GenericHID {
* @return true if the touchpad finger is available.
*/
public boolean getTouchpadFingerAvailable(int touchpad, int finger) {
return DriverStation.getStickTouchpadFingerAvailable(m_port, touchpad, finger);
return DriverStationBackend.getStickTouchpadFingerAvailable(m_port, touchpad, finger);
}
/**
@@ -554,6 +553,6 @@ public class GenericHID {
* @return The touchpad finger data.
*/
public TouchpadFinger getTouchpadFinger(int touchpad, int finger) {
return DriverStation.getStickTouchpadFinger(m_port, touchpad, finger);
return DriverStationBackend.getStickTouchpadFinger(m_port, touchpad, finger);
}
}

View File

@@ -0,0 +1,104 @@
// 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 org.wpilib.driverstation;
import java.util.Optional;
import java.util.OptionalInt;
import org.wpilib.driverstation.internal.DriverStationBackend;
/** Provides access to match state information from the Driver Station. */
public final class MatchState {
private MatchState() {}
/**
* Return the approximate match time. The FMS does not send an official match time to the robots,
* but does send an approximate match time. The value will count down the time remaining in the
* current period (auto or teleop). Warning: This is not an official time (so it cannot be used to
* dispute ref calls or guarantee that a function will trigger before the match ends).
*
* <p>When connected to the real field, this number only changes in full integer increments, and
* always counts down.
*
* <p>When the DS is in practice mode, this number is a floating point number, and counts down.
*
* <p>When the DS is in teleop or autonomous mode, this number returns -1.0.
*
* <p>Simulation matches DS behavior without an FMS connected.
*
* @return Time remaining in current match period (auto or teleop) in seconds
*/
public static double getMatchTime() {
return DriverStationBackend.getMatchTime();
}
/**
* Get the current alliance from the FMS.
*
* <p>If the FMS is not connected, it is set from the team alliance setting on the driver station.
*
* @return The alliance (red or blue) or an empty optional if the alliance is invalid
*/
public static Optional<Alliance> getAlliance() {
return DriverStationBackend.getAlliance();
}
/**
* Gets the location of the team's driver station controls from the FMS.
*
* <p>If the FMS is not connected, it is set from the team alliance setting on the driver station.
*
* @return the location of the team's driver station controls: 1, 2, or 3
*/
public static OptionalInt getLocation() {
return DriverStationBackend.getLocation();
}
/**
* Get the replay number from the FMS.
*
* @return the replay number
*/
public static int getReplayNumber() {
return DriverStationBackend.getReplayNumber();
}
/**
* Get the match number from the FMS.
*
* @return the match number
*/
public static int getMatchNumber() {
return DriverStationBackend.getMatchNumber();
}
/**
* Get the match type from the FMS.
*
* @return the match type
*/
public static MatchType getMatchType() {
return DriverStationBackend.getMatchType();
}
/**
* Get the event name from the FMS.
*
* @return the event name
*/
public static String getEventName() {
return DriverStationBackend.getEventName();
}
/**
* Get the game specific message from the FMS.
*
* <p>If the FMS is not connected, it is set from the game data setting on the driver station.
*
* @return the game specific message
*/
public static Optional<String> getGameData() {
return DriverStationBackend.getGameData();
}
}

View File

@@ -0,0 +1,17 @@
// 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 org.wpilib.driverstation;
/** The type of robot match that the robot is part of. */
public enum MatchType {
/** None. */
NONE,
/** Practice. */
PRACTICE,
/** Qualification. */
QUALIFICATION,
/** Elimination. */
ELIMINATION
}

View File

@@ -0,0 +1,82 @@
// 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 org.wpilib.driverstation;
import java.util.Optional;
import org.wpilib.math.geometry.Rotation2d;
import org.wpilib.system.Timer;
/** A controller POV direction. */
public enum POVDirection {
/** POV center. */
CENTER(0x00),
/** POV up. */
UP(0x01),
/** POV up right. */
UP_RIGHT(0x01 | 0x02),
/** POV right. */
RIGHT(0x02),
/** POV down right. */
DOWN_RIGHT(0x02 | 0x04),
/** POV down. */
DOWN(0x04),
/** POV down left. */
DOWN_LEFT(0x04 | 0x08),
/** POV left. */
LEFT(0x08),
/** POV up left. */
UP_LEFT(0x01 | 0x08);
private static final double INVALID_POV_VALUE_INTERVAL = 1.0;
private static double s_nextMessageTime;
/**
* Converts a byte value into a POVDirection enum value.
*
* @param value The byte value to convert.
* @return The corresponding POVDirection enum value.
* @throws IllegalArgumentException If value does not correspond to a POVDirection.
*/
public static POVDirection of(byte value) {
for (var direction : values()) {
if (direction.value == value) {
return direction;
}
}
double currentTime = Timer.getTimestamp();
if (currentTime > s_nextMessageTime) {
DriverStationErrors.reportError("Invalid POV value " + value + "!", false);
s_nextMessageTime = currentTime + INVALID_POV_VALUE_INTERVAL;
}
return CENTER;
}
/** The corresponding HAL value. */
public final byte value;
POVDirection(int value) {
this.value = (byte) value;
}
/**
* Gets the angle of a POVDirection.
*
* @return The angle clockwise from straight up, or Optional.empty() if this POVDirection is
* CENTER.
*/
public Optional<Rotation2d> getAngle() {
return switch (this) {
case CENTER -> Optional.empty();
case UP -> Optional.of(Rotation2d.fromDegrees(0));
case UP_RIGHT -> Optional.of(Rotation2d.fromDegrees(45));
case RIGHT -> Optional.of(Rotation2d.fromDegrees(90));
case DOWN_RIGHT -> Optional.of(Rotation2d.fromDegrees(135));
case DOWN -> Optional.of(Rotation2d.fromDegrees(180));
case DOWN_LEFT -> Optional.of(Rotation2d.fromDegrees(225));
case LEFT -> Optional.of(Rotation2d.fromDegrees(270));
case UP_LEFT -> Optional.of(Rotation2d.fromDegrees(315));
};
}
}

View File

@@ -0,0 +1,270 @@
// 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 org.wpilib.driverstation;
import org.wpilib.driverstation.internal.DriverStationBackend;
import org.wpilib.hardware.hal.RobotMode;
import org.wpilib.util.Color;
/** Provides access to robot state information from the Driver Station. */
public final class RobotState {
private RobotState() {}
/**
* Gets a value indicating whether the Driver Station requires the robot to be enabled.
*
* @return True if the robot is enabled, false otherwise.
*/
public static boolean isEnabled() {
return DriverStationBackend.isEnabled();
}
/**
* Gets a value indicating whether the Driver Station requires the robot to be disabled.
*
* @return True if the robot should be disabled, false otherwise.
*/
public static boolean isDisabled() {
return DriverStationBackend.isDisabled();
}
/**
* Gets a value indicating whether the Robot is e-stopped.
*
* @return True if the robot is e-stopped, false otherwise.
*/
public static boolean isEStopped() {
return DriverStationBackend.isEStopped();
}
/**
* Gets the current robot mode.
*
* <p>Note that this does not indicate whether the robot is enabled or disabled.
*
* @return robot mode
*/
public static RobotMode getRobotMode() {
return DriverStationBackend.getRobotMode();
}
/**
* Gets a value indicating whether the Driver Station requires the robot to be running in
* autonomous mode.
*
* @return True if autonomous mode should be enabled, false otherwise.
*/
public static boolean isAutonomous() {
return DriverStationBackend.isAutonomous();
}
/**
* Gets a value indicating whether the Driver Station requires the robot to be running in
* autonomous mode and enabled.
*
* @return True if autonomous should be set and the robot should be enabled.
*/
public static boolean isAutonomousEnabled() {
return DriverStationBackend.isAutonomousEnabled();
}
/**
* Gets a value indicating whether the Driver Station requires the robot to be running in
* operator-controlled mode.
*
* @return True if operator-controlled mode should be enabled, false otherwise.
*/
public static boolean isTeleop() {
return DriverStationBackend.isTeleop();
}
/**
* Gets a value indicating whether the Driver Station requires the robot to be running in
* operator-controller mode and enabled.
*
* @return True if operator-controlled mode should be set and the robot should be enabled.
*/
public static boolean isTeleopEnabled() {
return DriverStationBackend.isTeleopEnabled();
}
/**
* Gets a value indicating whether the Driver Station requires the robot to be running in Test
* mode.
*
* @return True if test mode should be enabled, false otherwise.
*/
public static boolean isTest() {
return DriverStationBackend.isTest();
}
/**
* Gets a value indicating whether the Driver Station requires the robot to be running in Test
* mode and enabled.
*
* @return True if test mode should be set and the robot should be enabled.
*/
public static boolean isTestEnabled() {
return DriverStationBackend.isTestEnabled();
}
/**
* Adds an operating mode option. It's necessary to call publishOpModes() to make the added modes
* visible to the driver station.
*
* @param mode robot mode
* @param name name of the operating mode
* @param group group of the operating mode
* @param description description of the operating mode
* @param textColor text color, or null for default
* @param backgroundColor background color, or null for default
* @return unique ID used to later identify the operating mode
* @throws IllegalArgumentException if name is empty or an operating mode with the same robot mode
* and name already exists
*/
public static long addOpMode(
RobotMode mode,
String name,
String group,
String description,
Color textColor,
Color backgroundColor) {
return DriverStationBackend.addOpMode(
mode, name, group, description, textColor, backgroundColor);
}
/**
* Adds an operating mode option. It's necessary to call publishOpModes() to make the added modes
* visible to the driver station.
*
* @param mode robot mode
* @param name name of the operating mode
* @param group group of the operating mode
* @param description description of the operating mode
* @return unique ID used to later identify the operating mode
* @throws IllegalArgumentException if name is empty or an operating mode with the same name
* already exists
*/
public static long addOpMode(RobotMode mode, String name, String group, String description) {
return DriverStationBackend.addOpMode(mode, name, group, description);
}
/**
* Adds an operating mode option. It's necessary to call publishOpModes() to make the added modes
* visible to the driver station.
*
* @param mode robot mode
* @param name name of the operating mode
* @param group group of the operating mode
* @return unique ID used to later identify the operating mode
* @throws IllegalArgumentException if name is empty or an operating mode with the same name
* already exists
*/
public static long addOpMode(RobotMode mode, String name, String group) {
return DriverStationBackend.addOpMode(mode, name, group);
}
/**
* Adds an operating mode option. It's necessary to call publishOpModes() to make the added modes
* visible to the driver station.
*
* @param mode robot mode
* @param name name of the operating mode
* @return unique ID used to later identify the operating mode
* @throws IllegalArgumentException if name is empty or an operating mode with the same name
* already exists
*/
public static long addOpMode(RobotMode mode, String name) {
return DriverStationBackend.addOpMode(mode, name);
}
/**
* Removes an operating mode option. It's necessary to call publishOpModes() to make the removed
* mode no longer visible to the driver station.
*
* @param mode robot mode
* @param name name of the operating mode
* @return unique ID for the opmode, or 0 if not found
*/
public static long removeOpMode(RobotMode mode, String name) {
return DriverStationBackend.removeOpMode(mode, name);
}
/** Publishes the operating mode options to the driver station. */
public static void publishOpModes() {
DriverStationBackend.publishOpModes();
}
/** Clears all operating mode options and publishes an empty list to the driver station. */
public static void clearOpModes() {
DriverStationBackend.clearOpModes();
}
/**
* Gets the operating mode selected on the driver station. Note this does not mean the robot is
* enabled; use isEnabled() for that. In a match, this will indicate the operating mode selected
* for auto before the match starts (i.e., while the robot is disabled in auto mode); after the
* auto period ends, this will change to reflect the operating mode selected for teleop.
*
* @return the unique ID provided by the addOpMode() function; may return 0 or a unique ID not
* added, so callers should be prepared to handle that case
*/
public static long getOpModeId() {
return DriverStationBackend.getOpModeId();
}
/**
* Gets the operating mode selected on the driver station. Note this does not mean the robot is
* enabled; use isEnabled() for that. In a match, this will indicate the operating mode selected
* for auto before the match starts (i.e., while the robot is disabled in auto mode); after the
* auto period ends, this will change to reflect the operating mode selected for teleop.
*
* @return Operating mode string; may return a string not in the list of options, so callers
* should be prepared to handle that case
*/
public static String getOpMode() {
return DriverStationBackend.getOpMode();
}
/**
* Check to see if the selected operating mode is a particular value. Note this does not mean the
* robot is enabled; use isEnabled() for that.
*
* @param id operating mode unique ID
* @return True if that mode is the current mode
*/
public static boolean isOpMode(long id) {
return DriverStationBackend.isOpMode(id);
}
/**
* Check to see if the selected operating mode is a particular value. Note this does not mean the
* robot is enabled; use isEnabled() for that.
*
* @param mode operating mode
* @return True if that mode is the current mode
*/
public static boolean isOpMode(String mode) {
return DriverStationBackend.isOpMode(mode);
}
/**
* Gets a value indicating whether the Driver Station is attached.
*
* @return True if Driver Station is attached, false otherwise.
*/
public static boolean isDSAttached() {
return DriverStationBackend.isDSAttached();
}
/**
* Gets if the driver station attached to a Field Management System.
*
* @return true if the robot is competing on a field being controlled by a Field Management System
*/
public static boolean isFMSAttached() {
return DriverStationBackend.isFMSAttached();
}
}

View File

@@ -0,0 +1,31 @@
// 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 org.wpilib.driverstation;
/** Represents a finger on a touchpad. */
@SuppressWarnings("MemberName")
public final class TouchpadFinger {
/** Whether the finger is touching the touchpad. */
public final boolean down;
/** The x position of the finger. 0 is at top left. */
public final float x;
/** The y position of the finger. 0 is at top left. */
public final float y;
/**
* Creates a TouchpadFinger object.
*
* @param down Whether the finger is touching the touchpad.
* @param x The x position of the finger.
* @param y The y position of the finger.
*/
public TouchpadFinger(boolean down, float x, float y) {
this.x = x;
this.y = y;
this.down = down;
}
}

File diff suppressed because it is too large Load Diff

View File

@@ -4,7 +4,8 @@
package org.wpilib.framework;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.driverstation.DriverStationErrors;
import org.wpilib.driverstation.internal.DriverStationBackend;
import org.wpilib.hardware.hal.ControlWord;
import org.wpilib.hardware.hal.DriverStationJNI;
import org.wpilib.hardware.hal.HAL;
@@ -236,8 +237,8 @@ public abstract class IterativeRobotBase extends RobotBase {
/** Loop function. */
protected final void loopFunc() {
DriverStation.refreshData();
DriverStation.refreshControlWordFromCache(m_word);
DriverStationBackend.refreshData();
DriverStationBackend.refreshControlWordFromCache(m_word);
m_watchdog.reset();
// Get current mode; treat disabled as unknown
@@ -344,6 +345,6 @@ public abstract class IterativeRobotBase extends RobotBase {
}
private void printLoopOverrunMessage() {
DriverStation.reportWarning("Loop time of " + m_period + "s overrun\n", false);
DriverStationErrors.reportWarning("Loop time of " + m_period + "s overrun\n", false);
}
}

View File

@@ -20,9 +20,11 @@ import java.util.function.Supplier;
import java.util.jar.JarEntry;
import java.util.jar.JarFile;
import org.wpilib.driverstation.Alert;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.driverstation.DriverStationErrors;
import org.wpilib.driverstation.RobotState;
import org.wpilib.driverstation.UserControls;
import org.wpilib.driverstation.UserControlsInstance;
import org.wpilib.driverstation.internal.DriverStationBackend;
import org.wpilib.hardware.hal.ControlWord;
import org.wpilib.hardware.hal.DriverStationJNI;
import org.wpilib.hardware.hal.HAL;
@@ -82,7 +84,8 @@ public abstract class OpModeRobot extends RobotBase {
private final Alert m_loopOverrunAlert;
private static void reportAddOpModeError(Class<?> cls, String message) {
DriverStation.reportError("Error adding OpMode " + cls.getSimpleName() + ": " + message, false);
DriverStationErrors.reportError(
"Error adding OpMode " + cls.getSimpleName() + ": " + message, false);
}
private final Optional<Class<? extends UserControls>> m_userControlsBaseClass;
@@ -142,7 +145,7 @@ public abstract class OpModeRobot extends RobotBase {
private <T extends OpMode> T constructOpModeClass(Class<T> cls) {
Optional<ConstructorMatch<T>> constructor = findOpModeConstructor(cls);
if (constructor.isEmpty()) {
DriverStation.reportError(
DriverStationErrors.reportError(
"No suitable constructor to instantiate OpMode " + cls.getSimpleName(), true);
return null;
}
@@ -153,7 +156,7 @@ public abstract class OpModeRobot extends RobotBase {
return constructor.get().newInstance(this);
}
} catch (ReflectiveOperationException e) {
DriverStation.reportError(
DriverStationErrors.reportError(
"Could not instantiate OpMode " + cls.getSimpleName(), e.getStackTrace());
return null;
}
@@ -207,7 +210,7 @@ public abstract class OpModeRobot extends RobotBase {
String description,
Color textColor,
Color backgroundColor) {
long id = DriverStation.addOpMode(mode, name, group, description, textColor, backgroundColor);
long id = RobotState.addOpMode(mode, name, group, description, textColor, backgroundColor);
m_opModes.put(id, new OpModeFactory(name, factory));
}
@@ -355,7 +358,7 @@ public abstract class OpModeRobot extends RobotBase {
}
Color tColor = textColor.isBlank() ? null : Color.fromString(textColor);
Color bColor = backgroundColor.isBlank() ? null : Color.fromString(backgroundColor);
long id = DriverStation.addOpMode(mode, name, group, description, tColor, bColor);
long id = RobotState.addOpMode(mode, name, group, description, tColor, bColor);
m_opModes.put(id, new OpModeFactory(name, () -> constructOpModeClass(cls)));
}
@@ -504,7 +507,7 @@ public abstract class OpModeRobot extends RobotBase {
* @param name name of the operating mode
*/
public void removeOpMode(RobotMode mode, String name) {
long id = DriverStation.removeOpMode(mode, name);
long id = RobotState.removeOpMode(mode, name);
if (id != 0) {
m_opModes.remove(id);
}
@@ -512,12 +515,12 @@ public abstract class OpModeRobot extends RobotBase {
/** Publishes the operating mode options to the driver station. */
public void publishOpModes() {
DriverStation.publishOpModes();
RobotState.publishOpModes();
}
/** Clears all operating mode options and publishes an empty list to the driver station. */
public void clearOpModes() {
DriverStation.clearOpModes();
RobotState.clearOpModes();
m_opModes.clear();
}
@@ -562,7 +565,7 @@ public abstract class OpModeRobot extends RobotBase {
}
// Scan for annotated opmode classes within the derived class's package and subpackages
addAnnotatedOpModeClasses(getClass().getPackage());
DriverStation.publishOpModes();
RobotState.publishOpModes();
HAL.reportUsage("Framework", "OpModeRobot");
}
@@ -631,10 +634,10 @@ public abstract class OpModeRobot extends RobotBase {
/** Main robot loop function. Handles disabled state logic and opmode management. */
private void loopFunc() {
DriverStation.refreshData();
DriverStationBackend.refreshData();
// Get current enabled state and opmode
DriverStation.refreshControlWordFromCache(m_word);
DriverStationBackend.refreshControlWordFromCache(m_word);
m_watchdog.reset();
boolean enabled = m_word.isEnabled();
long modeId = m_word.isDSAttached() ? m_word.getOpModeId() : 0;
@@ -676,7 +679,7 @@ public abstract class OpModeRobot extends RobotBase {
m_callbacks.addAll(m_activeOpModeCallbacks);
}
} else {
DriverStation.reportError("No OpMode found for mode " + modeId, false);
DriverStationErrors.reportError("No OpMode found for mode " + modeId, false);
}
}
m_lastModeId = modeId;
@@ -723,7 +726,7 @@ public abstract class OpModeRobot extends RobotBase {
}
// Call nonePeriodic when no opmode is selected
if (DriverStation.getOpModeId() == 0) {
if (RobotState.getOpModeId() == 0) {
nonePeriodic();
m_watchdog.addEpoch("nonePeriodic()");
}
@@ -767,7 +770,7 @@ public abstract class OpModeRobot extends RobotBase {
}
// Tell the DS that the robot is ready to be enabled
DriverStation.observeUserProgramStarting();
DriverStationBackend.observeUserProgramStarting();
// Loop forever, calling the callback system which handles periodic functions
while (true) {

View File

@@ -6,9 +6,11 @@ package org.wpilib.framework;
import java.util.Optional;
import java.util.concurrent.locks.ReentrantLock;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.driverstation.DriverStationErrors;
import org.wpilib.driverstation.RobotState;
import org.wpilib.driverstation.UserControls;
import org.wpilib.driverstation.UserControlsInstance;
import org.wpilib.driverstation.internal.DriverStationBackend;
import org.wpilib.hardware.hal.HAL;
import org.wpilib.hardware.hal.HALUtil;
import org.wpilib.math.util.MathShared;
@@ -52,7 +54,7 @@ public abstract class RobotBase implements AutoCloseable {
@Override
public void reportDriverStationError(String error) {
DriverStation.reportError(error, true);
DriverStationErrors.reportError(error, true);
}
@Override
@@ -74,7 +76,7 @@ public abstract class RobotBase implements AutoCloseable {
new MathShared() {
@Override
public void reportError(String error, StackTraceElement[] stackTrace) {
DriverStation.reportError(error, stackTrace);
DriverStationErrors.reportError(error, stackTrace);
}
@Override
@@ -183,7 +185,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the Robot is currently disabled by the Driver Station.
*/
public static boolean isDisabled() {
return DriverStation.isDisabled();
return RobotState.isDisabled();
}
/**
@@ -192,7 +194,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the Robot is currently enabled by the Driver Station.
*/
public static boolean isEnabled() {
return DriverStation.isEnabled();
return RobotState.isEnabled();
}
/**
@@ -201,7 +203,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the robot is currently operating Autonomously.
*/
public static boolean isAutonomous() {
return DriverStation.isAutonomous();
return RobotState.isAutonomous();
}
/**
@@ -211,7 +213,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the robot is currently operating autonomously while enabled.
*/
public static boolean isAutonomousEnabled() {
return DriverStation.isAutonomousEnabled();
return RobotState.isAutonomousEnabled();
}
/**
@@ -220,7 +222,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the robot is currently operating in Test mode.
*/
public static boolean isTest() {
return DriverStation.isTest();
return RobotState.isTest();
}
/**
@@ -229,7 +231,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the robot is currently operating in Test mode while enabled.
*/
public static boolean isTestEnabled() {
return DriverStation.isTestEnabled();
return RobotState.isTestEnabled();
}
/**
@@ -239,7 +241,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the robot is currently operating in Tele-Op mode.
*/
public static boolean isTeleop() {
return DriverStation.isTeleop();
return RobotState.isTeleop();
}
/**
@@ -249,7 +251,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the robot is currently operating in Tele-Op mode while enabled.
*/
public static boolean isTeleopEnabled() {
return DriverStation.isTeleopEnabled();
return RobotState.isTeleopEnabled();
}
/**
@@ -260,7 +262,7 @@ public abstract class RobotBase implements AutoCloseable {
* unique ID not added, so callers should be prepared to handle that case
*/
public static long getOpModeId() {
return DriverStation.getOpModeId();
return RobotState.getOpModeId();
}
/**
@@ -271,7 +273,7 @@ public abstract class RobotBase implements AutoCloseable {
* should be prepared to handle that case
*/
public static String getOpMode() {
return DriverStation.getOpMode();
return RobotState.getOpMode();
}
/**
@@ -332,15 +334,15 @@ public abstract class RobotBase implements AutoCloseable {
if (elements.length > 0) {
robotName = elements[0].getClassName();
}
DriverStation.reportError(
DriverStationErrors.reportError(
"Unhandled exception instantiating robot " + robotName + " " + throwable, elements);
DriverStation.reportError(
DriverStationErrors.reportError(
"The robot program quit unexpectedly."
+ " This is usually due to a code error.\n"
+ " The above stacktrace can help determine where the error occurred.\n"
+ " See https://wpilib.org/stacktrace for more information.\n",
false);
DriverStation.reportError("Could not instantiate robot " + robotName + "!", false);
DriverStationErrors.reportError("Could not instantiate robot " + robotName + "!", false);
return;
}
@@ -356,7 +358,8 @@ public abstract class RobotBase implements AutoCloseable {
if (cause != null) {
throwable = cause;
}
DriverStation.reportError("Unhandled exception: " + throwable, throwable.getStackTrace());
DriverStationErrors.reportError(
"Unhandled exception: " + throwable, throwable.getStackTrace());
errorOnExit = true;
} finally {
m_runMutex.lock();
@@ -364,19 +367,20 @@ public abstract class RobotBase implements AutoCloseable {
m_runMutex.unlock();
if (!suppressExitWarning) {
// startCompetition never returns unless exception occurs....
DriverStation.reportWarning(
DriverStationErrors.reportWarning(
"The robot program quit unexpectedly."
+ " This is usually due to a code error.\n"
+ " The above stacktrace can help determine where the error occurred.\n"
+ " See https://wpilib.org/stacktrace for more information.",
false);
if (errorOnExit) {
DriverStation.reportError(
DriverStationErrors.reportError(
"The startCompetition() method (or methods called by it) should have "
+ "handled the exception above.",
false);
} else {
DriverStation.reportError("Unexpected return from startCompetition() method.", false);
DriverStationErrors.reportError(
"Unexpected return from startCompetition() method.", false);
}
}
}
@@ -408,7 +412,7 @@ public abstract class RobotBase implements AutoCloseable {
}
// Force refresh DS data
DriverStation.refreshData();
DriverStationBackend.refreshData();
HAL.reportUsage("Language", "Java");
HAL.reportUsage("WPILibVersion", WPILibVersion.Version);

View File

@@ -6,7 +6,7 @@ package org.wpilib.framework;
import static org.wpilib.units.Units.Seconds;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.driverstation.internal.DriverStationBackend;
import org.wpilib.hardware.hal.HAL;
import org.wpilib.hardware.hal.NotifierJNI;
import org.wpilib.internal.PeriodicPriorityQueue;
@@ -86,7 +86,7 @@ public class TimedRobot extends IterativeRobotBase {
// Tell the DS that the robot is ready to be enabled
System.out.println("********** Robot program startup complete **********");
DriverStation.observeUserProgramStarting();
DriverStationBackend.observeUserProgramStarting();
// Loop forever, calling the appropriate mode-dependent function
while (true) {

View File

@@ -13,7 +13,7 @@ import java.util.Map;
import java.util.Objects;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.driverstation.DriverStationErrors;
import org.wpilib.hardware.hal.HAL;
import org.wpilib.system.RobotController;
import org.wpilib.units.collections.LongToObjectHashMap;
@@ -576,13 +576,13 @@ public interface LEDPattern {
HAL.reportUsage("LEDPattern", "");
if (steps.isEmpty()) {
// no colors specified
DriverStation.reportWarning("Creating LED steps with no colors!", false);
DriverStationErrors.reportWarning("Creating LED steps with no colors!", false);
return kOff;
}
if (steps.size() == 1 && steps.keySet().iterator().next().doubleValue() == 0) {
// only one color specified, just show a static color
DriverStation.reportWarning("Creating LED steps with only one color!", false);
DriverStationErrors.reportWarning("Creating LED steps with only one color!", false);
return solid(steps.values().iterator().next());
}
@@ -638,13 +638,13 @@ public interface LEDPattern {
HAL.reportUsage("LEDPattern", "");
if (colors.length == 0) {
// Nothing to display
DriverStation.reportWarning("Creating a gradient with no colors!", false);
DriverStationErrors.reportWarning("Creating a gradient with no colors!", false);
return kOff;
}
if (colors.length == 1) {
// No gradients with one color
DriverStation.reportWarning("Creating a gradient with only one color!", false);
DriverStationErrors.reportWarning("Creating a gradient with only one color!", false);
return solid(colors[0]);
}

View File

@@ -6,7 +6,8 @@ package org.wpilib.hardware.motor;
import java.util.LinkedHashSet;
import java.util.Set;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.driverstation.DriverStationErrors;
import org.wpilib.driverstation.RobotState;
import org.wpilib.hardware.hal.ControlWord;
import org.wpilib.hardware.hal.DriverStationJNI;
import org.wpilib.system.Timer;
@@ -133,12 +134,12 @@ public abstract class MotorSafety {
stopTime = m_stopTime;
}
if (!enabled || DriverStation.isDisabled() || DriverStation.isTest()) {
if (!enabled || RobotState.isDisabled() || RobotState.isTest()) {
return;
}
if (stopTime < Timer.getMonotonicTimestamp()) {
DriverStation.reportError(
DriverStationErrors.reportError(
getDescription()
+ "... Output not updated often enough. See https://docs.wpilib.org/motorsafety for more information.",
false);

View File

@@ -6,7 +6,7 @@ package org.wpilib.internal;
import java.util.concurrent.atomic.AtomicBoolean;
import java.util.concurrent.atomic.AtomicLong;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.driverstation.internal.DriverStationBackend;
import org.wpilib.hardware.hal.ControlWord;
import org.wpilib.hardware.hal.DriverStationJNI;
import org.wpilib.util.WPIUtilJNI;
@@ -41,7 +41,7 @@ public class DriverStationModeThread implements AutoCloseable {
if (!m_keepAlive.get()) {
return;
}
DriverStation.refreshData();
DriverStationBackend.refreshData();
DriverStationJNI.observeUserProgram(m_userControlWord.get());
}
}

View File

@@ -5,7 +5,9 @@
package org.wpilib.simulation;
import java.util.function.BiConsumer;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.driverstation.MatchType;
import org.wpilib.driverstation.POVDirection;
import org.wpilib.driverstation.internal.DriverStationBackend;
import org.wpilib.hardware.hal.AllianceStationID;
import org.wpilib.hardware.hal.DriverStationJNI;
import org.wpilib.hardware.hal.OpModeOption;
@@ -321,7 +323,7 @@ public final class DriverStationSim {
}
DriverStationJNI.removeNewDataEventHandle(handle);
WPIUtilJNI.destroyEvent(handle);
DriverStation.refreshData();
DriverStationBackend.refreshData();
}
/**
@@ -392,7 +394,7 @@ public final class DriverStationSim {
* @param pov The POV number
* @param value the angle of the POV
*/
public static void setJoystickPOV(int stick, int pov, DriverStation.POVDirection value) {
public static void setJoystickPOV(int stick, int pov, POVDirection value) {
DriverStationDataJNI.setJoystickPOV(stick, pov, value.value);
}
@@ -523,7 +525,7 @@ public final class DriverStationSim {
*
* @param type the match type
*/
public static void setMatchType(DriverStation.MatchType type) {
public static void setMatchType(MatchType type) {
int matchType =
switch (type) {
case PRACTICE -> 1;

View File

@@ -5,8 +5,8 @@
package org.wpilib.simulation;
import java.util.EnumSet;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.driverstation.GenericHID;
import org.wpilib.driverstation.POVDirection;
/** Class to control a simulated generic joystick. */
public class GenericHIDSim {
@@ -62,7 +62,7 @@ public class GenericHIDSim {
* @param pov the POV to set
* @param value the new value
*/
public void setPOV(int pov, DriverStation.POVDirection value) {
public void setPOV(int pov, POVDirection value) {
DriverStationSim.setJoystickPOV(m_port, pov, value);
}
@@ -71,7 +71,7 @@ public class GenericHIDSim {
*
* @param value the new value
*/
public void setPOV(DriverStation.POVDirection value) {
public void setPOV(POVDirection value) {
setPOV(0, value);
}

View File

@@ -20,7 +20,11 @@ import org.wpilib.datalog.DataLogBackgroundWriter;
import org.wpilib.datalog.FileLogger;
import org.wpilib.datalog.IntegerLogEntry;
import org.wpilib.datalog.StringLogEntry;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.driverstation.DriverStationErrors;
import org.wpilib.driverstation.MatchState;
import org.wpilib.driverstation.MatchType;
import org.wpilib.driverstation.RobotState;
import org.wpilib.driverstation.internal.DriverStationBackend;
import org.wpilib.framework.RobotBase;
import org.wpilib.hardware.hal.HAL;
import org.wpilib.networktables.NetworkTableInstance;
@@ -326,7 +330,7 @@ public final class DataLogManager {
}
long length = file.length();
if (file.delete()) {
DriverStation.reportWarning("DataLogManager: Deleted " + file.getName(), false);
DriverStationErrors.reportWarning("DataLogManager: Deleted " + file.getName(), false);
freeSpace += length;
if (freeSpace >= FREE_SPACE_THRESHOLD) {
break;
@@ -337,7 +341,7 @@ public final class DataLogManager {
}
}
} else if (freeSpace < 2 * FREE_SPACE_THRESHOLD) {
DriverStation.reportWarning(
DriverStationErrors.reportWarning(
"DataLogManager: Log storage device has "
+ freeSpace / 1000000
+ " MB of free space remaining! Logs will get deleted below "
@@ -360,7 +364,7 @@ public final class DataLogManager {
m_log, "systemTime", "{\"source\":\"DataLogManager\",\"format\":\"time_t_us\"}");
Event newDataEvent = new Event();
DriverStation.provideRefreshedDataEventHandle(newDataEvent.getHandle());
DriverStationBackend.provideRefreshedDataEventHandle(newDataEvent.getHandle());
while (!Thread.interrupted()) {
boolean timedOut;
try {
@@ -390,7 +394,7 @@ public final class DataLogManager {
if (!dsRenamed) {
// track DS attach
if (DriverStation.isDSAttached()) {
if (RobotState.isDSAttached()) {
dsAttachCount++;
} else {
dsAttachCount = 0;
@@ -408,7 +412,7 @@ public final class DataLogManager {
if (!fmsRenamed) {
// track FMS attach
if (DriverStation.isFMSAttached()) {
if (RobotState.isFMSAttached()) {
fmsAttachCount++;
} else {
fmsAttachCount = 0;
@@ -416,8 +420,8 @@ public final class DataLogManager {
if (fmsAttachCount > 250) { // 5 seconds
// match info comes through TCP, so we need to double-check we've
// actually received it
DriverStation.MatchType matchType = DriverStation.getMatchType();
if (matchType != DriverStation.MatchType.NONE) {
MatchType matchType = MatchState.getMatchType();
if (matchType != MatchType.NONE) {
// rename per match info
char matchTypeChar =
switch (matchType) {
@@ -430,10 +434,10 @@ public final class DataLogManager {
"WPILIB_"
+ m_timeFormatter.format(LocalDateTime.now(m_utc))
+ "_"
+ DriverStation.getEventName()
+ MatchState.getEventName()
+ "_"
+ matchTypeChar
+ DriverStation.getMatchNumber()
+ MatchState.getMatchNumber()
+ ".wpilog");
fmsRenamed = true;
dsRenamed = true; // don't override FMS rename

View File

@@ -9,7 +9,7 @@ import static org.wpilib.util.ErrorMessages.requireNonNullParam;
import java.util.concurrent.atomic.AtomicInteger;
import java.util.concurrent.locks.ReentrantLock;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.driverstation.DriverStationErrors;
import org.wpilib.hardware.hal.NotifierJNI;
import org.wpilib.units.measure.Frequency;
import org.wpilib.units.measure.Time;
@@ -106,9 +106,9 @@ public class Notifier implements AutoCloseable {
if (cause != null) {
error = cause;
}
DriverStation.reportError(
DriverStationErrors.reportError(
"Unhandled exception in Notifier thread: " + error, error.getStackTrace());
DriverStation.reportError(
DriverStationErrors.reportError(
"The Runnable for this Notifier (or methods called by it) should have handled "
+ "the exception above.\n"
+ " The above stacktrace can help determine where the error occurred.\n"

View File

@@ -6,7 +6,7 @@ package org.wpilib.system;
import static org.wpilib.units.Units.Seconds;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.driverstation.MatchState;
import org.wpilib.units.measure.Time;
/**
@@ -54,7 +54,7 @@ public class Timer {
* @return Time remaining in current match period (auto or teleop) in seconds
*/
public static double getMatchTime() {
return DriverStation.getMatchTime();
return MatchState.getMatchTime();
}
/**

View File

@@ -7,7 +7,7 @@ package org.wpilib.system;
import java.util.HashMap;
import java.util.Map;
import java.util.function.Consumer;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.driverstation.DriverStationErrors;
/**
* A class for keeping track of how much time it takes for different parts of code to execute. This
@@ -60,7 +60,7 @@ public class Tracer {
/** Prints list of epochs added so far and their times to the DriverStation. */
public void printEpochs() {
printEpochs(out -> DriverStation.reportWarning(out, false));
printEpochs(out -> DriverStationErrors.reportWarning(out, false));
}
/**

View File

@@ -9,7 +9,7 @@ import static org.wpilib.units.Units.Seconds;
import java.io.Closeable;
import java.util.PriorityQueue;
import java.util.concurrent.locks.ReentrantLock;
import org.wpilib.driverstation.DriverStation;
import org.wpilib.driverstation.DriverStationErrors;
import org.wpilib.hardware.hal.HALUtil;
import org.wpilib.hardware.hal.NotifierJNI;
import org.wpilib.units.measure.Time;
@@ -263,7 +263,7 @@ public class Watchdog implements Closeable, Comparable<Watchdog> {
if (now - watchdog.m_lastTimeoutPrint > MIN_PRINT_PERIOD) {
watchdog.m_lastTimeoutPrint = now;
if (!watchdog.m_suppressTimeoutMessage) {
DriverStation.reportWarning(
DriverStationErrors.reportWarning(
String.format("Watchdog not fed within %.6fs\n", watchdog.m_timeout), false);
}
}