Package edu.wpi.first.wpilibj
Class DriverStation
- java.lang.Object
-
- edu.wpi.first.wpilibj.DriverStation
-
public class DriverStation extends Object
Provide access to the network communication data to / from the Driver Station.
-
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static classDriverStation.AllianceThe robot alliance that the robot is a part of.static classDriverStation.MatchType
-
Field Summary
Fields Modifier and Type Field Description static intkJoystickPortsNumber of Joystick Ports.
-
Method Summary
All Methods Static Methods Instance Methods Concrete Methods Modifier and Type Method Description DriverStation.AlliancegetAlliance()Get the current alliance from the FMS.protected voidgetData()Copy data from the DS task for the user.StringgetEventName()Get the event name.StringgetGameSpecificMessage()Get the game specific message.static DriverStationgetInstance()Gets an instance of the DriverStation.intgetJoystickAxisType(int stick, int axis)Returns the types of Axes on a given joystick port.booleangetJoystickIsXbox(int stick)Gets the value of isXbox on a joystick.StringgetJoystickName(int stick)Gets the name of the joystick at a port.intgetJoystickType(int stick)Gets the value of type on a joystick.intgetLocation()Gets the location of the team's driver station controls.intgetMatchNumber()Get the match number.doublegetMatchTime()Return the approximate match time.DriverStation.MatchTypegetMatchType()Get the match type.intgetReplayNumber()Get the replay number.doublegetStickAxis(int stick, int axis)Get the value of the axis on a joystick.intgetStickAxisCount(int stick)Returns the number of axes on a given joystick port.booleangetStickButton(int stick, int button)The state of one joystick button.intgetStickButtonCount(int stick)Gets the number of buttons on a joystick.intgetStickButtons(int stick)The state of the buttons on the joystick.intgetStickPOV(int stick, int pov)Get the state of a POV on the joystick.intgetStickPOVCount(int stick)Returns the number of POVs on a given joystick port.voidInAutonomous(boolean entering)Only to be used to tell the Driver Station what code you claim to be executing for diagnostic purposes only.voidInDisabled(boolean entering)Only to be used to tell the Driver Station what code you claim to be executing for diagnostic purposes only.voidInOperatorControl(boolean entering)Only to be used to tell the Driver Station what code you claim to be executing for diagnostic purposes only.voidInTest(boolean entering)Only to be used to tell the Driver Station what code you claim to be executing for diagnostic purposes only.booleanisAutonomous()Gets a value indicating whether the Driver Station requires the robot to be running in autonomous mode.booleanisDisabled()Gets a value indicating whether the Driver Station requires the robot to be disabled.booleanisDSAttached()Gets a value indicating whether the Driver Station is attached.booleanisEnabled()Gets a value indicating whether the Driver Station requires the robot to be enabled.booleanisEStopped()Gets a value indicating whether the Robot is e-stopped.booleanisFMSAttached()Gets if the driver station attached to a Field Management System.booleanisNewControlData()Gets if a new control packet from the driver station arrived since the last time this function was called.booleanisOperatorControl()Gets a value indicating whether the Driver Station requires the robot to be running in operator-controlled mode.booleanisTest()Gets a value indicating whether the Driver Station requires the robot to be running in test mode.voidrelease()Kill the thread.static voidreportError(String error, boolean printTrace)Report error to Driver Station.static voidreportError(String error, StackTraceElement[] stackTrace)Report error to Driver Station.static voidreportWarning(String error, boolean printTrace)Report warning to Driver Station.static voidreportWarning(String error, StackTraceElement[] stackTrace)Report warning to Driver Station.voidwaitForData()Wait for new data from the driver station.booleanwaitForData(double timeout)Wait for new data or for timeout, which ever comes first.voidwakeupWaitForData()Forces waitForData() to return immediately.
-
-
-
Field Detail
-
kJoystickPorts
public static final int kJoystickPorts
Number of Joystick Ports.- See Also:
- Constant Field Values
-
-
Method Detail
-
getInstance
public static DriverStation getInstance()
Gets an instance of the DriverStation.- Returns:
- The DriverStation.
-
release
public void release()
Kill the thread.
-
reportError
public static void reportError(String error, boolean printTrace)
Report error to Driver Station. Optionally appends Stack trace to error message.- Parameters:
printTrace- If true, append stack trace to error string
-
reportError
public static void reportError(String error, StackTraceElement[] stackTrace)
Report error to Driver Station. Appends provided stack trace to error message.- Parameters:
stackTrace- The stack trace to append
-
reportWarning
public static void reportWarning(String error, boolean printTrace)
Report warning to Driver Station. Optionally appends Stack trace to warning message.- Parameters:
printTrace- If true, append stack trace to warning string
-
reportWarning
public static void reportWarning(String error, StackTraceElement[] stackTrace)
Report warning to Driver Station. Appends provided stack trace to warning message.- Parameters:
stackTrace- The stack trace to append
-
getStickButton
public boolean getStickButton(int stick, int button)The state of one joystick button. Button indexes begin at 1.- Parameters:
stick- The joystick to read.button- The button index, beginning at 1.- Returns:
- The state of the joystick button.
-
getStickAxis
public double getStickAxis(int stick, int axis)Get the value of the axis on a joystick. This depends on the mapping of the joystick connected to the specified port.- Parameters:
stick- The joystick to read.axis- The analog axis value to read from the joystick.- Returns:
- The value of the axis on the joystick.
-
getStickPOV
public int getStickPOV(int stick, int pov)Get the state of a POV on the joystick.- Returns:
- the angle of the POV in degrees, or -1 if the POV is not pressed.
-
getStickButtons
public int getStickButtons(int stick)
The state of the buttons on the joystick.- Parameters:
stick- The joystick to read.- Returns:
- The state of the buttons on the joystick.
-
getStickAxisCount
public int getStickAxisCount(int stick)
Returns the number of axes on a given joystick port.- Parameters:
stick- The joystick port number- Returns:
- The number of axes on the indicated joystick
-
getStickPOVCount
public int getStickPOVCount(int stick)
Returns the number of POVs on a given joystick port.- Parameters:
stick- The joystick port number- Returns:
- The number of POVs on the indicated joystick
-
getStickButtonCount
public int getStickButtonCount(int stick)
Gets the number of buttons on a joystick.- Parameters:
stick- The joystick port number- Returns:
- The number of buttons on the indicated joystick
-
getJoystickIsXbox
public boolean getJoystickIsXbox(int stick)
Gets the value of isXbox on a joystick.- Parameters:
stick- The joystick port number- Returns:
- A boolean that returns the value of isXbox
-
getJoystickType
public int getJoystickType(int stick)
Gets the value of type on a joystick.- Parameters:
stick- The joystick port number- Returns:
- The value of type
-
getJoystickName
public String getJoystickName(int stick)
Gets the name of the joystick at a port.- Parameters:
stick- The joystick port number- Returns:
- The value of name
-
getJoystickAxisType
public int getJoystickAxisType(int stick, int axis)Returns the types of Axes on a given joystick port.- Parameters:
stick- The joystick port numberaxis- The target axis- Returns:
- What type of axis the axis is reporting to be
-
isEnabled
public boolean isEnabled()
Gets a value indicating whether the Driver Station requires the robot to be enabled.- Returns:
- True if the robot is enabled, false otherwise.
-
isDisabled
public boolean isDisabled()
Gets a value indicating whether the Driver Station requires the robot to be disabled.- Returns:
- True if the robot should be disabled, false otherwise.
-
isEStopped
public boolean isEStopped()
Gets a value indicating whether the Robot is e-stopped.- Returns:
- True if the robot is e-stopped, false otherwise.
-
isAutonomous
public boolean isAutonomous()
Gets a value indicating whether the Driver Station requires the robot to be running in autonomous mode.- Returns:
- True if autonomous mode should be enabled, false otherwise.
-
isOperatorControl
public boolean isOperatorControl()
Gets a value indicating whether the Driver Station requires the robot to be running in operator-controlled mode.- Returns:
- True if operator-controlled mode should be enabled, false otherwise.
-
isTest
public boolean isTest()
Gets a value indicating whether the Driver Station requires the robot to be running in test mode.- Returns:
- True if test mode should be enabled, false otherwise.
-
isDSAttached
public boolean isDSAttached()
Gets a value indicating whether the Driver Station is attached.- Returns:
- True if Driver Station is attached, false otherwise.
-
isNewControlData
public boolean isNewControlData()
Gets if a new control packet from the driver station arrived since the last time this function was called.- Returns:
- True if the control data has been updated since the last call.
-
isFMSAttached
public boolean isFMSAttached()
Gets if the driver station attached to a Field Management System.- Returns:
- true if the robot is competing on a field being controlled by a Field Management System
-
getGameSpecificMessage
public String getGameSpecificMessage()
Get the game specific message.- Returns:
- the game specific message
-
getEventName
public String getEventName()
Get the event name.- Returns:
- the event name
-
getMatchType
public DriverStation.MatchType getMatchType()
Get the match type.- Returns:
- the match type
-
getMatchNumber
public int getMatchNumber()
Get the match number.- Returns:
- the match number
-
getReplayNumber
public int getReplayNumber()
Get the replay number.- Returns:
- the replay number
-
getAlliance
public DriverStation.Alliance getAlliance()
Get the current alliance from the FMS.- Returns:
- the current alliance
-
getLocation
public int getLocation()
Gets the location of the team's driver station controls.- Returns:
- the location of the team's driver station controls: 1, 2, or 3
-
waitForData
public void waitForData()
Wait for new data from the driver station.
-
waitForData
public boolean waitForData(double timeout)
Wait for new data or for timeout, which ever comes first. If timeout is 0, wait for new data only.- Parameters:
timeout- The maximum time in seconds to wait.- Returns:
- true if there is new data, otherwise false
-
getMatchTime
public double getMatchTime()
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) The Practice Match function of the DS approximates the behaviour seen on the field.- Returns:
- Time remaining in current match period (auto or teleop) in seconds
-
InDisabled
public void InDisabled(boolean entering)
Only to be used to tell the Driver Station what code you claim to be executing for diagnostic purposes only.- Parameters:
entering- If true, starting disabled code; if false, leaving disabled code
-
InAutonomous
public void InAutonomous(boolean entering)
Only to be used to tell the Driver Station what code you claim to be executing for diagnostic purposes only.- Parameters:
entering- If true, starting autonomous code; if false, leaving autonomous code
-
InOperatorControl
public void InOperatorControl(boolean entering)
Only to be used to tell the Driver Station what code you claim to be executing for diagnostic purposes only.- Parameters:
entering- If true, starting teleop code; if false, leaving teleop code
-
InTest
public void InTest(boolean entering)
Only to be used to tell the Driver Station what code you claim to be executing for diagnostic purposes only.- Parameters:
entering- If true, starting test code; if false, leaving test code
-
wakeupWaitForData
public void wakeupWaitForData()
Forces waitForData() to return immediately.
-
getData
protected void getData()
Copy data from the DS task for the user. If no new data exists, it will just be returned, otherwise the data will be copied from the DS polling loop.
-
-