diff --git a/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java b/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java
index 160d53db2a..379e9c78fc 100644
--- a/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java
@@ -4,8 +4,6 @@
package edu.wpi.first.hal;
-import java.nio.ByteBuffer;
-
/**
* Driver Station JNI Functions.
*
@@ -142,55 +140,18 @@ public class DriverStationJNI extends JNIWrapper {
/** The maximum number of axes. */
public static final int kMaxJoystickAxes = 12;
+ public static final int kMaxJoystickButtons = 64;
+
/** The maximum number of POVs. */
public static final int kMaxJoystickPOVs = 8;
/** The maximum number of joysticks. */
public static final int kMaxJoysticks = 6;
- /**
- * Gets the axes of a specific joystick.
- *
- * @param joystickNum the joystick number
- * @param axesArray the axes values
- * @return number of joystick axes, or 0 for error
- * @see "HAL_GetJoystickAxes"
- */
- public static native int getJoystickAxes(byte joystickNum, float[] axesArray);
-
- /**
- * Gets the axes of a specific joystick.
- *
- * @param joystickNum the joystick number
- * @param rawAxesArray the raw int axes values (-32767-32768)
- * @return number of joystick axes, or 0 for error
- * @see "HAL_GetJoystickAxes"
- */
- public static native int getJoystickAxesRaw(byte joystickNum, short[] rawAxesArray);
-
- /**
- * Gets the POVs of a specific joystick.
- *
- * @param joystickNum the joystick number
- * @param povsArray the POV values
- * @return number of POVs, or 0 for error
- * @see "HAL_GetJoystickPOVs"
- */
- public static native int getJoystickPOVs(byte joystickNum, byte[] povsArray);
-
- /**
- * Gets the buttons of a specific joystick.
- *
- * @param joystickNum the joystick number
- * @param count the count of buttons
- * @return The joystick button values
- * @see "HAL_GetJoystickButtons"
- */
- public static native int getJoystickButtons(byte joystickNum, ByteBuffer count);
-
/**
* Get all joystick data.
*
+ * @param stick the joystick to grab
* @param axesArray all joystick axes
* @param rawAxesArray all joystick axes as int
* @param povsArray all povs
@@ -199,7 +160,11 @@ public class DriverStationJNI extends JNIWrapper {
* @see "HAL_GetAllJoystickData"
*/
public static native void getAllJoystickData(
- float[] axesArray, short[] rawAxesArray, byte[] povsArray, long[] buttonsAndMetadata);
+ int stick,
+ float[] axesArray,
+ short[] rawAxesArray,
+ byte[] povsArray,
+ long[] buttonsAndMetadata);
/**
* Set joystick outputs.
@@ -246,19 +211,6 @@ public class DriverStationJNI extends JNIWrapper {
*/
public static native String getJoystickName(byte joystickNum);
- /**
- * Gets the type of a specific joystick axis.
- *
- *
This is device specific, and different depending on what system input type the joystick
- * uses.
- *
- * @param joystickNum the joystick number
- * @param axis the axis number
- * @return the enumerated axis type
- * @see "HAL_GetJoystickAxisType"
- */
- public static native int getJoystickAxisType(byte joystickNum, byte axis);
-
/**
* Returns the approximate match time.
*
diff --git a/hal/src/main/java/edu/wpi/first/hal/simulation/DriverStationDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/simulation/DriverStationDataJNI.java
index 311766e5ee..71e00d32f4 100644
--- a/hal/src/main/java/edu/wpi/first/hal/simulation/DriverStationDataJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/simulation/DriverStationDataJNI.java
@@ -77,11 +77,14 @@ public class DriverStationDataJNI extends JNIWrapper {
public static native void setMatchTime(double matchTime);
- public static native void setJoystickAxes(byte joystickNum, float[] axesArray);
+ public static native void setJoystickAxes(
+ byte joystickNum, float[] axesArray, short availableAxes);
- public static native void setJoystickPOVs(byte joystickNum, byte[] povsArray);
+ public static native void setJoystickPOVs(
+ byte joystickNum, byte[] povsArray, short availablePovs);
- public static native void setJoystickButtons(byte joystickNum, int buttons, int count);
+ public static native void setJoystickButtons(
+ byte joystickNum, long buttons, long availableButtons);
public static native long getJoystickOutputs(int stick);
@@ -108,13 +111,13 @@ public class DriverStationDataJNI extends JNIWrapper {
public static native void setJoystickPOV(int stick, int pov, byte value);
- public static native void setJoystickButtonsValue(int stick, int buttons);
+ public static native void setJoystickButtonsValue(int stick, long buttons);
- public static native void setJoystickAxisCount(int stick, int count);
+ public static native void setJoystickAxesAvailable(int stick, int available);
- public static native void setJoystickPOVCount(int stick, int count);
+ public static native void setJoystickPOVsAvailable(int stick, int available);
- public static native void setJoystickButtonCount(int stick, int count);
+ public static native void setJoystickButtonsAvailable(int stick, long available);
public static native void setJoystickIsGamepad(int stick, boolean isGamepad);
@@ -122,8 +125,6 @@ public class DriverStationDataJNI extends JNIWrapper {
public static native void setJoystickName(int stick, String name);
- public static native void setJoystickAxisType(int stick, int axis, int type);
-
public static native void setGameSpecificMessage(String message);
public static native void setEventName(String name);
diff --git a/hal/src/main/native/cpp/jni/DriverStationJNI.cpp b/hal/src/main/native/cpp/jni/DriverStationJNI.cpp
index 5f735aba9b..dbbfde76fc 100644
--- a/hal/src/main/native/cpp/jni/DriverStationJNI.cpp
+++ b/hal/src/main/native/cpp/jni/DriverStationJNI.cpp
@@ -133,142 +133,39 @@ Java_edu_wpi_first_hal_DriverStationJNI_nativeGetAllianceStation
return static_cast(allianceStation);
}
-/*
- * Class: edu_wpi_first_hal_DriverStationJNI
- * Method: getJoystickAxesRaw
- * Signature: (B[S)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_DriverStationJNI_getJoystickAxesRaw
- (JNIEnv* env, jclass, jbyte joystickNum, jshortArray axesRawArray)
-{
- HAL_JoystickAxes axes;
- HAL_GetJoystickAxes(joystickNum, &axes);
-
- jsize javaSize = env->GetArrayLength(axesRawArray);
- if (axes.count > javaSize) {
- ThrowIllegalArgumentException(
- env,
- fmt::format("Native array size larger then passed in java array "
- "size\nNative Size: {} Java Size: {}",
- static_cast(axes.count), static_cast(javaSize)));
- return 0;
- }
-
- env->SetShortArrayRegion(axesRawArray, 0, axes.count, axes.raw);
-
- return axes.count;
-}
-
-/*
- * Class: edu_wpi_first_hal_DriverStationJNI
- * Method: getJoystickAxes
- * Signature: (B[F)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_DriverStationJNI_getJoystickAxes
- (JNIEnv* env, jclass, jbyte joystickNum, jfloatArray axesArray)
-{
- HAL_JoystickAxes axes;
- HAL_GetJoystickAxes(joystickNum, &axes);
-
- jsize javaSize = env->GetArrayLength(axesArray);
- if (axes.count > javaSize) {
- ThrowIllegalArgumentException(
- env,
- fmt::format("Native array size larger then passed in java array "
- "size\nNative Size: {} Java Size: {}",
- static_cast(axes.count), static_cast(javaSize)));
- return 0;
- }
-
- env->SetFloatArrayRegion(axesArray, 0, axes.count, axes.axes);
-
- return axes.count;
-}
-
-/*
- * Class: edu_wpi_first_hal_DriverStationJNI
- * Method: getJoystickPOVs
- * Signature: (B[B)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_DriverStationJNI_getJoystickPOVs
- (JNIEnv* env, jclass, jbyte joystickNum, jbyteArray povsArray)
-{
- HAL_JoystickPOVs povs;
- HAL_GetJoystickPOVs(joystickNum, &povs);
-
- jsize javaSize = env->GetArrayLength(povsArray);
- if (povs.count > javaSize) {
- ThrowIllegalArgumentException(
- env,
- fmt::format("Native array size larger then passed in java array "
- "size\nNative Size: {} Java Size: {}",
- static_cast(povs.count), static_cast(javaSize)));
- return 0;
- }
-
- env->SetByteArrayRegion(povsArray, 0, povs.count,
- reinterpret_cast(povs.povs));
-
- return povs.count;
-}
-
/*
* Class: edu_wpi_first_hal_DriverStationJNI
* Method: getAllJoystickData
- * Signature: ([F[S[B[J)V
+ * Signature: (I[F[S[B[J)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_hal_DriverStationJNI_getAllJoystickData
- (JNIEnv* env, jclass cls, jfloatArray axesArray, jshortArray rawAxesArray,
- jbyteArray povsArray, jlongArray buttonsAndMetadataArray)
+ (JNIEnv* env, jclass cls, jint stick, jfloatArray axesArray,
+ jshortArray rawAxesArray, jbyteArray povsArray,
+ jlongArray buttonsAndMetadataArray)
{
- HAL_JoystickAxes axes[HAL_kMaxJoysticks];
- HAL_JoystickPOVs povs[HAL_kMaxJoysticks];
- HAL_JoystickButtons buttons[HAL_kMaxJoysticks];
+ HAL_JoystickAxes axes;
+ HAL_JoystickPOVs povs;
+ HAL_JoystickButtons buttons;
- HAL_GetAllJoystickData(axes, povs, buttons);
+ HAL_GetAllJoystickData(stick, &axes, &povs, &buttons);
CriticalJSpan jAxes(env, axesArray);
CriticalJSpan jRawAxes(env, rawAxesArray);
CriticalJSpan jPovs(env, povsArray);
CriticalJSpan jButtons(env, buttonsAndMetadataArray);
- static_assert(sizeof(jAxes[0]) == sizeof(axes[0].axes[0]));
- static_assert(sizeof(jRawAxes[0]) == sizeof(axes[0].raw[0]));
- static_assert(sizeof(jPovs[0]) == sizeof(povs[0].povs[0]));
+ static_assert(sizeof(jAxes[0]) == sizeof(axes.axes[0]));
+ static_assert(sizeof(jRawAxes[0]) == sizeof(axes.raw[0]));
+ static_assert(sizeof(jPovs[0]) == sizeof(povs.povs[0]));
- for (size_t i = 0; i < HAL_kMaxJoysticks; i++) {
- std::memcpy(&jAxes[i * HAL_kMaxJoystickAxes], axes[i].axes,
- sizeof(axes[i].axes));
- std::memcpy(&jRawAxes[i * HAL_kMaxJoystickAxes], axes[i].raw,
- sizeof(axes[i].raw));
- std::memcpy(&jPovs[i * HAL_kMaxJoystickPOVs], povs[i].povs,
- sizeof(povs[i].povs));
- jButtons[i * 4] = axes[i].count;
- jButtons[(i * 4) + 1] = povs[i].count;
- jButtons[(i * 4) + 2] = buttons[i].count;
- jButtons[(i * 4) + 3] = buttons[i].buttons;
- }
-}
-
-/*
- * Class: edu_wpi_first_hal_DriverStationJNI
- * Method: getJoystickButtons
- * Signature: (BLjava/lang/Object;)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_DriverStationJNI_getJoystickButtons
- (JNIEnv* env, jclass, jbyte joystickNum, jobject count)
-{
- HAL_JoystickButtons joystickButtons;
- HAL_GetJoystickButtons(joystickNum, &joystickButtons);
- jbyte* countPtr =
- reinterpret_cast(env->GetDirectBufferAddress(count));
- *countPtr = joystickButtons.count;
- return joystickButtons.buttons;
+ std::memcpy(&jAxes[0], axes.axes, sizeof(axes.axes));
+ std::memcpy(&jRawAxes[0], axes.raw, sizeof(axes.raw));
+ std::memcpy(&jPovs[0], povs.povs, sizeof(povs.povs));
+ jButtons[0] = axes.available;
+ jButtons[1] = povs.available;
+ jButtons[2] = buttons.available;
+ jButtons[3] = buttons.buttons;
}
/*
@@ -323,18 +220,6 @@ Java_edu_wpi_first_hal_DriverStationJNI_getJoystickName
return str;
}
-/*
- * Class: edu_wpi_first_hal_DriverStationJNI
- * Method: getJoystickAxisType
- * Signature: (BB)I
- */
-JNIEXPORT jint JNICALL
-Java_edu_wpi_first_hal_DriverStationJNI_getJoystickAxisType
- (JNIEnv*, jclass, jbyte joystickNum, jbyte axis)
-{
- return HAL_GetJoystickAxisType(joystickNum, axis);
-}
-
/*
* Class: edu_wpi_first_hal_DriverStationJNI
* Method: getMatchTime
diff --git a/hal/src/main/native/cpp/jni/simulation/DriverStationDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/DriverStationDataJNI.cpp
index 82edd55482..0db407f316 100644
--- a/hal/src/main/native/cpp/jni/simulation/DriverStationDataJNI.cpp
+++ b/hal/src/main/native/cpp/jni/simulation/DriverStationDataJNI.cpp
@@ -427,11 +427,12 @@ Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setMatchTime
/*
* Class: edu_wpi_first_hal_simulation_DriverStationDataJNI
* Method: setJoystickAxes
- * Signature: (B[F)V
+ * Signature: (B[FS)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickAxes
- (JNIEnv* env, jclass, jbyte joystickNum, jfloatArray axesArray)
+ (JNIEnv* env, jclass, jbyte joystickNum, jfloatArray axesArray,
+ jshort availableAxes)
{
HAL_JoystickAxes axes;
{
@@ -440,7 +441,7 @@ Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickAxes
auto arraySize = arrayRef.size();
int maxCount =
arraySize < HAL_kMaxJoystickAxes ? arraySize : HAL_kMaxJoystickAxes;
- axes.count = maxCount;
+ axes.available = availableAxes;
for (int i = 0; i < maxCount; i++) {
axes.axes[i] = arrayRef[i];
}
@@ -452,11 +453,12 @@ Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickAxes
/*
* Class: edu_wpi_first_hal_simulation_DriverStationDataJNI
* Method: setJoystickPOVs
- * Signature: (B[B)V
+ * Signature: (B[BS)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickPOVs
- (JNIEnv* env, jclass, jbyte joystickNum, jbyteArray povsArray)
+ (JNIEnv* env, jclass, jbyte joystickNum, jbyteArray povsArray,
+ jshort availablePovs)
{
HAL_JoystickPOVs povs;
{
@@ -465,7 +467,7 @@ Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickPOVs
auto arraySize = arrayRef.size();
int maxCount =
arraySize < HAL_kMaxJoystickPOVs ? arraySize : HAL_kMaxJoystickPOVs;
- povs.count = maxCount;
+ povs.available = availablePovs;
for (int i = 0; i < maxCount; i++) {
povs.povs[i] = static_cast(arrayRef[i]);
}
@@ -477,17 +479,15 @@ Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickPOVs
/*
* Class: edu_wpi_first_hal_simulation_DriverStationDataJNI
* Method: setJoystickButtons
- * Signature: (BII)V
+ * Signature: (BJJ)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickButtons
- (JNIEnv* env, jclass, jbyte joystickNum, jint buttons, jint count)
+ (JNIEnv* env, jclass, jbyte joystickNum, jlong buttons,
+ jlong availableButtons)
{
- if (count > 32) {
- count = 32;
- }
HAL_JoystickButtons joystickButtons;
- joystickButtons.count = count;
+ joystickButtons.available = availableButtons;
joystickButtons.buttons = buttons;
HALSIM_SetJoystickButtons(joystickNum, &joystickButtons);
}
@@ -654,49 +654,49 @@ Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickPOV
/*
* Class: edu_wpi_first_hal_simulation_DriverStationDataJNI
* Method: setJoystickButtonsValue
- * Signature: (II)V
+ * Signature: (IJ)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickButtonsValue
- (JNIEnv*, jclass, jint stick, jint buttons)
+ (JNIEnv*, jclass, jint stick, jlong buttons)
{
HALSIM_SetJoystickButtonsValue(stick, buttons);
}
/*
* Class: edu_wpi_first_hal_simulation_DriverStationDataJNI
- * Method: setJoystickAxisCount
+ * Method: setJoystickAxesAvailable
* Signature: (II)V
*/
JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickAxisCount
- (JNIEnv*, jclass, jint stick, jint count)
+Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickAxesAvailable
+ (JNIEnv*, jclass, jint stick, jint available)
{
- HALSIM_SetJoystickAxisCount(stick, count);
+ HALSIM_SetJoystickAxesAvailable(stick, available);
}
/*
* Class: edu_wpi_first_hal_simulation_DriverStationDataJNI
- * Method: setJoystickPOVCount
+ * Method: setJoystickPOVsAvailable
* Signature: (II)V
*/
JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickPOVCount
- (JNIEnv*, jclass, jint stick, jint count)
+Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickPOVsAvailable
+ (JNIEnv*, jclass, jint stick, jint available)
{
- HALSIM_SetJoystickPOVCount(stick, count);
+ HALSIM_SetJoystickPOVsAvailable(stick, available);
}
/*
* Class: edu_wpi_first_hal_simulation_DriverStationDataJNI
- * Method: setJoystickButtonCount
- * Signature: (II)V
+ * Method: setJoystickButtonsAvailable
+ * Signature: (IJ)V
*/
JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickButtonCount
- (JNIEnv*, jclass, jint stick, jint count)
+Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickButtonsAvailable
+ (JNIEnv*, jclass, jint stick, jlong available)
{
- HALSIM_SetJoystickButtonCount(stick, count);
+ HALSIM_SetJoystickButtonsAvailable(stick, available);
}
/*
@@ -737,18 +737,6 @@ Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickName
HALSIM_SetJoystickName(stick, &str);
}
-/*
- * Class: edu_wpi_first_hal_simulation_DriverStationDataJNI
- * Method: setJoystickAxisType
- * Signature: (III)V
- */
-JNIEXPORT void JNICALL
-Java_edu_wpi_first_hal_simulation_DriverStationDataJNI_setJoystickAxisType
- (JNIEnv*, jclass, jint stick, jint axis, jint type)
-{
- HALSIM_SetJoystickAxisType(stick, axis, type);
-}
-
/*
* Class: edu_wpi_first_hal_simulation_DriverStationDataJNI
* Method: setGameSpecificMessage
diff --git a/hal/src/main/native/include/hal/DriverStation.h b/hal/src/main/native/include/hal/DriverStation.h
index 4e2ab48752..533871f87c 100644
--- a/hal/src/main/native/include/hal/DriverStation.h
+++ b/hal/src/main/native/include/hal/DriverStation.h
@@ -102,7 +102,8 @@ int32_t HAL_GetJoystickPOVs(int32_t joystickNum, HAL_JoystickPOVs* povs);
int32_t HAL_GetJoystickButtons(int32_t joystickNum,
HAL_JoystickButtons* buttons);
-void HAL_GetAllJoystickData(HAL_JoystickAxes* axes, HAL_JoystickPOVs* povs,
+void HAL_GetAllJoystickData(int32_t joystickNum, HAL_JoystickAxes* axes,
+ HAL_JoystickPOVs* povs,
HAL_JoystickButtons* buttons);
/**
@@ -150,18 +151,6 @@ int32_t HAL_GetJoystickType(int32_t joystickNum);
*/
void HAL_GetJoystickName(struct WPI_String* name, int32_t joystickNum);
-/**
- * Gets the type of a specific joystick axis.
- *
- * This is device specific, and different depending on what system input type
- * the joystick uses.
- *
- * @param joystickNum the joystick number
- * @param axis the axis number
- * @return the enumerated axis type
- */
-int32_t HAL_GetJoystickAxisType(int32_t joystickNum, int32_t axis);
-
/**
* Set joystick outputs.
*
diff --git a/hal/src/main/native/include/hal/DriverStationTypes.h b/hal/src/main/native/include/hal/DriverStationTypes.h
index 871f0afbc5..095f8cb155 100644
--- a/hal/src/main/native/include/hal/DriverStationTypes.h
+++ b/hal/src/main/native/include/hal/DriverStationTypes.h
@@ -21,7 +21,8 @@ struct HAL_ControlWord {
uint32_t eStop : 1;
uint32_t fmsAttached : 1;
uint32_t dsAttached : 1;
- uint32_t control_reserved : 26;
+ uint32_t watchdogEnabled : 1;
+ uint32_t control_reserved : 25;
};
typedef struct HAL_ControlWord HAL_ControlWord;
@@ -67,7 +68,7 @@ HAL_ENUM(HAL_MatchType) {
#define HAL_kMaxJoysticks 6
struct HAL_JoystickAxes {
- int16_t count;
+ uint16_t available;
float axes[HAL_kMaxJoystickAxes];
int16_t raw[HAL_kMaxJoystickAxes];
};
@@ -95,14 +96,14 @@ HAL_ENUM_WITH_UNDERLYING_TYPE(HAL_JoystickPOV, uint8_t){
};
struct HAL_JoystickPOVs {
- int16_t count;
+ uint8_t available;
HAL_JoystickPOV povs[HAL_kMaxJoystickPOVs];
};
typedef struct HAL_JoystickPOVs HAL_JoystickPOVs;
struct HAL_JoystickButtons {
- uint32_t buttons;
- uint8_t count;
+ uint64_t buttons;
+ uint64_t available;
};
typedef struct HAL_JoystickButtons HAL_JoystickButtons;
@@ -110,10 +111,6 @@ struct HAL_JoystickDescriptor {
uint8_t isGamepad;
uint8_t type;
char name[256];
- uint8_t axisCount;
- uint8_t axisTypes[HAL_kMaxJoystickAxes];
- uint8_t buttonCount;
- uint8_t povCount;
};
typedef struct HAL_JoystickDescriptor HAL_JoystickDescriptor;
diff --git a/hal/src/main/native/include/hal/simulation/DriverStationData.h b/hal/src/main/native/include/hal/simulation/DriverStationData.h
index 404ba19623..20c26d498b 100644
--- a/hal/src/main/native/include/hal/simulation/DriverStationData.h
+++ b/hal/src/main/native/include/hal/simulation/DriverStationData.h
@@ -140,17 +140,17 @@ void HALSIM_SetMatchInfo(const HAL_MatchInfo* info);
void HALSIM_SetJoystickButton(int32_t stick, int32_t button, HAL_Bool state);
void HALSIM_SetJoystickAxis(int32_t stick, int32_t axis, double value);
void HALSIM_SetJoystickPOV(int32_t stick, int32_t pov, HAL_JoystickPOV value);
-void HALSIM_SetJoystickButtonsValue(int32_t stick, uint32_t buttons);
-void HALSIM_SetJoystickAxisCount(int32_t stick, int32_t count);
-void HALSIM_SetJoystickPOVCount(int32_t stick, int32_t count);
-void HALSIM_SetJoystickButtonCount(int32_t stick, int32_t count);
-void HALSIM_GetJoystickCounts(int32_t stick, int32_t* axisCount,
- int32_t* buttonCount, int32_t* povCount);
+void HALSIM_SetJoystickButtonsValue(int32_t stick, uint64_t buttons);
+void HALSIM_SetJoystickAxesAvailable(int32_t stick, uint16_t available);
+void HALSIM_SetJoystickPOVsAvailable(int32_t stick, uint8_t available);
+void HALSIM_SetJoystickButtonsAvailable(int32_t stick, uint64_t available);
+void HALSIM_GetJoystickAvailables(int32_t stick, uint16_t* axesAvailable,
+ uint64_t* buttonsAvailable,
+ uint8_t* povsAvailable);
void HALSIM_SetJoystickIsGamepad(int32_t stick, HAL_Bool isGamepad);
void HALSIM_SetJoystickType(int32_t stick, int32_t type);
void HALSIM_SetJoystickName(int32_t stick, const struct WPI_String* name);
-void HALSIM_SetJoystickAxisType(int32_t stick, int32_t axis, int32_t type);
void HALSIM_SetGameSpecificMessage(const struct WPI_String* message);
void HALSIM_SetEventName(const struct WPI_String* name);
diff --git a/hal/src/main/native/sim/DriverStation.cpp b/hal/src/main/native/sim/DriverStation.cpp
index 89a5e3a8f4..2fc942087e 100644
--- a/hal/src/main/native/sim/DriverStation.cpp
+++ b/hal/src/main/native/sim/DriverStation.cpp
@@ -266,15 +266,16 @@ int32_t HAL_GetJoystickButtons(int32_t joystickNum,
return 0;
}
-void HAL_GetAllJoystickData(HAL_JoystickAxes* axes, HAL_JoystickPOVs* povs,
+void HAL_GetAllJoystickData(int32_t joystickNum, HAL_JoystickAxes* axes,
+ HAL_JoystickPOVs* povs,
HAL_JoystickButtons* buttons) {
if (gShutdown) {
return;
}
std::scoped_lock lock{driverStation->cacheMutex};
- std::memcpy(axes, currentRead->axes, sizeof(currentRead->axes));
- std::memcpy(povs, currentRead->povs, sizeof(currentRead->povs));
- std::memcpy(buttons, currentRead->buttons, sizeof(currentRead->buttons));
+ *axes = currentRead->axes[joystickNum];
+ *povs = currentRead->povs[joystickNum];
+ *buttons = currentRead->buttons[joystickNum];
}
int32_t HAL_GetJoystickDescriptor(int32_t joystickNum,
@@ -314,15 +315,6 @@ void HAL_GetJoystickName(struct WPI_String* name, int32_t joystickNum) {
std::memcpy(write, cName, len);
}
-int32_t HAL_GetJoystickAxisType(int32_t joystickNum, int32_t axis) {
- HAL_JoystickDescriptor joystickDesc;
- if (HAL_GetJoystickDescriptor(joystickNum, &joystickDesc) < 0) {
- return -1;
- } else {
- return joystickDesc.axisTypes[axis];
- }
-}
-
int32_t HAL_SetJoystickOutputs(int32_t joystickNum, int64_t outputs,
int32_t leftRumble, int32_t rightRumble) {
SimDriverStationData->SetJoystickOutputs(joystickNum, outputs, leftRumble,
diff --git a/hal/src/main/native/sim/mockdata/DriverStationData.cpp b/hal/src/main/native/sim/mockdata/DriverStationData.cpp
index 5dcd669934..e508d05f51 100644
--- a/hal/src/main/native/sim/mockdata/DriverStationData.cpp
+++ b/hal/src/main/native/sim/mockdata/DriverStationData.cpp
@@ -230,9 +230,9 @@ void DriverStationData::SetJoystickButton(int32_t stick, int32_t button,
}
std::scoped_lock lock(m_joystickDataMutex);
if (state) {
- m_joystickData[stick].buttons.buttons |= 1 << (button - 1);
+ m_joystickData[stick].buttons.buttons |= 1llu << button;
} else {
- m_joystickData[stick].buttons.buttons &= ~(1 << (button - 1));
+ m_joystickData[stick].buttons.buttons &= ~(1llu << button);
}
m_joystickButtonsCallbacks(stick, &m_joystickData[stick].buttons);
}
@@ -263,7 +263,7 @@ void DriverStationData::SetJoystickPOV(int32_t stick, int32_t pov,
m_joystickPOVsCallbacks(stick, &m_joystickData[stick].povs);
}
-void DriverStationData::SetJoystickButtons(int32_t stick, uint32_t buttons) {
+void DriverStationData::SetJoystickButtons(int32_t stick, uint64_t buttons) {
if (stick < 0 || stick >= kNumJoysticks) {
return;
}
@@ -272,52 +272,50 @@ void DriverStationData::SetJoystickButtons(int32_t stick, uint32_t buttons) {
m_joystickButtonsCallbacks(stick, &m_joystickData[stick].buttons);
}
-void DriverStationData::SetJoystickAxisCount(int32_t stick, int32_t count) {
+void DriverStationData::SetJoystickAxesAvailable(int32_t stick,
+ uint16_t available) {
if (stick < 0 || stick >= kNumJoysticks) {
return;
}
std::scoped_lock lock(m_joystickDataMutex);
- m_joystickData[stick].axes.count = count;
- m_joystickData[stick].descriptor.axisCount = count;
+ m_joystickData[stick].axes.available = available;
m_joystickAxesCallbacks(stick, &m_joystickData[stick].axes);
- m_joystickDescriptorCallbacks(stick, &m_joystickData[stick].descriptor);
}
-void DriverStationData::SetJoystickPOVCount(int32_t stick, int32_t count) {
+void DriverStationData::SetJoystickPOVsAvailable(int32_t stick,
+ uint8_t available) {
if (stick < 0 || stick >= kNumJoysticks) {
return;
}
std::scoped_lock lock(m_joystickDataMutex);
- m_joystickData[stick].povs.count = count;
- m_joystickData[stick].descriptor.povCount = count;
+ m_joystickData[stick].povs.available = available;
m_joystickPOVsCallbacks(stick, &m_joystickData[stick].povs);
- m_joystickDescriptorCallbacks(stick, &m_joystickData[stick].descriptor);
}
-void DriverStationData::SetJoystickButtonCount(int32_t stick, int32_t count) {
+void DriverStationData::SetJoystickButtonsAvailable(int32_t stick,
+ uint64_t available) {
if (stick < 0 || stick >= kNumJoysticks) {
return;
}
std::scoped_lock lock(m_joystickDataMutex);
- m_joystickData[stick].buttons.count = count;
- m_joystickData[stick].descriptor.buttonCount = count;
+ m_joystickData[stick].buttons.available = available;
m_joystickButtonsCallbacks(stick, &m_joystickData[stick].buttons);
- m_joystickDescriptorCallbacks(stick, &m_joystickData[stick].descriptor);
}
-void DriverStationData::GetJoystickCounts(int32_t stick, int32_t* axisCount,
- int32_t* buttonCount,
- int32_t* povCount) {
+void DriverStationData::GetJoystickAvailables(int32_t stick,
+ uint16_t* axesAvailable,
+ uint64_t* buttonsAvailable,
+ uint8_t* povsAvailable) {
if (stick < 0 || stick >= kNumJoysticks) {
- *axisCount = 0;
- *buttonCount = 0;
- *povCount = 0;
+ *axesAvailable = 0;
+ *buttonsAvailable = 0;
+ *povsAvailable = 0;
return;
}
std::scoped_lock lock(m_joystickDataMutex);
- *axisCount = m_joystickData[stick].axes.count;
- *buttonCount = m_joystickData[stick].buttons.count;
- *povCount = m_joystickData[stick].povs.count;
+ *axesAvailable = m_joystickData[stick].axes.available;
+ *buttonsAvailable = m_joystickData[stick].buttons.available;
+ *povsAvailable = m_joystickData[stick].povs.available;
}
void DriverStationData::SetJoystickIsGamepad(int32_t stick,
@@ -350,19 +348,6 @@ void DriverStationData::SetJoystickName(int32_t stick, std::string_view name) {
m_joystickDescriptorCallbacks(stick, &m_joystickData[stick].descriptor);
}
-void DriverStationData::SetJoystickAxisType(int32_t stick, int32_t axis,
- int32_t type) {
- if (stick < 0 || stick >= kNumJoysticks) {
- return;
- }
- if (axis < 0 || axis >= HAL_kMaxJoystickAxes) {
- return;
- }
- std::scoped_lock lock(m_joystickDataMutex);
- m_joystickData[stick].descriptor.axisTypes[axis] = type;
- m_joystickDescriptorCallbacks(stick, &m_joystickData[stick].descriptor);
-}
-
void DriverStationData::SetGameSpecificMessage(std::string_view message) {
std::scoped_lock lock(m_matchInfoMutex);
auto copied =
@@ -511,26 +496,27 @@ void HALSIM_SetJoystickPOV(int32_t stick, int32_t pov, HAL_JoystickPOV value) {
SimDriverStationData->SetJoystickPOV(stick, pov, value);
}
-void HALSIM_SetJoystickButtonsValue(int32_t stick, uint32_t buttons) {
+void HALSIM_SetJoystickButtonsValue(int32_t stick, uint64_t buttons) {
SimDriverStationData->SetJoystickButtons(stick, buttons);
}
-void HALSIM_SetJoystickAxisCount(int32_t stick, int32_t count) {
- SimDriverStationData->SetJoystickAxisCount(stick, count);
+void HALSIM_SetJoystickAxesAvailable(int32_t stick, uint16_t available) {
+ SimDriverStationData->SetJoystickAxesAvailable(stick, available);
}
-void HALSIM_SetJoystickPOVCount(int32_t stick, int32_t count) {
- SimDriverStationData->SetJoystickPOVCount(stick, count);
+void HALSIM_SetJoystickPOVsAvailable(int32_t stick, uint8_t available) {
+ SimDriverStationData->SetJoystickPOVsAvailable(stick, available);
}
-void HALSIM_SetJoystickButtonCount(int32_t stick, int32_t count) {
- SimDriverStationData->SetJoystickButtonCount(stick, count);
+void HALSIM_SetJoystickButtonsAvailable(int32_t stick, uint64_t available) {
+ SimDriverStationData->SetJoystickButtonsAvailable(stick, available);
}
-void HALSIM_GetJoystickCounts(int32_t stick, int32_t* axisCount,
- int32_t* buttonCount, int32_t* povCount) {
- SimDriverStationData->GetJoystickCounts(stick, axisCount, buttonCount,
- povCount);
+void HALSIM_GetJoystickAvailables(int32_t stick, uint16_t* axesAvailable,
+ uint64_t* buttonsAvailable,
+ uint8_t* povsAvailable) {
+ SimDriverStationData->GetJoystickAvailables(stick, axesAvailable,
+ buttonsAvailable, povsAvailable);
}
void HALSIM_SetJoystickIsGamepad(int32_t stick, HAL_Bool isGamepad) {
@@ -545,10 +531,6 @@ void HALSIM_SetJoystickName(int32_t stick, const WPI_String* name) {
SimDriverStationData->SetJoystickName(stick, wpi::to_string_view(name));
}
-void HALSIM_SetJoystickAxisType(int32_t stick, int32_t axis, int32_t type) {
- SimDriverStationData->SetJoystickAxisType(stick, axis, type);
-}
-
void HALSIM_SetGameSpecificMessage(const WPI_String* message) {
SimDriverStationData->SetGameSpecificMessage(wpi::to_string_view(message));
}
diff --git a/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h b/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h
index acf3ede705..62aeefd389 100644
--- a/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h
@@ -98,17 +98,17 @@ class DriverStationData {
void SetJoystickButton(int32_t stick, int32_t button, HAL_Bool state);
void SetJoystickAxis(int32_t stick, int32_t axis, double value);
void SetJoystickPOV(int32_t stick, int32_t pov, HAL_JoystickPOV value);
- void SetJoystickButtons(int32_t stick, uint32_t buttons);
- void SetJoystickAxisCount(int32_t stick, int32_t count);
- void SetJoystickPOVCount(int32_t stick, int32_t count);
- void SetJoystickButtonCount(int32_t stick, int32_t count);
- void GetJoystickCounts(int32_t stick, int32_t* axisCount,
- int32_t* buttonCount, int32_t* povCount);
+ void SetJoystickButtons(int32_t stick, uint64_t buttons);
+ void SetJoystickAxesAvailable(int32_t stick, uint16_t available);
+ void SetJoystickPOVsAvailable(int32_t stick, uint8_t available);
+ void SetJoystickButtonsAvailable(int32_t stick, uint64_t available);
+ void GetJoystickAvailables(int32_t stick, uint16_t* axesAvailable,
+ uint64_t* buttonsAvailable,
+ uint8_t* povsAvailable);
void SetJoystickIsGamepad(int32_t stick, HAL_Bool isGamepad);
void SetJoystickType(int32_t stick, int32_t type);
void SetJoystickName(int32_t stick, std::string_view message);
- void SetJoystickAxisType(int32_t stick, int32_t axis, int32_t type);
void SetGameSpecificMessage(std::string_view message);
void SetEventName(std::string_view name);
diff --git a/hal/src/main/native/systemcore/FRCDriverStation.cpp b/hal/src/main/native/systemcore/FRCDriverStation.cpp
index f7d59aa3c1..7e61725b19 100644
--- a/hal/src/main/native/systemcore/FRCDriverStation.cpp
+++ b/hal/src/main/native/systemcore/FRCDriverStation.cpp
@@ -256,7 +256,8 @@ void JoystickDataCache::Update(const mrc::ControlData& data) {
auto newAxes = newStick.Axes.Axes();
auto newPovs = newStick.Povs.Povs();
- axes[count].count = newAxes.size();
+ axes[count].available = newStick.Axes.GetAvailable();
+
for (size_t i = 0; i < newAxes.size(); i++) {
axes[count].raw[i] = newAxes[i];
int16_t axisValue = newAxes[i];
@@ -267,12 +268,13 @@ void JoystickDataCache::Update(const mrc::ControlData& data) {
}
}
- povs[count].count = newPovs.size();
+ // When mrccomm switches this to available, move to available
+ povs[count].available = (1lu << newPovs.size()) - 1;
for (size_t i = 0; i < newPovs.size(); i++) {
povs[count].povs[i] = static_cast(newPovs[i]);
}
- buttons[count].count = newStick.Buttons.GetMaxAvailableCount();
+ buttons[count].available = newStick.Buttons.GetAvailable();
buttons[count].buttons = newStick.Buttons.Buttons;
}
}
@@ -339,8 +341,6 @@ void TcpCache::Update() {
desc.isGamepad = newDesc.IsGamepad;
desc.type = newDesc.Type;
- desc.buttonCount = newDesc.GetButtonsCount();
- desc.povCount = newDesc.GetPovsCount();
auto joystickName = newDesc.GetName();
auto joystickNameLen =
@@ -350,14 +350,6 @@ void TcpCache::Update() {
std::memcpy(desc.name, joystickName.data(), joystickNameLen);
}
desc.name[joystickNameLen] = '\0';
-
- auto sticks = newDesc.AxesTypes();
-
- desc.axisCount = sticks.size();
-
- for (size_t i = 0; i < sticks.size(); i++) {
- desc.axisTypes[i] = sticks[i];
- }
}
}
@@ -490,12 +482,13 @@ int32_t HAL_GetJoystickButtons(int32_t joystickNum,
return 0;
}
-void HAL_GetAllJoystickData(HAL_JoystickAxes* axes, HAL_JoystickPOVs* povs,
+void HAL_GetAllJoystickData(int32_t joystickNum, HAL_JoystickAxes* axes,
+ HAL_JoystickPOVs* povs,
HAL_JoystickButtons* buttons) {
std::scoped_lock lock{cacheMutex};
- std::memcpy(axes, currentRead->axes, sizeof(currentRead->axes));
- std::memcpy(povs, currentRead->povs, sizeof(currentRead->povs));
- std::memcpy(buttons, currentRead->buttons, sizeof(currentRead->buttons));
+ *axes = currentRead->axes[joystickNum];
+ *povs = currentRead->povs[joystickNum];
+ *buttons = currentRead->buttons[joystickNum];
}
int32_t HAL_GetJoystickDescriptor(int32_t joystickNum,
@@ -546,15 +539,6 @@ void HAL_GetJoystickName(struct WPI_String* name, int32_t joystickNum) {
std::memcpy(write, cName, len);
}
-int32_t HAL_GetJoystickAxisType(int32_t joystickNum, int32_t axis) {
- HAL_JoystickDescriptor joystickDesc;
- if (HAL_GetJoystickDescriptor(joystickNum, &joystickDesc) < 0) {
- return -1;
- } else {
- return joystickDesc.axisTypes[axis];
- }
-}
-
int32_t HAL_SetJoystickOutputs(int32_t joystickNum, int64_t outputs,
int32_t leftRumble, int32_t rightRumble) {
CHECK_JOYSTICK_NUMBER(joystickNum);
diff --git a/hal/src/main/native/systemcore/mockdata/DriverStationData.cpp b/hal/src/main/native/systemcore/mockdata/DriverStationData.cpp
index 7d5fdadfa7..093e00e95d 100644
--- a/hal/src/main/native/systemcore/mockdata/DriverStationData.cpp
+++ b/hal/src/main/native/systemcore/mockdata/DriverStationData.cpp
@@ -84,19 +84,20 @@ void HALSIM_SetJoystickAxis(int32_t stick, int32_t axis, double value) {}
void HALSIM_SetJoystickPOV(int32_t stick, int32_t pov, HAL_JoystickPOV value) {}
-void HALSIM_SetJoystickButtonsValue(int32_t stick, uint32_t buttons) {}
+void HALSIM_SetJoystickButtonsValue(int32_t stick, uint64_t buttons) {}
-void HALSIM_SetJoystickAxisCount(int32_t stick, int32_t count) {}
+void HALSIM_SetJoystickAxesAvailable(int32_t stick, uint16_t available) {}
-void HALSIM_SetJoystickPOVCount(int32_t stick, int32_t count) {}
+void HALSIM_SetJoystickPOVsAvailable(int32_t stick, uint8_t available) {}
-void HALSIM_SetJoystickButtonCount(int32_t stick, int32_t count) {}
+void HALSIM_SetJoystickButtonsAvailable(int32_t stick, uint64_t available) {}
-void HALSIM_GetJoystickCounts(int32_t stick, int32_t* axisCount,
- int32_t* buttonCount, int32_t* povCount) {
- *axisCount = 0;
- *buttonCount = 0;
- *povCount = 0;
+void HALSIM_GetJoystickAvailables(int32_t stick, uint16_t* axesAvailable,
+ uint64_t* buttonsAvailable,
+ uint8_t* povsAvailable) {
+ *axesAvailable = 0;
+ *buttonsAvailable = 0;
+ *povsAvailable = 0;
}
void HALSIM_SetJoystickIsGamepad(int32_t stick, HAL_Bool isGamepad) {}
@@ -105,8 +106,6 @@ void HALSIM_SetJoystickType(int32_t stick, int32_t type) {}
void HALSIM_SetJoystickName(int32_t stick, const struct WPI_String* name) {}
-void HALSIM_SetJoystickAxisType(int32_t stick, int32_t axis, int32_t type) {}
-
void HALSIM_SetGameSpecificMessage(const struct WPI_String* message) {}
void HALSIM_SetEventName(const struct WPI_String* name) {}
diff --git a/hal/src/test/native/cpp/mockdata/DriverStationDataTest.cpp b/hal/src/test/native/cpp/mockdata/DriverStationDataTest.cpp
index fed63a93bf..0f8e1f0cc5 100644
--- a/hal/src/test/native/cpp/mockdata/DriverStationDataTest.cpp
+++ b/hal/src/test/native/cpp/mockdata/DriverStationDataTest.cpp
@@ -24,18 +24,18 @@ TEST(DriverStationTest, Joystick) {
HAL_GetJoystickPOVs(joystickNum, &povs);
HAL_GetJoystickButtons(joystickNum, &buttons);
- EXPECT_EQ(0, axes.count);
+ EXPECT_EQ(0, axes.available);
for (int i = 0; i < HAL_kMaxJoystickAxes; ++i) {
EXPECT_EQ(0, axes.axes[i]);
}
- EXPECT_EQ(0, povs.count);
+ EXPECT_EQ(0, povs.available);
for (int i = 0; i < HAL_kMaxJoystickPOVs; ++i) {
EXPECT_EQ(0, povs.povs[i]);
}
- EXPECT_EQ(0, buttons.count);
- EXPECT_EQ(0u, buttons.buttons);
+ EXPECT_EQ(0llu, buttons.available);
+ EXPECT_EQ(0llu, buttons.buttons);
}
HAL_JoystickAxes set_axes;
@@ -47,17 +47,17 @@ TEST(DriverStationTest, Joystick) {
// Set values
int joystickUnderTest = 4;
- set_axes.count = 5;
- for (int i = 0; i < set_axes.count; ++i) {
+ set_axes.available = 0x1F;
+ for (int i = 0; i < 5; ++i) {
set_axes.axes[i] = i * 0.125;
}
- set_povs.count = 3;
+ set_povs.available = 0x7;
set_povs.povs[0] = HAL_JoystickPOV_kUp;
set_povs.povs[1] = HAL_JoystickPOV_kRight;
set_povs.povs[2] = HAL_JoystickPOV_kDown;
- set_buttons.count = 8;
+ set_buttons.available = 0xFF;
set_buttons.buttons = 0xDEADBEEF;
HALSIM_SetJoystickAxes(joystickUnderTest, &set_axes);
@@ -72,7 +72,7 @@ TEST(DriverStationTest, Joystick) {
HAL_GetJoystickPOVs(joystickUnderTest, &povs);
HAL_GetJoystickButtons(joystickUnderTest, &buttons);
- EXPECT_EQ(5, axes.count);
+ EXPECT_EQ(0x1F, axes.available);
EXPECT_NEAR(0.000, axes.axes[0], 0.000001);
EXPECT_NEAR(0.125, axes.axes[1], 0.000001);
EXPECT_NEAR(0.250, axes.axes[2], 0.000001);
@@ -81,7 +81,7 @@ TEST(DriverStationTest, Joystick) {
EXPECT_NEAR(0, axes.axes[5], 0.000001); // Should not have been set, still 0
EXPECT_NEAR(0, axes.axes[6], 0.000001); // Should not have been set, still 0
- EXPECT_EQ(3, povs.count);
+ EXPECT_EQ(0x7, povs.available);
EXPECT_EQ(HAL_JoystickPOV_kUp, povs.povs[0]);
EXPECT_EQ(HAL_JoystickPOV_kRight, povs.povs[1]);
EXPECT_EQ(HAL_JoystickPOV_kDown, povs.povs[2]);
@@ -90,8 +90,8 @@ TEST(DriverStationTest, Joystick) {
EXPECT_EQ(0, povs.povs[5]); // Should not have been set, still 0
EXPECT_EQ(0, povs.povs[6]); // Should not have been set, still 0
- EXPECT_EQ(8, buttons.count);
- EXPECT_EQ(0xDEADBEEFu, buttons.buttons);
+ EXPECT_EQ(0xFFllu, buttons.available);
+ EXPECT_EQ(0xDEADBEEFllu, buttons.buttons);
// Reset
HALSIM_ResetDriverStationData();
@@ -103,18 +103,18 @@ TEST(DriverStationTest, Joystick) {
HAL_GetJoystickPOVs(joystickNum, &povs);
HAL_GetJoystickButtons(joystickNum, &buttons);
- EXPECT_EQ(0, axes.count);
+ EXPECT_EQ(0, axes.available);
for (int i = 0; i < HAL_kMaxJoystickAxes; ++i) {
EXPECT_EQ(0, axes.axes[i]);
}
- EXPECT_EQ(0, povs.count);
+ EXPECT_EQ(0, povs.available);
for (int i = 0; i < HAL_kMaxJoystickPOVs; ++i) {
EXPECT_EQ(0, povs.povs[i]);
}
- EXPECT_EQ(0, buttons.count);
- EXPECT_EQ(0u, buttons.buttons);
+ EXPECT_EQ(0llu, buttons.available);
+ EXPECT_EQ(0llu, buttons.buttons);
}
}
diff --git a/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp b/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp
index 6445522cfe..7c51f71c66 100644
--- a/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp
+++ b/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp
@@ -108,7 +108,7 @@ void DSCommPacket::ReadJoystickTag(std::span dataInput,
stick.axes.axes[i] = value / 127.0;
}
}
- stick.axes.count = axesLength;
+ stick.axes.available = (1 << axesLength) - 1;
dataInput = dataInput.subspan(1 + axesLength);
@@ -119,7 +119,12 @@ void DSCommPacket::ReadJoystickTag(std::span dataInput,
for (int i = 0; i < numBytes; i++) {
stick.buttons.buttons |= dataInput[numBytes - i] << (8 * (i));
}
- stick.buttons.count = buttonCount;
+
+ if (buttonCount < 64) {
+ stick.buttons.available = (1ULL << buttonCount) - 1;
+ } else {
+ stick.buttons.available = (std::numeric_limits::max)();
+ }
dataInput = dataInput.subspan(1 + numBytes);
@@ -129,7 +134,7 @@ void DSCommPacket::ReadJoystickTag(std::span dataInput,
DegreesToPOV((dataInput[1 + i] << 8) | dataInput[2 + i]);
}
- stick.povs.count = povsLength;
+ stick.povs.available = (1 << povsLength) - 1;
return;
}
@@ -264,17 +269,6 @@ void DSCommPacket::ReadJoystickDescriptionTag(std::span data) {
}
data = data.subspan(4 + nameLength);
packet.descriptor.name[nameLength] = '\0';
- int axesCount = data[0];
- packet.descriptor.axisCount = axesCount;
- for (int i = 0,
- len = std::min(axesCount, sizeof(packet.descriptor.axisTypes));
- i < len; i++) {
- packet.descriptor.axisTypes[i] = data[1 + i];
- }
- data = data.subspan(1 + axesCount);
-
- packet.descriptor.buttonCount = data[0];
- packet.descriptor.povCount = data[1];
}
void DSCommPacket::SendJoysticks(void) {
diff --git a/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp b/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp
index daddff48ab..9a9a6f6a72 100644
--- a/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp
+++ b/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp
@@ -42,9 +42,9 @@ TEST_F(DSCommPacketTest, EmptyJoystickTag) {
for (int i = 0; i < HAL_kMaxJoysticks; i++) {
uint8_t arr[2];
auto& data = ReadJoystickTag(arr, 0);
- ASSERT_EQ(data.axes.count, 0);
- ASSERT_EQ(data.povs.count, 0);
- ASSERT_EQ(data.buttons.count, 0);
+ ASSERT_EQ(data.axes.available, 0);
+ ASSERT_EQ(data.povs.available, 0);
+ ASSERT_EQ(data.buttons.available, 0llu);
}
}
@@ -57,9 +57,9 @@ TEST_F(DSCommPacketTest, BlankJoystickTag) {
arr[3] = 0;
arr[4] = 0;
auto& data = ReadJoystickTag(arr, 0);
- ASSERT_EQ(data.axes.count, 0);
- ASSERT_EQ(data.povs.count, 0);
- ASSERT_EQ(data.buttons.count, 0);
+ ASSERT_EQ(data.axes.available, 0);
+ ASSERT_EQ(data.povs.available, 0);
+ ASSERT_EQ(data.buttons.available, 0llu);
}
}
@@ -87,12 +87,12 @@ TEST_F(DSCommPacketTest, MainJoystickTag) {
3, 0, 50, 0, 100, 0x0F, 0x00};
auto& data = ReadJoystickTag(arr, 0);
- ASSERT_EQ(data.axes.count, 4);
- ASSERT_EQ(data.povs.count, 3);
- ASSERT_EQ(data.buttons.count, 12);
+ ASSERT_EQ(data.axes.available, 0xF);
+ ASSERT_EQ(data.povs.available, 0x7);
+ ASSERT_EQ(data.buttons.available, 0xFFFllu);
for (int btn = 0; btn < 12; btn++) {
- ASSERT_EQ((data.buttons.buttons & (1 << btn)) != 0, _buttons[btn] != 0)
+ ASSERT_EQ((data.buttons.buttons & (1llu << btn)) != 0, _buttons[btn] != 0)
<< "Button " << btn;
}
}
@@ -115,12 +115,6 @@ TEST_F(DSCommPacketTest, DescriptorTag) {
ASSERT_EQ(data.descriptor.isGamepad, 1);
ASSERT_EQ(data.descriptor.type, 0);
ASSERT_STREQ(data.descriptor.name, "Hello World");
- ASSERT_EQ(data.descriptor.axisCount, 4);
- for (int i = 0; i < 4; i++) {
- ASSERT_EQ(data.descriptor.axisTypes[i], i + 1);
- }
- ASSERT_EQ(data.descriptor.buttonCount, 12);
- ASSERT_EQ(data.descriptor.povCount, 3);
}
}
diff --git a/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp b/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp
index 72fab161c0..78d62473d7 100644
--- a/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp
+++ b/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp
@@ -178,7 +178,7 @@ struct RobotJoystick {
void SetHAL(int i);
void GetHAL(int i);
bool IsButtonPressed(int i) {
- return (data.buttons.buttons & (1u << i)) != 0;
+ return (data.buttons.buttons & (1llu << i)) != 0;
}
};
@@ -294,7 +294,7 @@ static inline bool IsDSDisabled() {
JoystickModel::JoystickModel(int index) : m_index{index} {
HAL_JoystickAxes halAxes;
HALSIM_GetJoystickAxes(index, &halAxes);
- axisCount = halAxes.count;
+ axisCount = static_cast(16 - std::countl_zero(halAxes.available));
for (int i = 0; i < axisCount; ++i) {
axes[i] = std::make_unique(
fmt::format("Joystick[{}] Axis[{}]", index, i));
@@ -302,18 +302,19 @@ JoystickModel::JoystickModel(int index) : m_index{index} {
HAL_JoystickButtons halButtons;
HALSIM_GetJoystickButtons(index, &halButtons);
- buttonCount = halButtons.count;
+ buttonCount =
+ static_cast(64 - std::countl_zero(halButtons.available));
for (int i = 0; i < buttonCount; ++i) {
buttons[i] = new glass::BooleanSource(
fmt::format("Joystick[{}] Button[{}]", index, i + 1));
}
- for (int i = buttonCount; i < 32; ++i) {
+ for (int i = buttonCount; i < 64; ++i) {
buttons[i] = nullptr;
}
HAL_JoystickPOVs halPOVs;
HALSIM_GetJoystickPOVs(index, &halPOVs);
- povCount = halPOVs.count;
+ povCount = static_cast(8 - std::countl_zero(halPOVs.available));
for (int i = 0; i < povCount; ++i) {
povs[i] = std::make_unique(
fmt::format("Joystick[{}] POV [{}]", index, i));
@@ -328,7 +329,8 @@ void JoystickModel::CallbackFunc(const char*, void* param, const HAL_Value*) {
HAL_JoystickAxes halAxes;
HALSIM_GetJoystickAxes(self->m_index, &halAxes);
- for (int i = 0; i < halAxes.count; ++i) {
+ int halAxesCount = 16 - std::countl_zero(halAxes.available);
+ for (int i = 0; i < halAxesCount; ++i) {
if (auto axis = self->axes[i].get()) {
axis->SetValue(halAxes.axes[i]);
}
@@ -336,15 +338,17 @@ void JoystickModel::CallbackFunc(const char*, void* param, const HAL_Value*) {
HAL_JoystickButtons halButtons;
HALSIM_GetJoystickButtons(self->m_index, &halButtons);
- for (int i = 0; i < halButtons.count; ++i) {
+ int halButtonCount = 64 - std::countl_zero(halButtons.available);
+ for (int i = 0; i < halButtonCount; ++i) {
if (auto button = self->buttons[i]) {
- button->SetValue((halButtons.buttons & (1u << i)) != 0 ? 1 : 0);
+ button->SetValue((halButtons.buttons & (1llu << i)) != 0 ? 1 : 0);
}
}
HAL_JoystickPOVs halPOVs;
HALSIM_GetJoystickPOVs(self->m_index, &halPOVs);
- for (int i = 0; i < halPOVs.count; ++i) {
+ int halPovCount = 8 - std::countl_zero(halPOVs.available);
+ for (int i = 0; i < halPovCount; ++i) {
if (auto pov = self->povs[i].get()) {
pov->SetValue(halPOVs.povs[i]);
}
@@ -419,17 +423,22 @@ void GlfwSystemJoystick::GetData(HALJoystickData* data, bool mapGamepad) const {
data->desc.type = m_isGamepad ? 21 : 20;
std::strncpy(data->desc.name, m_name, sizeof(data->desc.name) - 1);
data->desc.name[sizeof(data->desc.name) - 1] = '\0';
- data->desc.axisCount = (std::min)(m_axisCount, HAL_kMaxJoystickAxes);
- // desc.axisTypes ???
- data->desc.buttonCount = (std::min)(m_buttonCount, 32);
- data->desc.povCount = (std::min)(m_hatCount, HAL_kMaxJoystickPOVs);
+ int axesCount = (std::min)(m_axisCount, HAL_kMaxJoystickAxes);
+ int buttonCount = (std::min)(m_buttonCount, 64);
+ int povsCount = (std::min)(m_hatCount, HAL_kMaxJoystickPOVs);
- data->buttons.count = data->desc.buttonCount;
- for (int j = 0; j < data->buttons.count; ++j) {
+ if (buttonCount < 64) {
+ data->buttons.available = (1ULL << buttonCount) - 1;
+ } else {
+ data->buttons.available = (std::numeric_limits::max)();
+ }
+ data->axes.available = (1 << axesCount) - 1;
+ data->povs.available = (1 << povsCount) - 1;
+
+ for (int j = 0; j < buttonCount; ++j) {
data->buttons.buttons |= (sysButtons[j] ? 1u : 0u) << j;
}
- data->axes.count = data->desc.axisCount;
if (m_isGamepad && mapGamepad) {
// the FRC DriverStation maps gamepad (XInput) trigger values to 0-1 range
// on axis 2 and 3.
@@ -440,21 +449,12 @@ void GlfwSystemJoystick::GetData(HALJoystickData* data, bool mapGamepad) const {
data->axes.axes[4] = sysAxes[2];
data->axes.axes[5] = sysAxes[3];
- // the start button for gamepads is not mapped on the FRC DriverStation
- // platforms, so remove it if present
- if (data->buttons.count == 11) {
- --data->desc.buttonCount;
- --data->buttons.count;
- data->buttons.buttons = (data->buttons.buttons & 0xff) |
- ((data->buttons.buttons >> 1) & 0x300);
- }
} else {
std::memcpy(data->axes.axes, sysAxes,
- data->axes.count * sizeof(data->axes.axes[0]));
+ axesCount * sizeof(data->axes.axes[0]));
}
- data->povs.count = data->desc.povCount;
- for (int j = 0; j < data->povs.count; ++j) {
+ for (int j = 0; j < povsCount; ++j) {
#if __GNUC__ >= 12
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wstringop-overflow="
@@ -706,20 +706,27 @@ void KeyboardJoystick::Update() {
m_povCount = 0;
}
- m_data.axes.count =
+ int axesCount =
(std::min)(m_axisCount, static_cast(m_axisConfig.size()));
- m_data.buttons.count =
+ int buttonsCount =
(std::min)(m_buttonCount, static_cast(m_buttonKey.size()));
- m_data.povs.count =
- (std::min)(m_povCount, static_cast(m_povConfig.size()));
+ int povsCount = (std::min)(m_povCount, static_cast(m_povConfig.size()));
- if (m_data.axes.count > 0 || m_data.buttons.count > 0 ||
- m_data.povs.count > 0) {
+ m_data.axes.available = (1 << axesCount) - 1;
+ m_data.povs.available = (1 << povsCount) - 1;
+ if (buttonsCount >= 64) {
+ m_data.buttons.available = (std::numeric_limits::max)();
+ } else {
+ m_data.buttons.available = (1u << buttonsCount) - 1;
+ }
+
+ if (m_data.axes.available > 0 || m_data.buttons.available > 0 ||
+ m_data.povs.available > 0) {
m_present = true;
}
// axes
- for (int i = 0; i < m_data.axes.count; ++i) {
+ for (int i = 0; i < axesCount; ++i) {
auto& config = m_axisConfig[i];
float& axisValue = m_data.axes.axes[i];
// increase/decrease while key held down (to saturation); decay back to 0
@@ -753,15 +760,15 @@ void KeyboardJoystick::Update() {
// buttons
m_data.buttons.buttons = 0;
m_anyButtonPressed = false;
- for (int i = 0; i < m_data.buttons.count; ++i) {
+ for (int i = 0; i < buttonsCount; ++i) {
if (IsKeyDown(io, m_buttonKey[i])) {
- m_data.buttons.buttons |= 1u << i;
+ m_data.buttons.buttons |= 1llu << i;
m_anyButtonPressed = true;
}
}
// povs
- for (int i = 0; i < m_data.povs.count; ++i) {
+ for (int i = 0; i < povsCount; ++i) {
auto& config = m_povConfig[i];
auto& povValue = m_data.povs.povs[i];
povValue = HAL_JoystickPOV_kCentered;
@@ -791,11 +798,6 @@ void KeyboardJoystick::Update() {
break;
}
}
-
- // update desc
- m_data.desc.axisCount = m_data.axes.count;
- m_data.desc.buttonCount = m_data.buttons.count;
- m_data.desc.povCount = m_data.povs.count;
}
void KeyboardJoystick::ClearKey(int key) {
@@ -1010,10 +1012,20 @@ static void DriverStationExecute() {
// update sources
for (int i = 0; i < HAL_kMaxJoysticks; ++i) {
auto& source = gJoystickSources[i];
- int32_t axisCount, buttonCount, povCount;
- HALSIM_GetJoystickCounts(i, &axisCount, &buttonCount, &povCount);
- if (axisCount != 0 || buttonCount != 0 || povCount != 0) {
- if (!source || source->axisCount != axisCount ||
+ uint16_t axesAvailable;
+ uint8_t povsAvailable;
+ uint64_t buttonsAvailable;
+ HALSIM_GetJoystickAvailables(i, &axesAvailable, &buttonsAvailable,
+ &povsAvailable);
+ if (axesAvailable != 0 || buttonsAvailable != 0 || povsAvailable != 0) {
+ uint8_t axesCount =
+ static_cast(16 - std::countl_zero(axesAvailable));
+ uint8_t buttonCount =
+ static_cast(64 - std::countl_zero(buttonsAvailable));
+ uint8_t povCount =
+ static_cast(8 - std::countl_zero(povsAvailable));
+
+ if (!source || source->axisCount != axesCount ||
source->buttonCount != buttonCount || source->povCount != povCount) {
source.reset();
source = std::make_unique(i);
@@ -1321,7 +1333,10 @@ static void DisplayJoysticks() {
}
}
- for (int j = 0; j < joy.data.axes.count; ++j) {
+ uint8_t axesCount =
+ static_cast(16 - std::countl_zero(joy.data.axes.available));
+
+ for (int j = 0; j < axesCount; ++j) {
if (source && source->axes[j]) {
char label[64];
wpi::format_to_n_c_str(label, sizeof(label), "Axis[{}]", j);
@@ -1335,7 +1350,10 @@ static void DisplayJoysticks() {
}
}
- for (int j = 0; j < joy.data.povs.count; ++j) {
+ uint8_t povCount =
+ static_cast(16 - std::countl_zero(joy.data.povs.available));
+
+ for (int j = 0; j < povCount; ++j) {
if (source && source->povs[j]) {
char label[64];
wpi::format_to_n_c_str(label, sizeof(label), "POVs[{}]", j);
@@ -1349,11 +1367,14 @@ static void DisplayJoysticks() {
}
}
+ uint8_t buttonCount = static_cast(
+ 64 - std::countl_zero(joy.data.buttons.available));
+
// show buttons as multiple lines of LED indicators, 8 per line
static const ImU32 color = IM_COL32(255, 255, 102, 255);
wpi::SmallVector buttons;
- buttons.resize(joy.data.buttons.count);
- for (int j = 0; j < joy.data.buttons.count; ++j) {
+ buttons.resize(buttonCount);
+ for (int j = 0; j < buttonCount; ++j) {
buttons[j] = joy.IsButtonPressed(j) ? 1 : -1;
}
DrawLEDSources(buttons.data(), source ? source->buttons : nullptr,
diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Joystick.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Joystick.cpp
index 8e35d56b50..8ac98a73a5 100644
--- a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Joystick.cpp
+++ b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Joystick.cpp
@@ -37,7 +37,9 @@ void HALSimWSProviderJoystick::RegisterCallbacks() {
std::vector axesValues;
HALSIM_GetJoystickAxes(provider->GetChannel(), &axes);
- for (int i = 0; i < axes.count; i++) {
+ int axesCount = 16 - std::countl_zero(axes.available);
+
+ for (int i = 0; i < axesCount; i++) {
axesValues.push_back(axes.axes[i]);
}
@@ -46,7 +48,9 @@ void HALSimWSProviderJoystick::RegisterCallbacks() {
std::vector povsValues;
HALSIM_GetJoystickPOVs(provider->GetChannel(), &povs);
- for (int i = 0; i < povs.count; i++) {
+ int povsCount = 8 - std::countl_zero(povs.available);
+
+ for (int i = 0; i < povsCount; i++) {
povsValues.push_back(povs.povs[i]);
}
@@ -54,7 +58,9 @@ void HALSimWSProviderJoystick::RegisterCallbacks() {
HAL_JoystickButtons buttons{};
std::vector buttonsValues;
- for (int i = 0; i < buttons.count; i++) {
+ int buttonsCount = 64 - std::countl_zero(buttons.available);
+
+ for (int i = 0; i < buttonsCount; i++) {
buttonsValues.push_back(((buttons.buttons >> i) & 0x1) == 1);
}
@@ -96,10 +102,11 @@ void HALSimWSProviderJoystick::OnNetValueChanged(const wpi::json& json) {
wpi::json::const_iterator it;
if ((it = json.find(">axes")) != json.end()) {
HAL_JoystickAxes axes{};
- axes.count =
+ wpi::json::size_type axesCount =
std::min(it.value().size(),
static_cast(HAL_kMaxJoystickAxes));
- for (int i = 0; i < axes.count; i++) {
+ axes.available = (1 << axesCount) - 1;
+ for (wpi::json::size_type i = 0; i < axesCount; i++) {
axes.axes[i] = it.value()[i];
}
@@ -108,11 +115,16 @@ void HALSimWSProviderJoystick::OnNetValueChanged(const wpi::json& json) {
if ((it = json.find(">buttons")) != json.end()) {
HAL_JoystickButtons buttons{};
- buttons.count =
- std::min(it.value().size(), static_cast(32));
- for (int i = 0; i < buttons.count; i++) {
+ wpi::json::size_type buttonsCount =
+ std::min(it.value().size(), static_cast(64));
+ if (buttonsCount < 64) {
+ buttons.available = (1ULL << buttonsCount) - 1;
+ } else {
+ buttons.available = (std::numeric_limits::max)();
+ }
+ for (wpi::json::size_type i = 0; i < buttonsCount; i++) {
if (it.value()[i]) {
- buttons.buttons |= 1 << i;
+ buttons.buttons |= 1llu << i;
}
}
@@ -121,10 +133,11 @@ void HALSimWSProviderJoystick::OnNetValueChanged(const wpi::json& json) {
if ((it = json.find(">povs")) != json.end()) {
HAL_JoystickPOVs povs{};
- povs.count =
+ wpi::json::size_type povsCount =
std::min(it.value().size(),
static_cast(HAL_kMaxJoystickPOVs));
- for (int i = 0; i < povs.count; i++) {
+ povs.available = (1 << povsCount) - 1;
+ for (wpi::json::size_type i = 0; i < povsCount; i++) {
povs.povs[i] = it.value()[i];
}
diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandGamepad.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandGamepad.java
new file mode 100644
index 0000000000..efa9374b14
--- /dev/null
+++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/CommandGamepad.java
@@ -0,0 +1,745 @@
+// 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.wpilibj2.command.button;
+
+import edu.wpi.first.wpilibj.Gamepad;
+import edu.wpi.first.wpilibj.event.EventLoop;
+import edu.wpi.first.wpilibj2.command.CommandScheduler;
+
+/**
+ * A version of {@link Gamepad} with {@link Trigger} factories for command-based.
+ *
+ * @see Gamepad
+ */
+@SuppressWarnings("MethodName")
+public class CommandGamepad extends CommandGenericHID {
+ private final Gamepad m_hid;
+
+ /**
+ * Construct an instance of a controller.
+ *
+ * @param port The port index on the Driver Station that the controller is plugged into.
+ */
+ public CommandGamepad(int port) {
+ super(port);
+ m_hid = new Gamepad(port);
+ }
+
+ /**
+ * Get the underlying GenericHID object.
+ *
+ * @return the wrapped GenericHID object
+ */
+ @Override
+ public Gamepad getHID() {
+ return m_hid;
+ }
+
+ /**
+ * Constructs a Trigger instance around the South Face button's digital signal.
+ *
+ * @return a Trigger instance representing the South Face button's digital signal attached to the
+ * {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #southFace(EventLoop)
+ */
+ public Trigger southFace() {
+ return southFace(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the South Face button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the South Face button's digital signal attached to the
+ * given loop.
+ */
+ public Trigger southFace(EventLoop loop) {
+ return button(Gamepad.Button.kSouthFace.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the East Face button's digital signal.
+ *
+ * @return a Trigger instance representing the East Face button's digital signal attached to the
+ * {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #eastFace(EventLoop)
+ */
+ public Trigger eastFace() {
+ return eastFace(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the East Face button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the East Face button's digital signal attached to the
+ * given loop.
+ */
+ public Trigger eastFace(EventLoop loop) {
+ return button(Gamepad.Button.kEastFace.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the West Face button's digital signal.
+ *
+ * @return a Trigger instance representing the West Face button's digital signal attached to the
+ * {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #westFace(EventLoop)
+ */
+ public Trigger westFace() {
+ return westFace(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the West Face button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the West Face button's digital signal attached to the
+ * given loop.
+ */
+ public Trigger westFace(EventLoop loop) {
+ return button(Gamepad.Button.kWestFace.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the North Face button's digital signal.
+ *
+ * @return a Trigger instance representing the North Face button's digital signal attached to the
+ * {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #northFacen(EventLoop)
+ */
+ public Trigger northFacen() {
+ return northFacen(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the North Face button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the North Face button's digital signal attached to the
+ * given loop.
+ */
+ public Trigger northFacen(EventLoop loop) {
+ return button(Gamepad.Button.kNorthFacen.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the Back button's digital signal.
+ *
+ * @return a Trigger instance representing the Back button's digital signal attached to the {@link
+ * CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #back(EventLoop)
+ */
+ public Trigger back() {
+ return back(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the Back button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the Back button's digital signal attached to the given
+ * loop.
+ */
+ public Trigger back(EventLoop loop) {
+ return button(Gamepad.Button.kBack.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the Guide button's digital signal.
+ *
+ * @return a Trigger instance representing the Guide button's digital signal attached to the
+ * {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #guide(EventLoop)
+ */
+ public Trigger guide() {
+ return guide(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the Guide button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the Guide button's digital signal attached to the given
+ * loop.
+ */
+ public Trigger guide(EventLoop loop) {
+ return button(Gamepad.Button.kGuide.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the Start button's digital signal.
+ *
+ * @return a Trigger instance representing the Start button's digital signal attached to the
+ * {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #start(EventLoop)
+ */
+ public Trigger start() {
+ return start(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the Start button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the Start button's digital signal attached to the given
+ * loop.
+ */
+ public Trigger start(EventLoop loop) {
+ return button(Gamepad.Button.kStart.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the left stick button's digital signal.
+ *
+ * @return a Trigger instance representing the left stick button's digital signal attached to the
+ * {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #leftStick(EventLoop)
+ */
+ public Trigger leftStick() {
+ return leftStick(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the left stick button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the left stick button's digital signal attached to the
+ * given loop.
+ */
+ public Trigger leftStick(EventLoop loop) {
+ return button(Gamepad.Button.kLeftStick.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the right stick button's digital signal.
+ *
+ * @return a Trigger instance representing the right stick button's digital signal attached to the
+ * {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #rightStick(EventLoop)
+ */
+ public Trigger rightStick() {
+ return rightStick(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the right stick button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the right stick button's digital signal attached to the
+ * given loop.
+ */
+ public Trigger rightStick(EventLoop loop) {
+ return button(Gamepad.Button.kRightStick.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the right shoulder button's digital signal.
+ *
+ * @return a Trigger instance representing the right shoulder button's digital signal attached to
+ * the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #leftShoulder(EventLoop)
+ */
+ public Trigger leftShoulder() {
+ return leftShoulder(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the right shoulder button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the right shoulder button's digital signal attached to
+ * the given loop.
+ */
+ public Trigger leftShoulder(EventLoop loop) {
+ return button(Gamepad.Button.kLeftShoulder.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the right shoulder button's digital signal.
+ *
+ * @return a Trigger instance representing the right shoulder button's digital signal attached to
+ * the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #rightShoulder(EventLoop)
+ */
+ public Trigger rightShoulder() {
+ return rightShoulder(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the right shoulder button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the right shoulder button's digital signal attached to
+ * the given loop.
+ */
+ public Trigger rightShoulder(EventLoop loop) {
+ return button(Gamepad.Button.kRightShoulder.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the D-pad up button's digital signal.
+ *
+ * @return a Trigger instance representing the D-pad up button's digital signal attached to the
+ * {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #dpadUp(EventLoop)
+ */
+ public Trigger dpadUp() {
+ return dpadUp(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the D-pad up button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the D-pad up button's digital signal attached to the
+ * given loop.
+ */
+ public Trigger dpadUp(EventLoop loop) {
+ return button(Gamepad.Button.kDpadUp.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the D-pad down button's digital signal.
+ *
+ * @return a Trigger instance representing the D-pad down button's digital signal attached to the
+ * {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #dpadDown(EventLoop)
+ */
+ public Trigger dpadDown() {
+ return dpadDown(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the D-pad down button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the D-pad down button's digital signal attached to the
+ * given loop.
+ */
+ public Trigger dpadDown(EventLoop loop) {
+ return button(Gamepad.Button.kDpadDown.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the D-pad left button's digital signal.
+ *
+ * @return a Trigger instance representing the D-pad left button's digital signal attached to the
+ * {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #dpadLeft(EventLoop)
+ */
+ public Trigger dpadLeft() {
+ return dpadLeft(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the D-pad left button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the D-pad left button's digital signal attached to the
+ * given loop.
+ */
+ public Trigger dpadLeft(EventLoop loop) {
+ return button(Gamepad.Button.kDpadLeft.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the D-pad right button's digital signal.
+ *
+ * @return a Trigger instance representing the D-pad right button's digital signal attached to the
+ * {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #dpadRight(EventLoop)
+ */
+ public Trigger dpadRight() {
+ return dpadRight(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the D-pad right button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the D-pad right button's digital signal attached to the
+ * given loop.
+ */
+ public Trigger dpadRight(EventLoop loop) {
+ return button(Gamepad.Button.kDpadRight.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 1 button's digital signal.
+ *
+ * @return a Trigger instance representing the Miscellaneous 1 button's digital signal attached to
+ * the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #misc1(EventLoop)
+ */
+ public Trigger misc1() {
+ return misc1(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 1 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the Miscellaneous 1 button's digital signal attached to
+ * the given loop.
+ */
+ public Trigger misc1(EventLoop loop) {
+ return button(Gamepad.Button.kMisc1.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the Right Paddle 1 button's digital signal.
+ *
+ * @return a Trigger instance representing the Right Paddle 1 button's digital signal attached to
+ * the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #rightPaddle1(EventLoop)
+ */
+ public Trigger rightPaddle1() {
+ return rightPaddle1(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the Right Paddle 1 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the Right Paddle 1 button's digital signal attached to
+ * the given loop.
+ */
+ public Trigger rightPaddle1(EventLoop loop) {
+ return button(Gamepad.Button.kRightPaddle1.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the Left Paddle 1 button's digital signal.
+ *
+ * @return a Trigger instance representing the Left Paddle 1 button's digital signal attached to
+ * the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #leftPaddle1(EventLoop)
+ */
+ public Trigger leftPaddle1() {
+ return leftPaddle1(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the Left Paddle 1 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the Left Paddle 1 button's digital signal attached to
+ * the given loop.
+ */
+ public Trigger leftPaddle1(EventLoop loop) {
+ return button(Gamepad.Button.kLeftPaddle1.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the Right Paddle 2 button's digital signal.
+ *
+ * @return a Trigger instance representing the Right Paddle 2 button's digital signal attached to
+ * the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #rightPaddle2(EventLoop)
+ */
+ public Trigger rightPaddle2() {
+ return rightPaddle2(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the Right Paddle 2 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the Right Paddle 2 button's digital signal attached to
+ * the given loop.
+ */
+ public Trigger rightPaddle2(EventLoop loop) {
+ return button(Gamepad.Button.kRightPaddle2.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the Left Paddle 2 button's digital signal.
+ *
+ * @return a Trigger instance representing the Left Paddle 2 button's digital signal attached to
+ * the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #leftPaddle2(EventLoop)
+ */
+ public Trigger leftPaddle2() {
+ return leftPaddle2(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the Left Paddle 2 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the Left Paddle 2 button's digital signal attached to
+ * the given loop.
+ */
+ public Trigger leftPaddle2(EventLoop loop) {
+ return button(Gamepad.Button.kLeftPaddle2.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the Touchpad button's digital signal.
+ *
+ * @return a Trigger instance representing the Touchpad button's digital signal attached to the
+ * {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #touchpad(EventLoop)
+ */
+ public Trigger touchpad() {
+ return touchpad(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the Touchpad button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the Touchpad button's digital signal attached to the
+ * given loop.
+ */
+ public Trigger touchpad(EventLoop loop) {
+ return button(Gamepad.Button.kTouchpad.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 2 button's digital signal.
+ *
+ * @return a Trigger instance representing the Miscellaneous 2 button's digital signal attached to
+ * the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #misc2(EventLoop)
+ */
+ public Trigger misc2() {
+ return misc2(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 2 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the Miscellaneous 2 button's digital signal attached to
+ * the given loop.
+ */
+ public Trigger misc2(EventLoop loop) {
+ return button(Gamepad.Button.kMisc2.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 3 button's digital signal.
+ *
+ * @return a Trigger instance representing the Miscellaneous 3 button's digital signal attached to
+ * the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #misc3(EventLoop)
+ */
+ public Trigger misc3() {
+ return misc3(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 3 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the Miscellaneous 3 button's digital signal attached to
+ * the given loop.
+ */
+ public Trigger misc3(EventLoop loop) {
+ return button(Gamepad.Button.kMisc3.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 4 button's digital signal.
+ *
+ * @return a Trigger instance representing the Miscellaneous 4 button's digital signal attached to
+ * the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #misc4(EventLoop)
+ */
+ public Trigger misc4() {
+ return misc4(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 4 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the Miscellaneous 4 button's digital signal attached to
+ * the given loop.
+ */
+ public Trigger misc4(EventLoop loop) {
+ return button(Gamepad.Button.kMisc4.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 5 button's digital signal.
+ *
+ * @return a Trigger instance representing the Miscellaneous 5 button's digital signal attached to
+ * the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #misc5(EventLoop)
+ */
+ public Trigger misc5() {
+ return misc5(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 5 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the Miscellaneous 5 button's digital signal attached to
+ * the given loop.
+ */
+ public Trigger misc5(EventLoop loop) {
+ return button(Gamepad.Button.kMisc5.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 6 button's digital signal.
+ *
+ * @return a Trigger instance representing the Miscellaneous 6 button's digital signal attached to
+ * the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ * @see #misc6(EventLoop)
+ */
+ public Trigger misc6() {
+ return misc6(CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 6 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return a Trigger instance representing the Miscellaneous 6 button's digital signal attached to
+ * the given loop.
+ */
+ public Trigger misc6(EventLoop loop) {
+ return button(Gamepad.Button.kMisc6.value, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the axis value of the left trigger. The returned trigger
+ * will be true when the axis value is greater than {@code threshold}.
+ *
+ * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value
+ * should be in the range [0, 1] where 0 is the unpressed state of the axis.
+ * @param loop the event loop instance to attach the Trigger to.
+ * @return a Trigger instance that is true when the left trigger's axis exceeds the provided
+ * threshold, attached to the given event loop
+ */
+ public Trigger leftTrigger(double threshold, EventLoop loop) {
+ return axisGreaterThan(Gamepad.Axis.kLeftTrigger.value, threshold, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the axis value of the left trigger. The returned trigger
+ * will be true when the axis value is greater than {@code threshold}.
+ *
+ * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value
+ * should be in the range [0, 1] where 0 is the unpressed state of the axis.
+ * @return a Trigger instance that is true when the left trigger's axis exceeds the provided
+ * threshold, attached to the {@link CommandScheduler#getDefaultButtonLoop() default scheduler
+ * button loop}.
+ */
+ public Trigger leftTrigger(double threshold) {
+ return leftTrigger(threshold, CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the axis value of the left trigger. The returned trigger
+ * will be true when the axis value is greater than 0.5.
+ *
+ * @return a Trigger instance that is true when the left trigger's axis exceeds 0.5, attached to
+ * the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ */
+ public Trigger leftTrigger() {
+ return leftTrigger(0.5);
+ }
+
+ /**
+ * Constructs a Trigger instance around the axis value of the right trigger. The returned trigger
+ * will be true when the axis value is greater than {@code threshold}.
+ *
+ * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value
+ * should be in the range [0, 1] where 0 is the unpressed state of the axis.
+ * @param loop the event loop instance to attach the Trigger to.
+ * @return a Trigger instance that is true when the right trigger's axis exceeds the provided
+ * threshold, attached to the given event loop
+ */
+ public Trigger rightTrigger(double threshold, EventLoop loop) {
+ return axisGreaterThan(Gamepad.Axis.kRightTrigger.value, threshold, loop);
+ }
+
+ /**
+ * Constructs a Trigger instance around the axis value of the right trigger. The returned trigger
+ * will be true when the axis value is greater than {@code threshold}.
+ *
+ * @param threshold the minimum axis value for the returned {@link Trigger} to be true. This value
+ * should be in the range [0, 1] where 0 is the unpressed state of the axis.
+ * @return a Trigger instance that is true when the right trigger's axis exceeds the provided
+ * threshold, attached to the {@link CommandScheduler#getDefaultButtonLoop() default scheduler
+ * button loop}.
+ */
+ public Trigger rightTrigger(double threshold) {
+ return rightTrigger(threshold, CommandScheduler.getInstance().getDefaultButtonLoop());
+ }
+
+ /**
+ * Constructs a Trigger instance around the axis value of the right trigger. The returned trigger
+ * will be true when the axis value is greater than 0.5.
+ *
+ * @return a Trigger instance that is true when the right trigger's axis exceeds 0.5, attached to
+ * the {@link CommandScheduler#getDefaultButtonLoop() default scheduler button loop}.
+ */
+ public Trigger rightTrigger() {
+ return rightTrigger(0.5);
+ }
+
+ /**
+ * Get the X axis value of left side of the controller. Right is positive.
+ *
+ * @return The axis value.
+ */
+ public double getLeftX() {
+ return m_hid.getLeftX();
+ }
+
+ /**
+ * Get the Y axis value of left side of the controller. Back is positive.
+ *
+ * @return The axis value.
+ */
+ public double getLeftY() {
+ return m_hid.getLeftY();
+ }
+
+ /**
+ * Get the X axis value of right side of the controller. Right is positive.
+ *
+ * @return The axis value.
+ */
+ public double getRightX() {
+ return m_hid.getRightX();
+ }
+
+ /**
+ * Get the Y axis value of right side of the controller. Back is positive.
+ *
+ * @return The axis value.
+ */
+ public double getRightY() {
+ return m_hid.getRightY();
+ }
+
+ /**
+ * Get the left trigger axis value of the controller. Note that this axis is bound to the range of
+ * [0, 1] as opposed to the usual [-1, 1].
+ *
+ * @return The axis value.
+ */
+ public double getLeftTriggerAxis() {
+ return m_hid.getLeftTriggerAxis();
+ }
+
+ /**
+ * Get the right trigger axis value of the controller. Note that this axis is bound to the range
+ * of [0, 1] as opposed to the usual [-1, 1].
+ *
+ * @return The axis value.
+ */
+ public double getRightTriggerAxis() {
+ return m_hid.getRightTriggerAxis();
+ }
+}
diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandGamepad.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandGamepad.cpp
new file mode 100644
index 0000000000..df7dd11b71
--- /dev/null
+++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/CommandGamepad.cpp
@@ -0,0 +1,156 @@
+// 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.
+
+#include "frc2/command/button/CommandGamepad.h"
+
+using namespace frc2;
+
+CommandGamepad::CommandGamepad(int port)
+ : CommandGenericHID(port), m_hid{frc::Gamepad(port)} {}
+
+frc::Gamepad& CommandGamepad::GetHID() {
+ return m_hid;
+}
+
+Trigger CommandGamepad::SouthFace(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kSouthFace, loop);
+}
+
+Trigger CommandGamepad::EastFace(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kEastFace, loop);
+}
+
+Trigger CommandGamepad::WestFace(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kWestFace, loop);
+}
+
+Trigger CommandGamepad::NorthFacen(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kNorthFacen, loop);
+}
+
+Trigger CommandGamepad::Back(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kBack, loop);
+}
+
+Trigger CommandGamepad::Guide(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kGuide, loop);
+}
+
+Trigger CommandGamepad::Start(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kStart, loop);
+}
+
+Trigger CommandGamepad::LeftStick(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kLeftStick, loop);
+}
+
+Trigger CommandGamepad::RightStick(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kRightStick, loop);
+}
+
+Trigger CommandGamepad::LeftShoulder(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kLeftShoulder, loop);
+}
+
+Trigger CommandGamepad::RightShoulder(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kRightShoulder, loop);
+}
+
+Trigger CommandGamepad::DpadUp(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kDpadUp, loop);
+}
+
+Trigger CommandGamepad::DpadDown(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kDpadDown, loop);
+}
+
+Trigger CommandGamepad::DpadLeft(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kDpadLeft, loop);
+}
+
+Trigger CommandGamepad::DpadRight(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kDpadRight, loop);
+}
+
+Trigger CommandGamepad::Misc1(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kMisc1, loop);
+}
+
+Trigger CommandGamepad::RightPaddle1(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kRightPaddle1, loop);
+}
+
+Trigger CommandGamepad::LeftPaddle1(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kLeftPaddle1, loop);
+}
+
+Trigger CommandGamepad::RightPaddle2(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kRightPaddle2, loop);
+}
+
+Trigger CommandGamepad::LeftPaddle2(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kLeftPaddle2, loop);
+}
+
+Trigger CommandGamepad::Touchpad(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kTouchpad, loop);
+}
+
+Trigger CommandGamepad::Misc2(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kMisc2, loop);
+}
+
+Trigger CommandGamepad::Misc3(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kMisc3, loop);
+}
+
+Trigger CommandGamepad::Misc4(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kMisc4, loop);
+}
+
+Trigger CommandGamepad::Misc5(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kMisc5, loop);
+}
+
+Trigger CommandGamepad::Misc6(frc::EventLoop* loop) const {
+ return Button(frc::Gamepad::Button::kMisc6, loop);
+}
+
+Trigger CommandGamepad::LeftTrigger(double threshold,
+ frc::EventLoop* loop) const {
+ return Trigger(loop, [this, threshold] {
+ return m_hid.GetLeftTriggerAxis() > threshold;
+ });
+}
+
+Trigger CommandGamepad::RightTrigger(double threshold,
+ frc::EventLoop* loop) const {
+ return Trigger(loop, [this, threshold] {
+ return m_hid.GetRightTriggerAxis() > threshold;
+ });
+}
+
+double CommandGamepad::GetLeftX() const {
+ return m_hid.GetLeftX();
+}
+
+double CommandGamepad::GetLeftY() const {
+ return m_hid.GetLeftY();
+}
+
+double CommandGamepad::GetRightX() const {
+ return m_hid.GetRightX();
+}
+
+double CommandGamepad::GetRightY() const {
+ return m_hid.GetRightY();
+}
+
+double CommandGamepad::GetLeftTriggerAxis() const {
+ return m_hid.GetLeftTriggerAxis();
+}
+
+double CommandGamepad::GetRightTriggerAxis() const {
+ return m_hid.GetRightTriggerAxis();
+}
diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandGamepad.h b/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandGamepad.h
new file mode 100644
index 0000000000..d02b60bb07
--- /dev/null
+++ b/wpilibNewCommands/src/main/native/include/frc2/command/button/CommandGamepad.h
@@ -0,0 +1,434 @@
+// 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.
+
+#pragma once
+#include
+
+#include "frc2/command/CommandScheduler.h"
+#include "frc2/command/button/CommandGenericHID.h"
+#include "frc2/command/button/Trigger.h"
+
+namespace frc2 {
+/**
+ * A version of {@link frc::Gamepad} with {@link Trigger} factories for
+ * command-based.
+ *
+ * @see frc::Gamepad
+ */
+class CommandGamepad : public CommandGenericHID {
+ public:
+ /**
+ * Construct an instance of a controller.
+ *
+ * @param port The port index on the Driver Station that the controller is
+ * plugged into.
+ */
+ explicit CommandGamepad(int port);
+
+ /**
+ * Get the underlying GenericHID object.
+ *
+ * @return the wrapped GenericHID object
+ */
+ frc::Gamepad& GetHID();
+
+ /**
+ * Constructs a Trigger instance around the South Face button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the South Face button's
+ * digital signal attached to the given loop.
+ */
+ Trigger SouthFace(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the East Face button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the East Face button's
+ * digital signal attached to the given loop.
+ */
+ Trigger EastFace(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the West Face button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the West Face button's
+ * digital signal attached to the given loop.
+ */
+ Trigger WestFace(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the North Face button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the North Face button's
+ * digital signal attached to the given loop.
+ */
+ Trigger NorthFacen(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the Back button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the Back button's
+ * digital signal attached to the given loop.
+ */
+ Trigger Back(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the Guide button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the Guide button's
+ * digital signal attached to the given loop.
+ */
+ Trigger Guide(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the Start button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the Start button's
+ * digital signal attached to the given loop.
+ */
+ Trigger Start(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the left stick button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the left stick button's
+ * digital signal attached to the given loop.
+ */
+ Trigger LeftStick(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the right stick button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the right stick button's
+ * digital signal attached to the given loop.
+ */
+ Trigger RightStick(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the right shoulder button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the right shoulder button's
+ * digital signal attached to the given loop.
+ */
+ Trigger LeftShoulder(
+ frc::EventLoop* loop =
+ CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the right shoulder button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the right shoulder button's
+ * digital signal attached to the given loop.
+ */
+ Trigger RightShoulder(
+ frc::EventLoop* loop =
+ CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the D-pad up button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the D-pad up button's
+ * digital signal attached to the given loop.
+ */
+ Trigger DpadUp(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the D-pad down button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the D-pad down button's
+ * digital signal attached to the given loop.
+ */
+ Trigger DpadDown(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the D-pad left button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the D-pad left button's
+ * digital signal attached to the given loop.
+ */
+ Trigger DpadLeft(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the D-pad right button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the D-pad right button's
+ * digital signal attached to the given loop.
+ */
+ Trigger DpadRight(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 1 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the Miscellaneous 1 button's
+ * digital signal attached to the given loop.
+ */
+ Trigger Misc1(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the Right Paddle 1 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the Right Paddle 1 button's
+ * digital signal attached to the given loop.
+ */
+ Trigger RightPaddle1(
+ frc::EventLoop* loop =
+ CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the Left Paddle 1 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the Left Paddle 1 button's
+ * digital signal attached to the given loop.
+ */
+ Trigger LeftPaddle1(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the Right Paddle 2 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the Right Paddle 2 button's
+ * digital signal attached to the given loop.
+ */
+ Trigger RightPaddle2(
+ frc::EventLoop* loop =
+ CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the Left Paddle 2 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the Left Paddle 2 button's
+ * digital signal attached to the given loop.
+ */
+ Trigger LeftPaddle2(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the Touchpad button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the Touchpad button's
+ * digital signal attached to the given loop.
+ */
+ Trigger Touchpad(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 2 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the Miscellaneous 2 button's
+ * digital signal attached to the given loop.
+ */
+ Trigger Misc2(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 3 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the Miscellaneous 3 button's
+ * digital signal attached to the given loop.
+ */
+ Trigger Misc3(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 4 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the Miscellaneous 4 button's
+ * digital signal attached to the given loop.
+ */
+ Trigger Misc4(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 5 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the Miscellaneous 5 button's
+ * digital signal attached to the given loop.
+ */
+ Trigger Misc5(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the Miscellaneous 6 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to. Defaults to the
+ * CommandScheduler's default loop.
+ * @return a Trigger instance representing the Miscellaneous 6 button's
+ * digital signal attached to the given loop.
+ */
+ Trigger Misc6(frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the axis value of the left trigger.
+ * The returned Trigger will be true when the axis value is greater than
+ * {@code threshold}.
+ *
+ * @param threshold the minimum axis value for the returned Trigger to be
+ * true. This value should be in the range [0, 1] where 0 is the unpressed
+ * state of the axis. Defaults to 0.5.
+ * @param loop the event loop instance to attach the Trigger to. Defaults to
+ * the CommandScheduler's default loop.
+ * @return a Trigger instance that is true when the left trigger's axis
+ * exceeds the provided threshold, attached to the given loop
+ */
+ Trigger LeftTrigger(double threshold = 0.5,
+ frc::EventLoop* loop = CommandScheduler::GetInstance()
+ .GetDefaultButtonLoop()) const;
+
+ /**
+ * Constructs a Trigger instance around the axis value of the right trigger.
+ * The returned Trigger will be true when the axis value is greater than
+ * {@code threshold}.
+ *
+ * @param threshold the minimum axis value for the returned Trigger to be
+ * true. This value should be in the range [0, 1] where 0 is the unpressed
+ * state of the axis. Defaults to 0.5.
+ * @param loop the event loop instance to attach the Trigger to. Defaults to
+ * the CommandScheduler's default loop.
+ * @return a Trigger instance that is true when the right trigger's axis
+ * exceeds the provided threshold, attached to the given loop
+ */
+ Trigger RightTrigger(
+ double threshold = 0.5,
+ frc::EventLoop* loop =
+ CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;
+
+ /**
+ * Get the X axis value of left side of the controller. Right is positive.
+ *
+ * @return The axis value.
+ */
+ double GetLeftX() const;
+
+ /**
+ * Get the Y axis value of left side of the controller. Back is positive.
+ *
+ * @return The axis value.
+ */
+ double GetLeftY() const;
+
+ /**
+ * Get the X axis value of right side of the controller. Right is positive.
+ *
+ * @return The axis value.
+ */
+ double GetRightX() const;
+
+ /**
+ * Get the Y axis value of right side of the controller. Back is positive.
+ *
+ * @return The axis value.
+ */
+ double GetRightY() const;
+
+ /**
+ * Get the left trigger axis value of the controller. Note that this axis is
+ * bound to the range of [0, 1] as opposed to the usual [-1, 1].
+ *
+ * @return The axis value.
+ */
+ double GetLeftTriggerAxis() const;
+
+ /**
+ * Get the right trigger axis value of the controller. Note that this axis is
+ * bound to the range of [0, 1] as opposed to the usual [-1, 1].
+ *
+ * @return The axis value.
+ */
+ double GetRightTriggerAxis() const;
+
+ private:
+ frc::Gamepad m_hid;
+};
+} // namespace frc2
diff --git a/wpilibc/src/generate/main/native/cpp/simulation/hidsim.cpp.jinja b/wpilibc/src/generate/main/native/cpp/simulation/hidsim.cpp.jinja
index 576b9ba139..944fd93f40 100644
--- a/wpilibc/src/generate/main/native/cpp/simulation/hidsim.cpp.jinja
+++ b/wpilibc/src/generate/main/native/cpp/simulation/hidsim.cpp.jinja
@@ -15,15 +15,15 @@ using namespace frc::sim;
{{ ConsoleName }}ControllerSim::{{ ConsoleName }}ControllerSim(const {{ ConsoleName }}Controller& joystick)
: GenericHIDSim{joystick} {
- SetAxisCount({{ sticks|length + triggers|length }});
- SetButtonCount({{ buttons|length }});
- SetPOVCount(1);
+ SetAxesMaximumIndex({{ sticks|length + triggers|length }});
+ SetButtonsMaximumIndex({{ buttons|length }});
+ SetPOVsMaximumIndex(1);
}
{{ ConsoleName }}ControllerSim::{{ ConsoleName }}ControllerSim(int port) : GenericHIDSim{port} {
- SetAxisCount({{ sticks|length + triggers|length }});
- SetButtonCount({{ buttons|length }});
- SetPOVCount(1);
+ SetAxesMaximumIndex({{ sticks|length + triggers|length }});
+ SetButtonsMaximumIndex({{ buttons|length }});
+ SetPOVsMaximumIndex(1);
}
{% for stick in sticks %}
void {{ ConsoleName }}ControllerSim::Set{{ stick.NameParts|map("capitalize")|join }}(double value) {
diff --git a/wpilibc/src/generated/main/native/cpp/simulation/PS4ControllerSim.cpp b/wpilibc/src/generated/main/native/cpp/simulation/PS4ControllerSim.cpp
index 9088e42fb7..61ee94da07 100644
--- a/wpilibc/src/generated/main/native/cpp/simulation/PS4ControllerSim.cpp
+++ b/wpilibc/src/generated/main/native/cpp/simulation/PS4ControllerSim.cpp
@@ -13,15 +13,15 @@ using namespace frc::sim;
PS4ControllerSim::PS4ControllerSim(const PS4Controller& joystick)
: GenericHIDSim{joystick} {
- SetAxisCount(6);
- SetButtonCount(14);
- SetPOVCount(1);
+ SetAxesMaximumIndex(6);
+ SetButtonsMaximumIndex(14);
+ SetPOVsMaximumIndex(1);
}
PS4ControllerSim::PS4ControllerSim(int port) : GenericHIDSim{port} {
- SetAxisCount(6);
- SetButtonCount(14);
- SetPOVCount(1);
+ SetAxesMaximumIndex(6);
+ SetButtonsMaximumIndex(14);
+ SetPOVsMaximumIndex(1);
}
void PS4ControllerSim::SetLeftX(double value) {
diff --git a/wpilibc/src/generated/main/native/cpp/simulation/PS5ControllerSim.cpp b/wpilibc/src/generated/main/native/cpp/simulation/PS5ControllerSim.cpp
index 4ee55db6d7..6ab901d6fe 100644
--- a/wpilibc/src/generated/main/native/cpp/simulation/PS5ControllerSim.cpp
+++ b/wpilibc/src/generated/main/native/cpp/simulation/PS5ControllerSim.cpp
@@ -13,15 +13,15 @@ using namespace frc::sim;
PS5ControllerSim::PS5ControllerSim(const PS5Controller& joystick)
: GenericHIDSim{joystick} {
- SetAxisCount(6);
- SetButtonCount(14);
- SetPOVCount(1);
+ SetAxesMaximumIndex(6);
+ SetButtonsMaximumIndex(14);
+ SetPOVsMaximumIndex(1);
}
PS5ControllerSim::PS5ControllerSim(int port) : GenericHIDSim{port} {
- SetAxisCount(6);
- SetButtonCount(14);
- SetPOVCount(1);
+ SetAxesMaximumIndex(6);
+ SetButtonsMaximumIndex(14);
+ SetPOVsMaximumIndex(1);
}
void PS5ControllerSim::SetLeftX(double value) {
diff --git a/wpilibc/src/generated/main/native/cpp/simulation/StadiaControllerSim.cpp b/wpilibc/src/generated/main/native/cpp/simulation/StadiaControllerSim.cpp
index 73f4a504e0..969ac07be6 100644
--- a/wpilibc/src/generated/main/native/cpp/simulation/StadiaControllerSim.cpp
+++ b/wpilibc/src/generated/main/native/cpp/simulation/StadiaControllerSim.cpp
@@ -13,15 +13,15 @@ using namespace frc::sim;
StadiaControllerSim::StadiaControllerSim(const StadiaController& joystick)
: GenericHIDSim{joystick} {
- SetAxisCount(4);
- SetButtonCount(15);
- SetPOVCount(1);
+ SetAxesMaximumIndex(4);
+ SetButtonsMaximumIndex(15);
+ SetPOVsMaximumIndex(1);
}
StadiaControllerSim::StadiaControllerSim(int port) : GenericHIDSim{port} {
- SetAxisCount(4);
- SetButtonCount(15);
- SetPOVCount(1);
+ SetAxesMaximumIndex(4);
+ SetButtonsMaximumIndex(15);
+ SetPOVsMaximumIndex(1);
}
void StadiaControllerSim::SetLeftX(double value) {
diff --git a/wpilibc/src/generated/main/native/cpp/simulation/XboxControllerSim.cpp b/wpilibc/src/generated/main/native/cpp/simulation/XboxControllerSim.cpp
index 0fe5675a56..fda0e5b87c 100644
--- a/wpilibc/src/generated/main/native/cpp/simulation/XboxControllerSim.cpp
+++ b/wpilibc/src/generated/main/native/cpp/simulation/XboxControllerSim.cpp
@@ -13,15 +13,15 @@ using namespace frc::sim;
XboxControllerSim::XboxControllerSim(const XboxController& joystick)
: GenericHIDSim{joystick} {
- SetAxisCount(6);
- SetButtonCount(10);
- SetPOVCount(1);
+ SetAxesMaximumIndex(6);
+ SetButtonsMaximumIndex(10);
+ SetPOVsMaximumIndex(1);
}
XboxControllerSim::XboxControllerSim(int port) : GenericHIDSim{port} {
- SetAxisCount(6);
- SetButtonCount(10);
- SetPOVCount(1);
+ SetAxesMaximumIndex(6);
+ SetButtonsMaximumIndex(10);
+ SetPOVsMaximumIndex(1);
}
void XboxControllerSim::SetLeftX(double value) {
diff --git a/wpilibc/src/generated/main/native/include/frc/PS4Controller.h b/wpilibc/src/generated/main/native/include/frc/PS4Controller.h
index 01e8c49c47..71f34687a1 100644
--- a/wpilibc/src/generated/main/native/include/frc/PS4Controller.h
+++ b/wpilibc/src/generated/main/native/include/frc/PS4Controller.h
@@ -557,33 +557,33 @@ class PS4Controller : public GenericHID,
/** Represents a digital button on an PS4Controller. */
struct Button {
/// Square button.
- static constexpr int kSquare = 1;
+ static constexpr int kSquare = 0;
/// Cross button.
- static constexpr int kCross = 2;
+ static constexpr int kCross = 1;
/// Circle button.
- static constexpr int kCircle = 3;
+ static constexpr int kCircle = 2;
/// Triangle button.
- static constexpr int kTriangle = 4;
+ static constexpr int kTriangle = 3;
/// Left trigger 1 button.
- static constexpr int kL1 = 5;
+ static constexpr int kL1 = 4;
/// Right trigger 1 button.
- static constexpr int kR1 = 6;
+ static constexpr int kR1 = 5;
/// Left trigger 2 button.
- static constexpr int kL2 = 7;
+ static constexpr int kL2 = 6;
/// Right trigger 2 button.
- static constexpr int kR2 = 8;
+ static constexpr int kR2 = 7;
/// Share button.
- static constexpr int kShare = 9;
+ static constexpr int kShare = 8;
/// Options button.
- static constexpr int kOptions = 10;
+ static constexpr int kOptions = 9;
/// L3 (left stick) button.
- static constexpr int kL3 = 11;
+ static constexpr int kL3 = 10;
/// R3 (right stick) button.
- static constexpr int kR3 = 12;
+ static constexpr int kR3 = 11;
/// PlayStation button.
- static constexpr int kPS = 13;
+ static constexpr int kPS = 12;
/// Touchpad button.
- static constexpr int kTouchpad = 14;
+ static constexpr int kTouchpad = 13;
};
/** Represents an axis on an PS4Controller. */
diff --git a/wpilibc/src/generated/main/native/include/frc/PS5Controller.h b/wpilibc/src/generated/main/native/include/frc/PS5Controller.h
index 2fd6557e25..e9048bb49b 100644
--- a/wpilibc/src/generated/main/native/include/frc/PS5Controller.h
+++ b/wpilibc/src/generated/main/native/include/frc/PS5Controller.h
@@ -557,33 +557,33 @@ class PS5Controller : public GenericHID,
/** Represents a digital button on an PS5Controller. */
struct Button {
/// Square button.
- static constexpr int kSquare = 1;
+ static constexpr int kSquare = 0;
/// Cross button.
- static constexpr int kCross = 2;
+ static constexpr int kCross = 1;
/// Circle button.
- static constexpr int kCircle = 3;
+ static constexpr int kCircle = 2;
/// Triangle button.
- static constexpr int kTriangle = 4;
+ static constexpr int kTriangle = 3;
/// Left trigger 1 button.
- static constexpr int kL1 = 5;
+ static constexpr int kL1 = 4;
/// Right trigger 1 button.
- static constexpr int kR1 = 6;
+ static constexpr int kR1 = 5;
/// Left trigger 2 button.
- static constexpr int kL2 = 7;
+ static constexpr int kL2 = 6;
/// Right trigger 2 button.
- static constexpr int kR2 = 8;
+ static constexpr int kR2 = 7;
/// Create button.
- static constexpr int kCreate = 9;
+ static constexpr int kCreate = 8;
/// Options button.
- static constexpr int kOptions = 10;
+ static constexpr int kOptions = 9;
/// L3 (left stick) button.
- static constexpr int kL3 = 11;
+ static constexpr int kL3 = 10;
/// R3 (right stick) button.
- static constexpr int kR3 = 12;
+ static constexpr int kR3 = 11;
/// PlayStation button.
- static constexpr int kPS = 13;
+ static constexpr int kPS = 12;
/// Touchpad button.
- static constexpr int kTouchpad = 14;
+ static constexpr int kTouchpad = 13;
};
/** Represents an axis on an PS5Controller. */
diff --git a/wpilibc/src/generated/main/native/include/frc/StadiaController.h b/wpilibc/src/generated/main/native/include/frc/StadiaController.h
index 89b7dab339..b159c35279 100644
--- a/wpilibc/src/generated/main/native/include/frc/StadiaController.h
+++ b/wpilibc/src/generated/main/native/include/frc/StadiaController.h
@@ -606,35 +606,35 @@ class StadiaController : public GenericHID,
/** Represents a digital button on an StadiaController. */
struct Button {
/// A button.
- static constexpr int kA = 1;
+ static constexpr int kA = 0;
/// B button.
- static constexpr int kB = 2;
+ static constexpr int kB = 1;
/// X button.
- static constexpr int kX = 3;
+ static constexpr int kX = 2;
/// Y button.
- static constexpr int kY = 4;
+ static constexpr int kY = 3;
/// Left bumper button.
- static constexpr int kLeftBumper = 5;
+ static constexpr int kLeftBumper = 4;
/// Right bumper button.
- static constexpr int kRightBumper = 6;
+ static constexpr int kRightBumper = 5;
/// Left stick button.
- static constexpr int kLeftStick = 7;
+ static constexpr int kLeftStick = 6;
/// Right stick button.
- static constexpr int kRightStick = 8;
+ static constexpr int kRightStick = 7;
/// Ellipses button.
- static constexpr int kEllipses = 9;
+ static constexpr int kEllipses = 8;
/// Hamburger button.
- static constexpr int kHamburger = 10;
+ static constexpr int kHamburger = 9;
/// Stadia button.
- static constexpr int kStadia = 11;
+ static constexpr int kStadia = 10;
/// Right trigger button.
- static constexpr int kRightTrigger = 12;
+ static constexpr int kRightTrigger = 11;
/// Left trigger button.
- static constexpr int kLeftTrigger = 13;
+ static constexpr int kLeftTrigger = 12;
/// Google button.
- static constexpr int kGoogle = 14;
+ static constexpr int kGoogle = 13;
/// Frame button.
- static constexpr int kFrame = 15;
+ static constexpr int kFrame = 14;
};
/** Represents an axis on an StadiaController. */
diff --git a/wpilibc/src/generated/main/native/include/frc/XboxController.h b/wpilibc/src/generated/main/native/include/frc/XboxController.h
index e69f9bdb02..1880e01f2d 100644
--- a/wpilibc/src/generated/main/native/include/frc/XboxController.h
+++ b/wpilibc/src/generated/main/native/include/frc/XboxController.h
@@ -511,25 +511,25 @@ class XboxController : public GenericHID,
/** Represents a digital button on an XboxController. */
struct Button {
/// A button.
- static constexpr int kA = 1;
+ static constexpr int kA = 0;
/// B button.
- static constexpr int kB = 2;
+ static constexpr int kB = 1;
/// X button.
- static constexpr int kX = 3;
+ static constexpr int kX = 2;
/// Y button.
- static constexpr int kY = 4;
+ static constexpr int kY = 3;
/// Left bumper button.
- static constexpr int kLeftBumper = 5;
+ static constexpr int kLeftBumper = 4;
/// Right bumper button.
- static constexpr int kRightBumper = 6;
+ static constexpr int kRightBumper = 5;
/// Back button.
- static constexpr int kBack = 7;
+ static constexpr int kBack = 6;
/// Start button.
- static constexpr int kStart = 8;
+ static constexpr int kStart = 7;
/// Left stick button.
- static constexpr int kLeftStick = 9;
+ static constexpr int kLeftStick = 8;
/// Right stick button.
- static constexpr int kRightStick = 10;
+ static constexpr int kRightStick = 9;
};
/** Represents an axis on an XboxController. */
diff --git a/wpilibc/src/main/native/cpp/DriverStation.cpp b/wpilibc/src/main/native/cpp/DriverStation.cpp
index 6aa5f57b40..1d03210bd9 100644
--- a/wpilibc/src/main/native/cpp/DriverStation.cpp
+++ b/wpilibc/src/main/native/cpp/DriverStation.cpp
@@ -35,6 +35,10 @@
using namespace frc;
+static constexpr int availableToCount(uint64_t available) {
+ return 64 - std::countl_zero(available);
+}
+
namespace {
// A simple class which caches the previous value written to an NT entry
// Used to prevent redundant, repeated writes of the same value
@@ -157,14 +161,6 @@ static Instance& GetInstance() {
static void SendMatchData();
-/**
- * Reports errors related to unplugged joysticks.
- *
- * Throttles the errors so that they don't overwhelm the DS.
- */
-static void ReportJoystickUnpluggedErrorV(fmt::string_view format,
- fmt::format_args args);
-
template
static inline void ReportJoystickUnpluggedError(const S& format,
Args&&... args) {
@@ -193,7 +189,7 @@ Instance::Instance() {
for (unsigned int i = 0; i < DriverStation::kJoystickPorts; i++) {
joystickButtonsPressed[i] = 0;
joystickButtonsReleased[i] = 0;
- previousButtonStates[i].count = 0;
+ previousButtonStates[i].available = 0;
previousButtonStates[i].buttons = 0;
}
}
@@ -209,24 +205,49 @@ bool DriverStation::GetStickButton(int stick, int button) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
return false;
}
- if (button <= 0) {
- ReportJoystickUnpluggedError(
- "Joystick Button {} index out of range; indexes begin at 1", button);
+ if (button < 0 || button >= 64) {
+ FRC_ReportError(warn::BadJoystickIndex, "button {} out of range", button);
return false;
}
+ uint64_t mask = 1LLU << button;
+
HAL_JoystickButtons buttons;
HAL_GetJoystickButtons(stick, &buttons);
- if (button > buttons.count) {
+ if ((buttons.available & mask) == 0) {
ReportJoystickUnpluggedWarning(
- "Joystick Button {} missing (max {}), check if all controllers are "
+ "Joystick Button {} missing (available {}), check if all controllers "
+ "are "
"plugged in",
- button, buttons.count);
+ button, buttons.available);
return false;
}
- return buttons.buttons & 1 << (button - 1);
+ return (buttons.buttons & mask) != 0;
+}
+
+std::optional DriverStation::GetStickButtonIfAvailable(int stick,
+ int button) {
+ if (stick < 0 || stick >= kJoystickPorts) {
+ FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
+ return false;
+ }
+ if (button < 0 || button >= 64) {
+ FRC_ReportError(warn::BadJoystickIndex, "button {} out of range", button);
+ return false;
+ }
+
+ uint64_t mask = 1LLU << button;
+
+ HAL_JoystickButtons buttons;
+ HAL_GetJoystickButtons(stick, &buttons);
+
+ if ((buttons.available & mask) == 0) {
+ return std::nullopt;
+ }
+
+ return (buttons.buttons & mask) != 0;
}
bool DriverStation::GetStickButtonPressed(int stick, int button) {
@@ -234,27 +255,29 @@ bool DriverStation::GetStickButtonPressed(int stick, int button) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
return false;
}
- if (button <= 0) {
- ReportJoystickUnpluggedError(
- "Joystick Button {} index out of range; indexes begin at 1", button);
+ if (button < 0 || button >= 64) {
+ FRC_ReportError(warn::BadJoystickIndex, "button {} out of range", button);
return false;
}
HAL_JoystickButtons buttons;
HAL_GetJoystickButtons(stick, &buttons);
- if (button > buttons.count) {
+ uint64_t mask = 1LLU << button;
+
+ if ((buttons.available & mask) == 0) {
ReportJoystickUnpluggedWarning(
- "Joystick Button {} missing (max {}), check if all controllers are "
+ "Joystick Button {} missing (available {}), check if all controllers "
+ "are "
"plugged in",
- button, buttons.count);
+ button, buttons.available);
return false;
}
auto& inst = ::GetInstance();
std::unique_lock lock(inst.buttonEdgeMutex);
// If button was pressed, clear flag and return true
- if (inst.joystickButtonsPressed[stick] & 1 << (button - 1)) {
- inst.joystickButtonsPressed[stick] &= ~(1 << (button - 1));
+ if (inst.joystickButtonsPressed[stick] & mask) {
+ inst.joystickButtonsPressed[stick] &= ~mask;
return true;
}
return false;
@@ -265,27 +288,29 @@ bool DriverStation::GetStickButtonReleased(int stick, int button) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
return false;
}
- if (button <= 0) {
- ReportJoystickUnpluggedError(
- "Joystick Button {} index out of range; indexes begin at 1", button);
+ if (button < 0 || button >= 64) {
+ FRC_ReportError(warn::BadJoystickIndex, "button {} out of range", button);
return false;
}
HAL_JoystickButtons buttons;
HAL_GetJoystickButtons(stick, &buttons);
- if (button > buttons.count) {
+ uint64_t mask = 1LLU << button;
+
+ if ((buttons.available & mask) == 0) {
ReportJoystickUnpluggedWarning(
- "Joystick Button {} missing (max {}), check if all controllers are "
+ "Joystick Button {} missing (available {}), check if all controllers "
+ "are "
"plugged in",
- button, buttons.count);
+ button, buttons.available);
return false;
}
auto& inst = ::GetInstance();
std::unique_lock lock(inst.buttonEdgeMutex);
// If button was released, clear flag and return true
- if (inst.joystickButtonsReleased[stick] & 1 << (button - 1)) {
- inst.joystickButtonsReleased[stick] &= ~(1 << (button - 1));
+ if (inst.joystickButtonsReleased[stick] & mask) {
+ inst.joystickButtonsReleased[stick] &= ~mask;
return true;
}
return false;
@@ -301,20 +326,45 @@ double DriverStation::GetStickAxis(int stick, int axis) {
return 0.0;
}
+ uint16_t mask = 1 << axis;
+
HAL_JoystickAxes axes;
HAL_GetJoystickAxes(stick, &axes);
- if (axis >= axes.count) {
+ if ((axes.available & mask) == 0) {
ReportJoystickUnpluggedWarning(
- "Joystick Axis {} missing (max {}), check if all controllers are "
+ "Joystick Axis {} missing (available {}), check if all controllers are "
"plugged in",
- axis, axes.count);
+ axis, axes.available);
return 0.0;
}
return axes.axes[axis];
}
+std::optional DriverStation::GetStickAxisIfAvailable(int stick,
+ int axis) {
+ if (stick < 0 || stick >= kJoystickPorts) {
+ FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
+ return 0.0;
+ }
+ if (axis < 0 || axis >= HAL_kMaxJoystickAxes) {
+ FRC_ReportError(warn::BadJoystickAxis, "axis {} out of range", axis);
+ return 0.0;
+ }
+
+ uint16_t mask = 1 << axis;
+
+ HAL_JoystickAxes axes;
+ HAL_GetJoystickAxes(stick, &axes);
+
+ if ((axes.available & mask) == 0) {
+ return std::nullopt;
+ }
+
+ return axes.axes[axis];
+}
+
DriverStation::POVDirection DriverStation::GetStickPOV(int stick, int pov) {
if (stick < 0 || stick >= kJoystickPorts) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
@@ -325,21 +375,23 @@ DriverStation::POVDirection DriverStation::GetStickPOV(int stick, int pov) {
return kCenter;
}
+ uint16_t mask = 1 << pov;
+
HAL_JoystickPOVs povs;
HAL_GetJoystickPOVs(stick, &povs);
- if (pov >= povs.count) {
+ if ((povs.available & mask) == 0) {
ReportJoystickUnpluggedWarning(
- "Joystick POV {} missing (max {}), check if all controllers are "
+ "Joystick POV {} missing (available {}), check if all controllers are "
"plugged in",
- pov, povs.count);
+ pov, povs.available);
return kCenter;
}
return static_cast(povs.povs[pov]);
}
-int DriverStation::GetStickButtons(int stick) {
+uint64_t DriverStation::GetStickButtons(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
return 0;
@@ -351,7 +403,11 @@ int DriverStation::GetStickButtons(int stick) {
return buttons.buttons;
}
-int DriverStation::GetStickAxisCount(int stick) {
+int DriverStation::GetStickAxesMaximumIndex(int stick) {
+ return availableToCount(GetStickAxesAvailable(stick));
+}
+
+int DriverStation::GetStickAxesAvailable(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
return 0;
@@ -360,10 +416,14 @@ int DriverStation::GetStickAxisCount(int stick) {
HAL_JoystickAxes axes;
HAL_GetJoystickAxes(stick, &axes);
- return axes.count;
+ return axes.available;
}
-int DriverStation::GetStickPOVCount(int stick) {
+int DriverStation::GetStickPOVsMaximumIndex(int stick) {
+ return availableToCount(GetStickPOVsAvailable(stick));
+}
+
+int DriverStation::GetStickPOVsAvailable(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
return 0;
@@ -372,10 +432,14 @@ int DriverStation::GetStickPOVCount(int stick) {
HAL_JoystickPOVs povs;
HAL_GetJoystickPOVs(stick, &povs);
- return povs.count;
+ return povs.available;
}
-int DriverStation::GetStickButtonCount(int stick) {
+int DriverStation::GetStickButtonsMaximumIndex(int stick) {
+ return availableToCount(GetStickButtonsAvailable(stick));
+}
+
+uint64_t DriverStation::GetStickButtonsAvailable(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
return 0;
@@ -384,7 +448,7 @@ int DriverStation::GetStickButtonCount(int stick) {
HAL_JoystickButtons buttons;
HAL_GetJoystickButtons(stick, &buttons);
- return buttons.count;
+ return buttons.available;
}
bool DriverStation::GetJoystickIsGamepad(int stick) {
@@ -422,25 +486,10 @@ std::string DriverStation::GetJoystickName(int stick) {
return descriptor.name;
}
-int DriverStation::GetJoystickAxisType(int stick, int axis) {
- if (stick < 0 || stick >= kJoystickPorts) {
- FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
- return -1;
- }
- if (axis < 0 || axis >= HAL_kMaxJoystickAxes) {
- FRC_ReportError(warn::BadJoystickAxis, "axis {} out of range", axis);
- return -1;
- }
-
- HAL_JoystickDescriptor descriptor;
- HAL_GetJoystickDescriptor(stick, &descriptor);
-
- return descriptor.axisTypes[axis];
-}
-
bool DriverStation::IsJoystickConnected(int stick) {
- return GetStickAxisCount(stick) > 0 || GetStickButtonCount(stick) > 0 ||
- GetStickPOVCount(stick) > 0;
+ return GetStickAxesAvailable(stick) != 0 ||
+ GetStickButtonsAvailable(stick) != 0 ||
+ GetStickPOVsAvailable(stick) != 0;
}
bool DriverStation::IsEnabled() {
@@ -661,16 +710,6 @@ void DriverStation::StartDataLog(wpi::log::DataLog& log, bool logJoysticks) {
}
}
-void ReportJoystickUnpluggedErrorV(fmt::string_view format,
- fmt::format_args args) {
- auto& inst = GetInstance();
- auto currentTime = Timer::GetTimestamp();
- if (currentTime > inst.nextMessageTime) {
- ReportErrorV(err::Error, "", 0, "", format, args);
- inst.nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;
- }
-}
-
void ReportJoystickUnpluggedWarningV(fmt::string_view format,
fmt::format_args args) {
auto& inst = GetInstance();
@@ -751,9 +790,9 @@ void JoystickLogSender::Init(wpi::log::DataLog& log, unsigned int stick,
HAL_GetJoystickAxes(m_stick, &m_prevAxes);
HAL_GetJoystickPOVs(m_stick, &m_prevPOVs);
AppendButtons(m_prevButtons, timestamp);
+ int axesCount = availableToCount(m_prevAxes.available);
m_logAxes.Append(
- std::span{m_prevAxes.axes,
- static_cast(m_prevAxes.count)},
+ std::span{m_prevAxes.axes, static_cast(axesCount)},
timestamp);
AppendPOVs(m_prevPOVs, timestamp);
}
@@ -761,7 +800,7 @@ void JoystickLogSender::Init(wpi::log::DataLog& log, unsigned int stick,
void JoystickLogSender::Send(uint64_t timestamp) {
HAL_JoystickButtons buttons;
HAL_GetJoystickButtons(m_stick, &buttons);
- if (buttons.count != m_prevButtons.count ||
+ if (buttons.available != m_prevButtons.available ||
buttons.buttons != m_prevButtons.buttons) {
AppendButtons(buttons, timestamp);
}
@@ -769,20 +808,22 @@ void JoystickLogSender::Send(uint64_t timestamp) {
HAL_JoystickAxes axes;
HAL_GetJoystickAxes(m_stick, &axes);
- if (axes.count != m_prevAxes.count ||
+ int axesCount = availableToCount(axes.available);
+ if (axes.available != m_prevAxes.available ||
std::memcmp(axes.axes, m_prevAxes.axes,
- sizeof(axes.axes[0]) * axes.count) != 0) {
+ sizeof(axes.axes[0]) * axesCount) != 0) {
m_logAxes.Append(
- std::span{axes.axes, static_cast(axes.count)},
+ std::span{axes.axes, static_cast(axesCount)},
timestamp);
}
m_prevAxes = axes;
HAL_JoystickPOVs povs;
HAL_GetJoystickPOVs(m_stick, &povs);
- if (povs.count != m_prevPOVs.count ||
+ int povsCount = availableToCount(povs.available);
+ if (povs.available != m_prevPOVs.available ||
std::memcmp(povs.povs, m_prevPOVs.povs,
- sizeof(povs.povs[0]) * povs.count) != 0) {
+ sizeof(povs.povs[0]) * povsCount) != 0) {
AppendPOVs(povs, timestamp);
}
m_prevPOVs = povs;
@@ -790,23 +831,25 @@ void JoystickLogSender::Send(uint64_t timestamp) {
void JoystickLogSender::AppendButtons(HAL_JoystickButtons buttons,
uint64_t timestamp) {
- uint8_t buttonsArr[32];
- for (unsigned int i = 0; i < buttons.count; ++i) {
- buttonsArr[i] = (buttons.buttons & (1u << i)) != 0;
+ int count = availableToCount(buttons.available);
+ uint8_t buttonsArr[64];
+ for (int i = 0; i < count; ++i) {
+ buttonsArr[i] = (buttons.buttons & (1llu << i)) != 0;
}
- m_logButtons.Append(std::span{buttonsArr, buttons.count},
- timestamp);
+ m_logButtons.Append(
+ std::span{buttonsArr, static_cast(count)},
+ timestamp);
}
void JoystickLogSender::AppendPOVs(const HAL_JoystickPOVs& povs,
uint64_t timestamp) {
+ int count = availableToCount(povs.available);
int64_t povsArr[HAL_kMaxJoystickPOVs];
- for (int i = 0; i < povs.count; ++i) {
+ for (int i = 0; i < count; ++i) {
povsArr[i] = povs.povs[i];
}
m_logPOVs.Append(
- std::span{povsArr, static_cast(povs.count)},
- timestamp);
+ std::span{povsArr, static_cast(count)}, timestamp);
}
void DataLogSender::Init(wpi::log::DataLog& log, bool logJoysticks,
diff --git a/wpilibc/src/main/native/cpp/Gamepad.cpp b/wpilibc/src/main/native/cpp/Gamepad.cpp
new file mode 100644
index 0000000000..b215c8b528
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Gamepad.cpp
@@ -0,0 +1,582 @@
+// 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.
+
+#include "frc/Gamepad.h"
+
+#include
+#include
+
+#include "frc/event/BooleanEvent.h"
+
+using namespace frc;
+
+Gamepad::Gamepad(int port) : GenericHID(port) {
+ HAL_ReportUsage("HID", port, "Gamepad");
+}
+
+double Gamepad::GetLeftX() const {
+ return GetRawAxis(Axis::kLeftX);
+}
+
+double Gamepad::GetLeftY() const {
+ return GetRawAxis(Axis::kLeftY);
+}
+
+double Gamepad::GetRightX() const {
+ return GetRawAxis(Axis::kRightX);
+}
+
+double Gamepad::GetRightY() const {
+ return GetRawAxis(Axis::kRightY);
+}
+
+double Gamepad::GetLeftTriggerAxis() const {
+ return GetRawAxis(Axis::kLeftTrigger);
+}
+
+BooleanEvent Gamepad::LeftTrigger(double threshold, EventLoop* loop) const {
+ return BooleanEvent(loop, [this, threshold] {
+ return this->GetLeftTriggerAxis() > threshold;
+ });
+}
+
+BooleanEvent Gamepad::LeftTrigger(EventLoop* loop) const {
+ return this->LeftTrigger(0.5, loop);
+}
+
+double Gamepad::GetRightTriggerAxis() const {
+ return GetRawAxis(Axis::kRightTrigger);
+}
+
+BooleanEvent Gamepad::RightTrigger(double threshold, EventLoop* loop) const {
+ return BooleanEvent(loop, [this, threshold] {
+ return this->GetRightTriggerAxis() > threshold;
+ });
+}
+
+BooleanEvent Gamepad::RightTrigger(EventLoop* loop) const {
+ return this->RightTrigger(0.5, loop);
+}
+
+bool Gamepad::GetSouthFaceButton() const {
+ return GetRawButton(Button::kSouthFace);
+}
+
+bool Gamepad::GetSouthFaceButtonPressed() {
+ return GetRawButtonPressed(Button::kSouthFace);
+}
+
+bool Gamepad::GetSouthFaceButtonReleased() {
+ return GetRawButtonReleased(Button::kSouthFace);
+}
+
+BooleanEvent Gamepad::SouthFace(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetSouthFaceButton(); });
+}
+
+bool Gamepad::GetEastFaceButton() const {
+ return GetRawButton(Button::kEastFace);
+}
+
+bool Gamepad::GetEastFaceButtonPressed() {
+ return GetRawButtonPressed(Button::kEastFace);
+}
+
+bool Gamepad::GetEastFaceButtonReleased() {
+ return GetRawButtonReleased(Button::kEastFace);
+}
+
+BooleanEvent Gamepad::EastFace(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetEastFaceButton(); });
+}
+
+bool Gamepad::GetWestFaceButton() const {
+ return GetRawButton(Button::kWestFace);
+}
+
+bool Gamepad::GetWestFaceButtonPressed() {
+ return GetRawButtonPressed(Button::kWestFace);
+}
+
+bool Gamepad::GetWestFaceButtonReleased() {
+ return GetRawButtonReleased(Button::kWestFace);
+}
+
+BooleanEvent Gamepad::WestFace(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetWestFaceButton(); });
+}
+
+bool Gamepad::GetNorthFacenButton() const {
+ return GetRawButton(Button::kNorthFacen);
+}
+
+bool Gamepad::GetNorthFacenButtonPressed() {
+ return GetRawButtonPressed(Button::kNorthFacen);
+}
+
+bool Gamepad::GetNorthFacenButtonReleased() {
+ return GetRawButtonReleased(Button::kNorthFacen);
+}
+
+BooleanEvent Gamepad::NorthFacen(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetNorthFacenButton(); });
+}
+
+bool Gamepad::GetBackButton() const {
+ return GetRawButton(Button::kBack);
+}
+
+bool Gamepad::GetBackButtonPressed() {
+ return GetRawButtonPressed(Button::kBack);
+}
+
+bool Gamepad::GetBackButtonReleased() {
+ return GetRawButtonReleased(Button::kBack);
+}
+
+BooleanEvent Gamepad::Back(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetBackButton(); });
+}
+
+bool Gamepad::GetGuideButton() const {
+ return GetRawButton(Button::kGuide);
+}
+
+bool Gamepad::GetGuideButtonPressed() {
+ return GetRawButtonPressed(Button::kGuide);
+}
+
+bool Gamepad::GetGuideButtonReleased() {
+ return GetRawButtonReleased(Button::kGuide);
+}
+
+BooleanEvent Gamepad::Guide(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetGuideButton(); });
+}
+
+bool Gamepad::GetStartButton() const {
+ return GetRawButton(Button::kStart);
+}
+
+bool Gamepad::GetStartButtonPressed() {
+ return GetRawButtonPressed(Button::kStart);
+}
+
+bool Gamepad::GetStartButtonReleased() {
+ return GetRawButtonReleased(Button::kStart);
+}
+
+BooleanEvent Gamepad::Start(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetStartButton(); });
+}
+
+bool Gamepad::GetLeftStickButton() const {
+ return GetRawButton(Button::kLeftStick);
+}
+
+bool Gamepad::GetLeftStickButtonPressed() {
+ return GetRawButtonPressed(Button::kLeftStick);
+}
+
+bool Gamepad::GetLeftStickButtonReleased() {
+ return GetRawButtonReleased(Button::kLeftStick);
+}
+
+BooleanEvent Gamepad::LeftStick(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetLeftStickButton(); });
+}
+
+bool Gamepad::GetRightStickButton() const {
+ return GetRawButton(Button::kRightStick);
+}
+
+bool Gamepad::GetRightStickButtonPressed() {
+ return GetRawButtonPressed(Button::kRightStick);
+}
+
+bool Gamepad::GetRightStickButtonReleased() {
+ return GetRawButtonReleased(Button::kRightStick);
+}
+
+BooleanEvent Gamepad::RightStick(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetRightStickButton(); });
+}
+
+bool Gamepad::GetLeftShoulderButton() const {
+ return GetRawButton(Button::kLeftShoulder);
+}
+
+bool Gamepad::GetLeftShoulderButtonPressed() {
+ return GetRawButtonPressed(Button::kLeftShoulder);
+}
+
+bool Gamepad::GetLeftShoulderButtonReleased() {
+ return GetRawButtonReleased(Button::kLeftShoulder);
+}
+
+BooleanEvent Gamepad::LeftShoulder(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetLeftShoulderButton(); });
+}
+
+bool Gamepad::GetRightShoulderButton() const {
+ return GetRawButton(Button::kRightShoulder);
+}
+
+bool Gamepad::GetRightShoulderButtonPressed() {
+ return GetRawButtonPressed(Button::kRightShoulder);
+}
+
+bool Gamepad::GetRightShoulderButtonReleased() {
+ return GetRawButtonReleased(Button::kRightShoulder);
+}
+
+BooleanEvent Gamepad::RightShoulder(EventLoop* loop) const {
+ return BooleanEvent(loop,
+ [this]() { return this->GetRightShoulderButton(); });
+}
+
+bool Gamepad::GetDpadUpButton() const {
+ return GetRawButton(Button::kDpadUp);
+}
+
+bool Gamepad::GetDpadUpButtonPressed() {
+ return GetRawButtonPressed(Button::kDpadUp);
+}
+
+bool Gamepad::GetDpadUpButtonReleased() {
+ return GetRawButtonReleased(Button::kDpadUp);
+}
+
+BooleanEvent Gamepad::DpadUp(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetDpadUpButton(); });
+}
+
+bool Gamepad::GetDpadDownButton() const {
+ return GetRawButton(Button::kDpadDown);
+}
+
+bool Gamepad::GetDpadDownButtonPressed() {
+ return GetRawButtonPressed(Button::kDpadDown);
+}
+
+bool Gamepad::GetDpadDownButtonReleased() {
+ return GetRawButtonReleased(Button::kDpadDown);
+}
+
+BooleanEvent Gamepad::DpadDown(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetDpadDownButton(); });
+}
+
+bool Gamepad::GetDpadLeftButton() const {
+ return GetRawButton(Button::kDpadLeft);
+}
+
+bool Gamepad::GetDpadLeftButtonPressed() {
+ return GetRawButtonPressed(Button::kDpadLeft);
+}
+
+bool Gamepad::GetDpadLeftButtonReleased() {
+ return GetRawButtonReleased(Button::kDpadLeft);
+}
+
+BooleanEvent Gamepad::DpadLeft(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetDpadLeftButton(); });
+}
+
+bool Gamepad::GetDpadRightButton() const {
+ return GetRawButton(Button::kDpadRight);
+}
+
+bool Gamepad::GetDpadRightButtonPressed() {
+ return GetRawButtonPressed(Button::kDpadRight);
+}
+
+bool Gamepad::GetDpadRightButtonReleased() {
+ return GetRawButtonReleased(Button::kDpadRight);
+}
+
+BooleanEvent Gamepad::DpadRight(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetDpadRightButton(); });
+}
+
+bool Gamepad::GetMisc1Button() const {
+ return GetRawButton(Button::kMisc1);
+}
+
+bool Gamepad::GetMisc1ButtonPressed() {
+ return GetRawButtonPressed(Button::kMisc1);
+}
+
+bool Gamepad::GetMisc1ButtonReleased() {
+ return GetRawButtonReleased(Button::kMisc1);
+}
+
+BooleanEvent Gamepad::Misc1(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetMisc1Button(); });
+}
+
+bool Gamepad::GetRightPaddle1Button() const {
+ return GetRawButton(Button::kRightPaddle1);
+}
+
+bool Gamepad::GetRightPaddle1ButtonPressed() {
+ return GetRawButtonPressed(Button::kRightPaddle1);
+}
+
+bool Gamepad::GetRightPaddle1ButtonReleased() {
+ return GetRawButtonReleased(Button::kRightPaddle1);
+}
+
+BooleanEvent Gamepad::RightPaddle1(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetRightPaddle1Button(); });
+}
+
+bool Gamepad::GetLeftPaddle1Button() const {
+ return GetRawButton(Button::kLeftPaddle1);
+}
+
+bool Gamepad::GetLeftPaddle1ButtonPressed() {
+ return GetRawButtonPressed(Button::kLeftPaddle1);
+}
+
+bool Gamepad::GetLeftPaddle1ButtonReleased() {
+ return GetRawButtonReleased(Button::kLeftPaddle1);
+}
+
+BooleanEvent Gamepad::LeftPaddle1(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetLeftPaddle1Button(); });
+}
+
+bool Gamepad::GetRightPaddle2Button() const {
+ return GetRawButton(Button::kRightPaddle2);
+}
+
+bool Gamepad::GetRightPaddle2ButtonPressed() {
+ return GetRawButtonPressed(Button::kRightPaddle2);
+}
+
+bool Gamepad::GetRightPaddle2ButtonReleased() {
+ return GetRawButtonReleased(Button::kRightPaddle2);
+}
+
+BooleanEvent Gamepad::RightPaddle2(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetRightPaddle2Button(); });
+}
+
+bool Gamepad::GetLeftPaddle2Button() const {
+ return GetRawButton(Button::kLeftPaddle2);
+}
+
+bool Gamepad::GetLeftPaddle2ButtonPressed() {
+ return GetRawButtonPressed(Button::kLeftPaddle2);
+}
+
+bool Gamepad::GetLeftPaddle2ButtonReleased() {
+ return GetRawButtonReleased(Button::kLeftPaddle2);
+}
+
+BooleanEvent Gamepad::LeftPaddle2(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetLeftPaddle2Button(); });
+}
+
+bool Gamepad::GetTouchpadButton() const {
+ return GetRawButton(Button::kTouchpad);
+}
+
+bool Gamepad::GetTouchpadButtonPressed() {
+ return GetRawButtonPressed(Button::kTouchpad);
+}
+
+bool Gamepad::GetTouchpadButtonReleased() {
+ return GetRawButtonReleased(Button::kTouchpad);
+}
+
+BooleanEvent Gamepad::Touchpad(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetTouchpadButton(); });
+}
+
+bool Gamepad::GetMisc2Button() const {
+ return GetRawButton(Button::kMisc2);
+}
+
+bool Gamepad::GetMisc2ButtonPressed() {
+ return GetRawButtonPressed(Button::kMisc2);
+}
+
+bool Gamepad::GetMisc2ButtonReleased() {
+ return GetRawButtonReleased(Button::kMisc2);
+}
+
+BooleanEvent Gamepad::Misc2(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetMisc2Button(); });
+}
+
+bool Gamepad::GetMisc3Button() const {
+ return GetRawButton(Button::kMisc3);
+}
+
+bool Gamepad::GetMisc3ButtonPressed() {
+ return GetRawButtonPressed(Button::kMisc3);
+}
+
+bool Gamepad::GetMisc3ButtonReleased() {
+ return GetRawButtonReleased(Button::kMisc3);
+}
+
+BooleanEvent Gamepad::Misc3(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetMisc3Button(); });
+}
+
+bool Gamepad::GetMisc4Button() const {
+ return GetRawButton(Button::kMisc4);
+}
+
+bool Gamepad::GetMisc4ButtonPressed() {
+ return GetRawButtonPressed(Button::kMisc4);
+}
+
+bool Gamepad::GetMisc4ButtonReleased() {
+ return GetRawButtonReleased(Button::kMisc4);
+}
+
+BooleanEvent Gamepad::Misc4(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetMisc4Button(); });
+}
+
+bool Gamepad::GetMisc5Button() const {
+ return GetRawButton(Button::kMisc5);
+}
+
+bool Gamepad::GetMisc5ButtonPressed() {
+ return GetRawButtonPressed(Button::kMisc5);
+}
+
+bool Gamepad::GetMisc5ButtonReleased() {
+ return GetRawButtonReleased(Button::kMisc5);
+}
+
+BooleanEvent Gamepad::Misc5(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetMisc5Button(); });
+}
+
+bool Gamepad::GetMisc6Button() const {
+ return GetRawButton(Button::kMisc6);
+}
+
+bool Gamepad::GetMisc6ButtonPressed() {
+ return GetRawButtonPressed(Button::kMisc6);
+}
+
+bool Gamepad::GetMisc6ButtonReleased() {
+ return GetRawButtonReleased(Button::kMisc6);
+}
+
+BooleanEvent Gamepad::Misc6(EventLoop* loop) const {
+ return BooleanEvent(loop, [this]() { return this->GetMisc6Button(); });
+}
+
+double Gamepad::GetAxisForSendable(int axis) const {
+ return DriverStation::GetStickAxisIfAvailable(GetPort(), axis).value_or(0.0);
+}
+
+bool Gamepad::GetButtonForSendable(int button) const {
+ return DriverStation::GetStickButtonIfAvailable(GetPort(), button)
+ .value_or(false);
+}
+
+void Gamepad::InitSendable(wpi::SendableBuilder& builder) {
+ builder.SetSmartDashboardType("HID");
+ builder.PublishConstString("ControllerType", "Gamepad");
+ builder.AddDoubleProperty(
+ "LeftTrigger Axis",
+ [this] { return GetAxisForSendable(Axis::kLeftTrigger); }, nullptr);
+ builder.AddDoubleProperty(
+ "RightTrigger Axis",
+ [this] { return GetAxisForSendable(Axis::kRightTrigger); }, nullptr);
+ builder.AddDoubleProperty(
+ "LeftX", [this] { return GetAxisForSendable(Axis::kLeftX); }, nullptr);
+ builder.AddDoubleProperty(
+ "LeftY", [this] { return GetAxisForSendable(Axis::kLeftY); }, nullptr);
+ builder.AddDoubleProperty(
+ "RightX", [this] { return GetAxisForSendable(Axis::kRightX); }, nullptr);
+ builder.AddDoubleProperty(
+ "RightY", [this] { return GetAxisForSendable(Axis::kRightY); }, nullptr);
+ builder.AddBooleanProperty(
+ "SouthFace", [this] { return GetButtonForSendable(Button::kSouthFace); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "EastFace", [this] { return GetButtonForSendable(Button::kEastFace); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "WestFace", [this] { return GetButtonForSendable(Button::kWestFace); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "NorthFacen",
+ [this] { return GetButtonForSendable(Button::kNorthFacen); }, nullptr);
+ builder.AddBooleanProperty(
+ "Back", [this] { return GetButtonForSendable(Button::kBack); }, nullptr);
+ builder.AddBooleanProperty(
+ "Guide", [this] { return GetButtonForSendable(Button::kGuide); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "Start", [this] { return GetButtonForSendable(Button::kStart); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "LeftStick", [this] { return GetButtonForSendable(Button::kLeftStick); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "RightStick",
+ [this] { return GetButtonForSendable(Button::kRightStick); }, nullptr);
+ builder.AddBooleanProperty(
+ "LeftShoulder",
+ [this] { return GetButtonForSendable(Button::kLeftShoulder); }, nullptr);
+ builder.AddBooleanProperty(
+ "RightShoulder",
+ [this] { return GetButtonForSendable(Button::kRightShoulder); }, nullptr);
+ builder.AddBooleanProperty(
+ "DpadUp", [this] { return GetButtonForSendable(Button::kDpadUp); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "DpadDown", [this] { return GetButtonForSendable(Button::kDpadDown); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "DpadLeft", [this] { return GetButtonForSendable(Button::kDpadLeft); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "DpadRight", [this] { return GetButtonForSendable(Button::kDpadRight); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "Misc1", [this] { return GetButtonForSendable(Button::kMisc1); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "RightPaddle1",
+ [this] { return GetButtonForSendable(Button::kRightPaddle1); }, nullptr);
+ builder.AddBooleanProperty(
+ "LeftPaddle1",
+ [this] { return GetButtonForSendable(Button::kLeftPaddle1); }, nullptr);
+ builder.AddBooleanProperty(
+ "RightPaddle2",
+ [this] { return GetButtonForSendable(Button::kRightPaddle2); }, nullptr);
+ builder.AddBooleanProperty(
+ "LeftPaddle2",
+ [this] { return GetButtonForSendable(Button::kLeftPaddle2); }, nullptr);
+ builder.AddBooleanProperty(
+ "Touchpad", [this] { return GetButtonForSendable(Button::kTouchpad); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "Misc2", [this] { return GetButtonForSendable(Button::kMisc2); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "Misc3", [this] { return GetButtonForSendable(Button::kMisc3); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "Misc4", [this] { return GetButtonForSendable(Button::kMisc4); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "Misc5", [this] { return GetButtonForSendable(Button::kMisc5); },
+ nullptr);
+ builder.AddBooleanProperty(
+ "Misc6", [this] { return GetButtonForSendable(Button::kMisc6); },
+ nullptr);
+}
diff --git a/wpilibc/src/main/native/cpp/GenericHID.cpp b/wpilibc/src/main/native/cpp/GenericHID.cpp
index 589a5b4fce..57914bd973 100644
--- a/wpilibc/src/main/native/cpp/GenericHID.cpp
+++ b/wpilibc/src/main/native/cpp/GenericHID.cpp
@@ -107,16 +107,28 @@ BooleanEvent GenericHID::AxisGreaterThan(int axis, double threshold,
});
}
-int GenericHID::GetAxisCount() const {
- return DriverStation::GetStickAxisCount(m_port);
+int GenericHID::GetAxesMaximumIndex() const {
+ return DriverStation::GetStickAxesMaximumIndex(m_port);
}
-int GenericHID::GetPOVCount() const {
- return DriverStation::GetStickPOVCount(m_port);
+int GenericHID::GetAxesAvailable() const {
+ return DriverStation::GetStickAxesAvailable(m_port);
}
-int GenericHID::GetButtonCount() const {
- return DriverStation::GetStickButtonCount(m_port);
+int GenericHID::GetPOVsMaximumIndex() const {
+ return DriverStation::GetStickPOVsMaximumIndex(m_port);
+}
+
+int GenericHID::GetPOVsAvailable() const {
+ return DriverStation::GetStickPOVsAvailable(m_port);
+}
+
+int GenericHID::GetButtonsMaximumIndex() const {
+ return DriverStation::GetStickButtonsMaximumIndex(m_port);
+}
+
+uint64_t GenericHID::GetButtonsAvailable() const {
+ return DriverStation::GetStickButtonsAvailable(m_port);
}
bool GenericHID::IsConnected() const {
@@ -131,10 +143,6 @@ std::string GenericHID::GetName() const {
return DriverStation::GetJoystickName(m_port);
}
-int GenericHID::GetAxisType(int axis) const {
- return DriverStation::GetJoystickAxisType(m_port, axis);
-}
-
int GenericHID::GetPort() const {
return m_port;
}
diff --git a/wpilibc/src/main/native/cpp/simulation/DriverStationSim.cpp b/wpilibc/src/main/native/cpp/simulation/DriverStationSim.cpp
index 290e9c2a0c..c6bd193769 100644
--- a/wpilibc/src/main/native/cpp/simulation/DriverStationSim.cpp
+++ b/wpilibc/src/main/native/cpp/simulation/DriverStationSim.cpp
@@ -210,22 +210,54 @@ void DriverStationSim::SetJoystickPOV(int stick, int pov,
HALSIM_SetJoystickPOV(stick, pov, static_cast(value));
}
-void DriverStationSim::SetJoystickButtons(int stick, uint32_t buttons) {
- HALSIM_SetJoystickButtonsValue(stick, buttons);
+void DriverStationSim::SetJoystickAxesMaximumIndex(int stick,
+ int maximumIndex) {
+ SetJoystickAxesAvailable(stick, (1 << maximumIndex) - 1);
}
-void DriverStationSim::SetJoystickAxisCount(int stick, int count) {
- HALSIM_SetJoystickAxisCount(stick, count);
+void DriverStationSim::SetJoystickAxesAvailable(int stick, int count) {
+ HALSIM_SetJoystickAxesAvailable(stick, count);
}
-void DriverStationSim::SetJoystickPOVCount(int stick, int count) {
- HALSIM_SetJoystickPOVCount(stick, count);
+void DriverStationSim::SetJoystickPOVsMaximumIndex(int stick,
+ int maximumIndex) {
+ SetJoystickPOVsAvailable(stick, (1 << maximumIndex) - 1);
}
-void DriverStationSim::SetJoystickButtonCount(int stick, int count) {
- HALSIM_SetJoystickButtonCount(stick, count);
+void DriverStationSim::SetJoystickPOVsAvailable(int stick, int count) {
+ HALSIM_SetJoystickPOVsAvailable(stick, count);
}
+void DriverStationSim::SetJoystickButtonsMaximumIndex(int stick,
+ int maximumIndex) {
+ if (maximumIndex >= 64) {
+ SetJoystickButtonsAvailable(stick, 0xFFFFFFFFFFFFFFFFL);
+ } else {
+ SetJoystickButtonsAvailable(stick, (1L << maximumIndex) - 1);
+ }
+}
+
+void DriverStationSim::SetJoystickButtonsAvailable(int stick,
+ uint64_t available) {
+ HALSIM_SetJoystickButtonsAvailable(stick, available);
+}
+
+// void DriverStationSim::SetJoystickButtons(int stick, uint32_t buttons) {
+// HALSIM_SetJoystickButtonsValue(stick, buttons);
+// }
+
+// void DriverStationSim::SetJoystickAxisCount(int stick, int count) {
+// HALSIM_SetJoystickAxisCount(stick, count);
+// }
+
+// void DriverStationSim::SetJoystickPOVCount(int stick, int count) {
+// HALSIM_SetJoystickPOVCount(stick, count);
+// }
+
+// void DriverStationSim::SetJoystickButtonCount(int stick, int count) {
+// HALSIM_SetJoystickButtonCount(stick, count);
+// }
+
void DriverStationSim::SetJoystickIsGamepad(int stick, bool isGamepad) {
HALSIM_SetJoystickIsGamepad(stick, isGamepad);
}
@@ -239,10 +271,6 @@ void DriverStationSim::SetJoystickName(int stick, std::string_view name) {
HALSIM_SetJoystickName(stick, &str);
}
-void DriverStationSim::SetJoystickAxisType(int stick, int axis, int type) {
- HALSIM_SetJoystickAxisType(stick, axis, type);
-}
-
void DriverStationSim::SetGameSpecificMessage(std::string_view message) {
auto str = wpi::make_string(message);
HALSIM_SetGameSpecificMessage(&str);
diff --git a/wpilibc/src/main/native/cpp/simulation/GamepadSim.cpp b/wpilibc/src/main/native/cpp/simulation/GamepadSim.cpp
new file mode 100644
index 0000000000..1b265e5e4d
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/simulation/GamepadSim.cpp
@@ -0,0 +1,150 @@
+// 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.
+
+#include "frc/simulation/GamepadSim.h"
+
+#include "frc/Gamepad.h"
+
+using namespace frc;
+using namespace frc::sim;
+
+GamepadSim::GamepadSim(const Gamepad& joystick) : GenericHIDSim{joystick} {
+ SetAxesMaximumIndex(6);
+ SetButtonsMaximumIndex(26);
+ SetPOVsMaximumIndex(1);
+}
+
+GamepadSim::GamepadSim(int port) : GenericHIDSim{port} {
+ SetAxesMaximumIndex(6);
+ SetButtonsMaximumIndex(26);
+ SetPOVsMaximumIndex(1);
+}
+
+void GamepadSim::SetLeftX(double value) {
+ SetRawAxis(Gamepad::Axis::kLeftX, value);
+}
+
+void GamepadSim::SetLeftY(double value) {
+ SetRawAxis(Gamepad::Axis::kLeftY, value);
+}
+
+void GamepadSim::SetRightX(double value) {
+ SetRawAxis(Gamepad::Axis::kRightX, value);
+}
+
+void GamepadSim::SetRightY(double value) {
+ SetRawAxis(Gamepad::Axis::kRightY, value);
+}
+
+void GamepadSim::SetLeftTriggerAxis(double value) {
+ SetRawAxis(Gamepad::Axis::kLeftTrigger, value);
+}
+
+void GamepadSim::SetRightTriggerAxis(double value) {
+ SetRawAxis(Gamepad::Axis::kRightTrigger, value);
+}
+
+void GamepadSim::SetSouthFaceButton(bool value) {
+ SetRawButton(Gamepad::Button::kSouthFace, value);
+}
+
+void GamepadSim::SetEastFaceButton(bool value) {
+ SetRawButton(Gamepad::Button::kEastFace, value);
+}
+
+void GamepadSim::SetWestFaceButton(bool value) {
+ SetRawButton(Gamepad::Button::kWestFace, value);
+}
+
+void GamepadSim::SetNorthFacenButton(bool value) {
+ SetRawButton(Gamepad::Button::kNorthFacen, value);
+}
+
+void GamepadSim::SetBackButton(bool value) {
+ SetRawButton(Gamepad::Button::kBack, value);
+}
+
+void GamepadSim::SetGuideButton(bool value) {
+ SetRawButton(Gamepad::Button::kGuide, value);
+}
+
+void GamepadSim::SetStartButton(bool value) {
+ SetRawButton(Gamepad::Button::kStart, value);
+}
+
+void GamepadSim::SetLeftStickButton(bool value) {
+ SetRawButton(Gamepad::Button::kLeftStick, value);
+}
+
+void GamepadSim::SetRightStickButton(bool value) {
+ SetRawButton(Gamepad::Button::kRightStick, value);
+}
+
+void GamepadSim::SetLeftShoulderButton(bool value) {
+ SetRawButton(Gamepad::Button::kLeftShoulder, value);
+}
+
+void GamepadSim::SetRightShoulderButton(bool value) {
+ SetRawButton(Gamepad::Button::kRightShoulder, value);
+}
+
+void GamepadSim::SetDpadUpButton(bool value) {
+ SetRawButton(Gamepad::Button::kDpadUp, value);
+}
+
+void GamepadSim::SetDpadDownButton(bool value) {
+ SetRawButton(Gamepad::Button::kDpadDown, value);
+}
+
+void GamepadSim::SetDpadLeftButton(bool value) {
+ SetRawButton(Gamepad::Button::kDpadLeft, value);
+}
+
+void GamepadSim::SetDpadRightButton(bool value) {
+ SetRawButton(Gamepad::Button::kDpadRight, value);
+}
+
+void GamepadSim::SetMisc1Button(bool value) {
+ SetRawButton(Gamepad::Button::kMisc1, value);
+}
+
+void GamepadSim::SetRightPaddle1Button(bool value) {
+ SetRawButton(Gamepad::Button::kRightPaddle1, value);
+}
+
+void GamepadSim::SetLeftPaddle1Button(bool value) {
+ SetRawButton(Gamepad::Button::kLeftPaddle1, value);
+}
+
+void GamepadSim::SetRightPaddle2Button(bool value) {
+ SetRawButton(Gamepad::Button::kRightPaddle2, value);
+}
+
+void GamepadSim::SetLeftPaddle2Button(bool value) {
+ SetRawButton(Gamepad::Button::kLeftPaddle2, value);
+}
+
+void GamepadSim::SetTouchpadButton(bool value) {
+ SetRawButton(Gamepad::Button::kTouchpad, value);
+}
+
+void GamepadSim::SetMisc2Button(bool value) {
+ SetRawButton(Gamepad::Button::kMisc2, value);
+}
+
+void GamepadSim::SetMisc3Button(bool value) {
+ SetRawButton(Gamepad::Button::kMisc3, value);
+}
+
+void GamepadSim::SetMisc4Button(bool value) {
+ SetRawButton(Gamepad::Button::kMisc4, value);
+}
+
+void GamepadSim::SetMisc5Button(bool value) {
+ SetRawButton(Gamepad::Button::kMisc5, value);
+}
+
+void GamepadSim::SetMisc6Button(bool value) {
+ SetRawButton(Gamepad::Button::kMisc6, value);
+}
diff --git a/wpilibc/src/main/native/cpp/simulation/GenericHIDSim.cpp b/wpilibc/src/main/native/cpp/simulation/GenericHIDSim.cpp
index f106517fb2..8ffcd26083 100644
--- a/wpilibc/src/main/native/cpp/simulation/GenericHIDSim.cpp
+++ b/wpilibc/src/main/native/cpp/simulation/GenericHIDSim.cpp
@@ -36,16 +36,28 @@ void GenericHIDSim::SetPOV(DriverStation::POVDirection value) {
SetPOV(0, value);
}
-void GenericHIDSim::SetAxisCount(int count) {
- DriverStationSim::SetJoystickAxisCount(m_port, count);
+void GenericHIDSim::SetAxesMaximumIndex(int maximumIndex) {
+ DriverStationSim::SetJoystickAxesMaximumIndex(m_port, maximumIndex);
}
-void GenericHIDSim::SetPOVCount(int count) {
- DriverStationSim::SetJoystickPOVCount(m_port, count);
+void GenericHIDSim::SetAxesAvailable(int count) {
+ DriverStationSim::SetJoystickAxesAvailable(m_port, count);
}
-void GenericHIDSim::SetButtonCount(int count) {
- DriverStationSim::SetJoystickButtonCount(m_port, count);
+void GenericHIDSim::SetPOVsMaximumIndex(int maximumIndex) {
+ DriverStationSim::SetJoystickPOVsMaximumIndex(m_port, maximumIndex);
+}
+
+void GenericHIDSim::SetPOVsAvailable(int count) {
+ DriverStationSim::SetJoystickPOVsAvailable(m_port, count);
+}
+
+void GenericHIDSim::SetButtonsMaximumIndex(int maximumIndex) {
+ DriverStationSim::SetJoystickButtonsMaximumIndex(m_port, maximumIndex);
+}
+
+void GenericHIDSim::SetButtonsAvailable(uint64_t count) {
+ DriverStationSim::SetJoystickButtonsAvailable(m_port, count);
}
void GenericHIDSim::SetType(GenericHID::HIDType type) {
@@ -56,10 +68,6 @@ void GenericHIDSim::SetName(const char* name) {
DriverStationSim::SetJoystickName(m_port, name);
}
-void GenericHIDSim::SetAxisType(int axis, int type) {
- DriverStationSim::SetJoystickAxisType(m_port, axis, type);
-}
-
bool GenericHIDSim::GetOutput(int outputNumber) {
int64_t outputs = GetOutputs();
return (outputs & (static_cast(1) << (outputNumber - 1))) != 0;
diff --git a/wpilibc/src/main/native/cpp/simulation/JoystickSim.cpp b/wpilibc/src/main/native/cpp/simulation/JoystickSim.cpp
index d10382274d..2019eff81d 100644
--- a/wpilibc/src/main/native/cpp/simulation/JoystickSim.cpp
+++ b/wpilibc/src/main/native/cpp/simulation/JoystickSim.cpp
@@ -13,16 +13,16 @@ using namespace frc::sim;
JoystickSim::JoystickSim(const Joystick& joystick)
: GenericHIDSim{joystick}, m_joystick{&joystick} {
// default to a reasonable joystick configuration
- SetAxisCount(5);
- SetButtonCount(12);
- SetPOVCount(1);
+ SetAxesMaximumIndex(5);
+ SetButtonsMaximumIndex(12);
+ SetPOVsMaximumIndex(1);
}
JoystickSim::JoystickSim(int port) : GenericHIDSim{port} {
// default to a reasonable joystick configuration
- SetAxisCount(5);
- SetButtonCount(12);
- SetPOVCount(1);
+ SetAxesMaximumIndex(5);
+ SetButtonsMaximumIndex(12);
+ SetPOVsMaximumIndex(1);
}
void JoystickSim::SetX(double value) {
diff --git a/wpilibc/src/main/native/include/frc/DriverStation.h b/wpilibc/src/main/native/include/frc/DriverStation.h
index fd8d449afc..36eca4ad46 100644
--- a/wpilibc/src/main/native/include/frc/DriverStation.h
+++ b/wpilibc/src/main/native/include/frc/DriverStation.h
@@ -109,20 +109,30 @@ class DriverStation final {
static constexpr int kJoystickPorts = 6;
/**
- * The state of one joystick button. %Button indexes begin at 1.
+ * The state of one joystick button. Button indexes begin at 0.
*
* @param stick The joystick to read.
- * @param button The button index, beginning at 1.
+ * @param button The button index, beginning at 0.
* @return The state of the joystick button.
*/
static bool GetStickButton(int stick, int button);
+ /**
+ * The state of one joystick button, only if available. Button indexes begin
+ * at 0.
+ *
+ * @param stick The joystick to read.
+ * @param button The button index, beginning at 0.
+ * @return The state of the joystick button, or empty if unavailable.
+ */
+ static std::optional GetStickButtonIfAvailable(int stick, int button);
+
/**
* Whether one joystick button was pressed since the last check. %Button
* indexes begin at 1.
*
* @param stick The joystick to read.
- * @param button The button index, beginning at 1.
+ * @param button The button index, beginning at 0.
* @return Whether the joystick button was pressed since the last check.
*/
static bool GetStickButtonPressed(int stick, int button);
@@ -132,7 +142,7 @@ class DriverStation final {
* indexes begin at 1.
*
* @param stick The joystick to read.
- * @param button The button index, beginning at 1.
+ * @param button The button index, beginning at 0.
* @return Whether the joystick button was released since the last check.
*/
static bool GetStickButtonReleased(int stick, int button);
@@ -149,6 +159,18 @@ class DriverStation final {
*/
static double GetStickAxis(int stick, int axis);
+ /**
+ * Get the value of the axis on a joystick, if available.
+ *
+ * This depends on the mapping of the joystick connected to the specified
+ * port.
+ *
+ * @param stick The joystick to read.
+ * @param axis The analog axis value to read from the joystick.
+ * @return The value of the axis on the joystick, or empty if not available.
+ */
+ static std::optional GetStickAxisIfAvailable(int stick, int axis);
+
/**
* Get the state of a POV on the joystick.
*
@@ -162,31 +184,55 @@ class DriverStation final {
* @param stick The joystick to read.
* @return The state of the buttons on the joystick.
*/
- static int GetStickButtons(int stick);
+ static uint64_t GetStickButtons(int stick);
/**
- * Returns the number of axes on a given joystick port.
+ * Returns the maximum axis index on a given joystick port.
*
* @param stick The joystick port number
- * @return The number of axes on the indicated joystick
+ * @return The maximum axis index on the indicated joystick
*/
- static int GetStickAxisCount(int stick);
+ static int GetStickAxesMaximumIndex(int stick);
/**
- * Returns the number of POVs on a given joystick port.
+ * Returns the mask of available axes on a given joystick port.
*
* @param stick The joystick port number
- * @return The number of POVs on the indicated joystick
+ * @return The mask of available axes on the indicated joystick
*/
- static int GetStickPOVCount(int stick);
+ static int GetStickAxesAvailable(int stick);
/**
- * Returns the number of buttons on a given joystick port.
+ * Returns the maximum POV index on a given joystick port.
*
* @param stick The joystick port number
- * @return The number of buttons on the indicated joystick
+ * @return The maximum POV index on the indicated joystick
*/
- static int GetStickButtonCount(int stick);
+ static int GetStickPOVsMaximumIndex(int stick);
+
+ /**
+ * Returns the mask of available POVs on a given joystick port.
+ *
+ * @param stick The joystick port number
+ * @return The mask of available POVs on the indicated joystick
+ */
+ static int GetStickPOVsAvailable(int stick);
+
+ /**
+ * Returns the maximum button index on a given joystick port.
+ *
+ * @param stick The joystick port number
+ * @return The maximum button index on the indicated joystick
+ */
+ static int GetStickButtonsMaximumIndex(int stick);
+
+ /**
+ * Returns the mask of available buttons on a given joystick port.
+ *
+ * @param stick The joystick port number
+ * @return The mask of available buttons on the indicated joystick
+ */
+ static uint64_t GetStickButtonsAvailable(int stick);
/**
* Returns a boolean indicating if the controller is an xbox controller.
@@ -212,15 +258,6 @@ class DriverStation final {
*/
static std::string GetJoystickName(int stick);
- /**
- * Returns the types of Axes on a given joystick port.
- *
- * @param stick The joystick port number and the target axis
- * @param axis The analog axis value to read from the joystick.
- * @return What type of axis the axis is reporting to be
- */
- static int GetJoystickAxisType(int stick, int axis);
-
/**
* Returns if a joystick is connected to the Driver Station.
*
diff --git a/wpilibc/src/main/native/include/frc/Gamepad.h b/wpilibc/src/main/native/include/frc/Gamepad.h
new file mode 100644
index 0000000000..8c72c33684
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Gamepad.h
@@ -0,0 +1,1018 @@
+// 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.
+
+#pragma once
+
+#include
+#include
+
+#include "frc/GenericHID.h"
+
+namespace frc {
+
+/**
+ * Handle input from Gamepad controllers connected to the Driver Station.
+ *
+ * This class handles Gamepad input that comes from the Driver Station. Each
+ * time a value is requested the most recent value is returned. There is a
+ * single class instance for each controller and the mapping of ports to
+ * hardware buttons depends on the code in the Driver Station.
+ *
+ * Only first party controllers from Generic are guaranteed to have the
+ * correct mapping, and only through the official NI DS. Sim is not guaranteed
+ * to have the same mapping, as well as any 3rd party controllers.
+ */
+class Gamepad : public GenericHID,
+ public wpi::Sendable,
+ public wpi::SendableHelper {
+ public:
+ /**
+ * Construct an instance of a controller.
+ *
+ * The controller index is the USB port on the Driver Station.
+ *
+ * @param port The port on the Driver Station that the controller is plugged
+ * into (0-5).
+ */
+ explicit Gamepad(int port);
+
+ ~Gamepad() override = default;
+
+ Gamepad(Gamepad&&) = default;
+ Gamepad& operator=(Gamepad&&) = default;
+
+ /**
+ * Get the X axis value of left side of the controller. Right is positive.
+ *
+ * @return the axis value.
+ */
+ double GetLeftX() const;
+
+ /**
+ * Get the Y axis value of left side of the controller. Back is positive.
+ *
+ * @return the axis value.
+ */
+ double GetLeftY() const;
+
+ /**
+ * Get the X axis value of right side of the controller. Right is positive.
+ *
+ * @return the axis value.
+ */
+ double GetRightX() const;
+
+ /**
+ * Get the Y axis value of right side of the controller. Back is positive.
+ *
+ * @return the axis value.
+ */
+ double GetRightY() const;
+
+ /**
+ * Get the left trigger axis value of the controller. Note that this axis
+ * is bound to the range of [0, 1] as opposed to the usual [-1, 1].
+ *
+ * @return the axis value.
+ */
+ double GetLeftTriggerAxis() const;
+
+ /**
+ * Constructs an event instance around the axis value of the left trigger.
+ * The returned trigger will be true when the axis value is greater than
+ * {@code threshold}.
+ * @param threshold the minimum axis value for the returned event to be true.
+ * This value should be in the range [0, 1] where 0 is the unpressed state of
+ * the axis.
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance that is true when the left trigger's axis
+ * exceeds the provided threshold, attached to the given event loop
+ */
+ BooleanEvent LeftTrigger(double threshold, EventLoop* loop) const;
+
+ /**
+ * Constructs an event instance around the axis value of the left trigger.
+ * The returned trigger will be true when the axis value is greater than 0.5.
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance that is true when the left trigger's axis
+ * exceeds 0.5, attached to the given event loop
+ */
+ BooleanEvent LeftTrigger(EventLoop* loop) const;
+
+ /**
+ * Get the right trigger axis value of the controller. Note that this axis
+ * is bound to the range of [0, 1] as opposed to the usual [-1, 1].
+ *
+ * @return the axis value.
+ */
+ double GetRightTriggerAxis() const;
+
+ /**
+ * Constructs an event instance around the axis value of the right trigger.
+ * The returned trigger will be true when the axis value is greater than
+ * {@code threshold}.
+ * @param threshold the minimum axis value for the returned event to be true.
+ * This value should be in the range [0, 1] where 0 is the unpressed state of
+ * the axis.
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance that is true when the right trigger's axis
+ * exceeds the provided threshold, attached to the given event loop
+ */
+ BooleanEvent RightTrigger(double threshold, EventLoop* loop) const;
+
+ /**
+ * Constructs an event instance around the axis value of the right trigger.
+ * The returned trigger will be true when the axis value is greater than 0.5.
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance that is true when the right trigger's axis
+ * exceeds 0.5, attached to the given event loop
+ */
+ BooleanEvent RightTrigger(EventLoop* loop) const;
+
+ /**
+ * Read the value of the South Face button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetSouthFaceButton() const;
+
+ /**
+ * Whether the South Face button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetSouthFaceButtonPressed();
+
+ /**
+ * Whether the South Face button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetSouthFaceButtonReleased();
+
+ /**
+ * Constructs an event instance around the South Face button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the South Face button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent SouthFace(EventLoop* loop) const;
+
+ /**
+ * Read the value of the East Face button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetEastFaceButton() const;
+
+ /**
+ * Whether the East Face button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetEastFaceButtonPressed();
+
+ /**
+ * Whether the East Face button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetEastFaceButtonReleased();
+
+ /**
+ * Constructs an event instance around the East Face button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the East Face button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent EastFace(EventLoop* loop) const;
+
+ /**
+ * Read the value of the West Face button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetWestFaceButton() const;
+
+ /**
+ * Whether the West Face button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetWestFaceButtonPressed();
+
+ /**
+ * Whether the West Face button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetWestFaceButtonReleased();
+
+ /**
+ * Constructs an event instance around the West Face button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the West Face button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent WestFace(EventLoop* loop) const;
+
+ /**
+ * Read the value of the North Face button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetNorthFacenButton() const;
+
+ /**
+ * Whether the North Face button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetNorthFacenButtonPressed();
+
+ /**
+ * Whether the North Face button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetNorthFacenButtonReleased();
+
+ /**
+ * Constructs an event instance around the North Face button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the North Face button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent NorthFacen(EventLoop* loop) const;
+
+ /**
+ * Read the value of the Back button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetBackButton() const;
+
+ /**
+ * Whether the Back button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetBackButtonPressed();
+
+ /**
+ * Whether the Back button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetBackButtonReleased();
+
+ /**
+ * Constructs an event instance around the Back button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Back button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent Back(EventLoop* loop) const;
+
+ /**
+ * Read the value of the Guide button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetGuideButton() const;
+
+ /**
+ * Whether the Guide button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetGuideButtonPressed();
+
+ /**
+ * Whether the Guide button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetGuideButtonReleased();
+
+ /**
+ * Constructs an event instance around the Guide button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Guide button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent Guide(EventLoop* loop) const;
+
+ /**
+ * Read the value of the Start button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetStartButton() const;
+
+ /**
+ * Whether the Start button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetStartButtonPressed();
+
+ /**
+ * Whether the Start button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetStartButtonReleased();
+
+ /**
+ * Constructs an event instance around the Start button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Start button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent Start(EventLoop* loop) const;
+
+ /**
+ * Read the value of the left stick button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetLeftStickButton() const;
+
+ /**
+ * Whether the left stick button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetLeftStickButtonPressed();
+
+ /**
+ * Whether the left stick button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetLeftStickButtonReleased();
+
+ /**
+ * Constructs an event instance around the left stick button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the left stick button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent LeftStick(EventLoop* loop) const;
+
+ /**
+ * Read the value of the right stick button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetRightStickButton() const;
+
+ /**
+ * Whether the right stick button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetRightStickButtonPressed();
+
+ /**
+ * Whether the right stick button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetRightStickButtonReleased();
+
+ /**
+ * Constructs an event instance around the right stick button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the right stick button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent RightStick(EventLoop* loop) const;
+
+ /**
+ * Read the value of the right shoulder button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetLeftShoulderButton() const;
+
+ /**
+ * Whether the right shoulder button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetLeftShoulderButtonPressed();
+
+ /**
+ * Whether the right shoulder button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetLeftShoulderButtonReleased();
+
+ /**
+ * Constructs an event instance around the right shoulder button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the right shoulder button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent LeftShoulder(EventLoop* loop) const;
+
+ /**
+ * Read the value of the right shoulder button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetRightShoulderButton() const;
+
+ /**
+ * Whether the right shoulder button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetRightShoulderButtonPressed();
+
+ /**
+ * Whether the right shoulder button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetRightShoulderButtonReleased();
+
+ /**
+ * Constructs an event instance around the right shoulder button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the right shoulder button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent RightShoulder(EventLoop* loop) const;
+
+ /**
+ * Read the value of the D-pad up button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetDpadUpButton() const;
+
+ /**
+ * Whether the D-pad up button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetDpadUpButtonPressed();
+
+ /**
+ * Whether the D-pad up button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetDpadUpButtonReleased();
+
+ /**
+ * Constructs an event instance around the D-pad up button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the D-pad up button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent DpadUp(EventLoop* loop) const;
+
+ /**
+ * Read the value of the D-pad down button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetDpadDownButton() const;
+
+ /**
+ * Whether the D-pad down button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetDpadDownButtonPressed();
+
+ /**
+ * Whether the D-pad down button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetDpadDownButtonReleased();
+
+ /**
+ * Constructs an event instance around the D-pad down button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the D-pad down button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent DpadDown(EventLoop* loop) const;
+
+ /**
+ * Read the value of the D-pad left button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetDpadLeftButton() const;
+
+ /**
+ * Whether the D-pad left button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetDpadLeftButtonPressed();
+
+ /**
+ * Whether the D-pad left button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetDpadLeftButtonReleased();
+
+ /**
+ * Constructs an event instance around the D-pad left button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the D-pad left button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent DpadLeft(EventLoop* loop) const;
+
+ /**
+ * Read the value of the D-pad right button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetDpadRightButton() const;
+
+ /**
+ * Whether the D-pad right button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetDpadRightButtonPressed();
+
+ /**
+ * Whether the D-pad right button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetDpadRightButtonReleased();
+
+ /**
+ * Constructs an event instance around the D-pad right button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the D-pad right button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent DpadRight(EventLoop* loop) const;
+
+ /**
+ * Read the value of the Miscellaneous 1 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetMisc1Button() const;
+
+ /**
+ * Whether the Miscellaneous 1 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetMisc1ButtonPressed();
+
+ /**
+ * Whether the Miscellaneous 1 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetMisc1ButtonReleased();
+
+ /**
+ * Constructs an event instance around the Miscellaneous 1 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Miscellaneous 1 button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent Misc1(EventLoop* loop) const;
+
+ /**
+ * Read the value of the Right Paddle 1 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetRightPaddle1Button() const;
+
+ /**
+ * Whether the Right Paddle 1 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetRightPaddle1ButtonPressed();
+
+ /**
+ * Whether the Right Paddle 1 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetRightPaddle1ButtonReleased();
+
+ /**
+ * Constructs an event instance around the Right Paddle 1 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Right Paddle 1 button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent RightPaddle1(EventLoop* loop) const;
+
+ /**
+ * Read the value of the Left Paddle 1 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetLeftPaddle1Button() const;
+
+ /**
+ * Whether the Left Paddle 1 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetLeftPaddle1ButtonPressed();
+
+ /**
+ * Whether the Left Paddle 1 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetLeftPaddle1ButtonReleased();
+
+ /**
+ * Constructs an event instance around the Left Paddle 1 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Left Paddle 1 button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent LeftPaddle1(EventLoop* loop) const;
+
+ /**
+ * Read the value of the Right Paddle 2 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetRightPaddle2Button() const;
+
+ /**
+ * Whether the Right Paddle 2 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetRightPaddle2ButtonPressed();
+
+ /**
+ * Whether the Right Paddle 2 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetRightPaddle2ButtonReleased();
+
+ /**
+ * Constructs an event instance around the Right Paddle 2 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Right Paddle 2 button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent RightPaddle2(EventLoop* loop) const;
+
+ /**
+ * Read the value of the Left Paddle 2 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetLeftPaddle2Button() const;
+
+ /**
+ * Whether the Left Paddle 2 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetLeftPaddle2ButtonPressed();
+
+ /**
+ * Whether the Left Paddle 2 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetLeftPaddle2ButtonReleased();
+
+ /**
+ * Constructs an event instance around the Left Paddle 2 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Left Paddle 2 button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent LeftPaddle2(EventLoop* loop) const;
+
+ /**
+ * Read the value of the Touchpad button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetTouchpadButton() const;
+
+ /**
+ * Whether the Touchpad button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetTouchpadButtonPressed();
+
+ /**
+ * Whether the Touchpad button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetTouchpadButtonReleased();
+
+ /**
+ * Constructs an event instance around the Touchpad button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Touchpad button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent Touchpad(EventLoop* loop) const;
+
+ /**
+ * Read the value of the Miscellaneous 2 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetMisc2Button() const;
+
+ /**
+ * Whether the Miscellaneous 2 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetMisc2ButtonPressed();
+
+ /**
+ * Whether the Miscellaneous 2 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetMisc2ButtonReleased();
+
+ /**
+ * Constructs an event instance around the Miscellaneous 2 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Miscellaneous 2 button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent Misc2(EventLoop* loop) const;
+
+ /**
+ * Read the value of the Miscellaneous 3 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetMisc3Button() const;
+
+ /**
+ * Whether the Miscellaneous 3 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetMisc3ButtonPressed();
+
+ /**
+ * Whether the Miscellaneous 3 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetMisc3ButtonReleased();
+
+ /**
+ * Constructs an event instance around the Miscellaneous 3 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Miscellaneous 3 button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent Misc3(EventLoop* loop) const;
+
+ /**
+ * Read the value of the Miscellaneous 4 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetMisc4Button() const;
+
+ /**
+ * Whether the Miscellaneous 4 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetMisc4ButtonPressed();
+
+ /**
+ * Whether the Miscellaneous 4 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetMisc4ButtonReleased();
+
+ /**
+ * Constructs an event instance around the Miscellaneous 4 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Miscellaneous 4 button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent Misc4(EventLoop* loop) const;
+
+ /**
+ * Read the value of the Miscellaneous 5 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetMisc5Button() const;
+
+ /**
+ * Whether the Miscellaneous 5 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetMisc5ButtonPressed();
+
+ /**
+ * Whether the Miscellaneous 5 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetMisc5ButtonReleased();
+
+ /**
+ * Constructs an event instance around the Miscellaneous 5 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Miscellaneous 5 button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent Misc5(EventLoop* loop) const;
+
+ /**
+ * Read the value of the Miscellaneous 6 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ bool GetMisc6Button() const;
+
+ /**
+ * Whether the Miscellaneous 6 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ bool GetMisc6ButtonPressed();
+
+ /**
+ * Whether the Miscellaneous 6 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ bool GetMisc6ButtonReleased();
+
+ /**
+ * Constructs an event instance around the Miscellaneous 6 button's
+ * digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Miscellaneous 6 button's
+ * digital signal attached to the given loop.
+ */
+ BooleanEvent Misc6(EventLoop* loop) const;
+
+ /** Represents a digital button on an Gamepad. */
+ struct Button {
+ /// South Face button.
+ static constexpr int kSouthFace = 0;
+ /// East Face button.
+ static constexpr int kEastFace = 1;
+ /// West Face button.
+ static constexpr int kWestFace = 2;
+ /// North Face button.
+ static constexpr int kNorthFacen = 3;
+ /// Back button.
+ static constexpr int kBack = 4;
+ /// Guide button.
+ static constexpr int kGuide = 5;
+ /// Start button.
+ static constexpr int kStart = 6;
+ /// Left stick button.
+ static constexpr int kLeftStick = 7;
+ /// Right stick button.
+ static constexpr int kRightStick = 8;
+ /// Right shoulder button.
+ static constexpr int kLeftShoulder = 9;
+ /// Right shoulder button.
+ static constexpr int kRightShoulder = 10;
+ /// D-pad up button.
+ static constexpr int kDpadUp = 11;
+ /// D-pad down button.
+ static constexpr int kDpadDown = 12;
+ /// D-pad left button.
+ static constexpr int kDpadLeft = 13;
+ /// D-pad right button.
+ static constexpr int kDpadRight = 14;
+ /// Miscellaneous 1 button.
+ static constexpr int kMisc1 = 15;
+ /// Right Paddle 1 button.
+ static constexpr int kRightPaddle1 = 16;
+ /// Left Paddle 1 button.
+ static constexpr int kLeftPaddle1 = 17;
+ /// Right Paddle 2 button.
+ static constexpr int kRightPaddle2 = 18;
+ /// Left Paddle 2 button.
+ static constexpr int kLeftPaddle2 = 19;
+ /// Touchpad button.
+ static constexpr int kTouchpad = 20;
+ /// Miscellaneous 2 button.
+ static constexpr int kMisc2 = 21;
+ /// Miscellaneous 3 button.
+ static constexpr int kMisc3 = 22;
+ /// Miscellaneous 4 button.
+ static constexpr int kMisc4 = 23;
+ /// Miscellaneous 5 button.
+ static constexpr int kMisc5 = 24;
+ /// Miscellaneous 6 button.
+ static constexpr int kMisc6 = 25;
+ };
+
+ /** Represents an axis on an Gamepad. */
+ struct Axis {
+ /// Left X axis.
+ static constexpr int kLeftX = 0;
+ /// Left Y axis.
+ static constexpr int kLeftY = 1;
+ /// Right X axis.
+ static constexpr int kRightX = 2;
+ /// Right Y axis.
+ static constexpr int kRightY = 3;
+ /// Left trigger.
+ static constexpr int kLeftTrigger = 4;
+ /// Right trigger.
+ static constexpr int kRightTrigger = 5;
+ };
+
+ void InitSendable(wpi::SendableBuilder& builder) override;
+
+ private:
+ double GetAxisForSendable(int axis) const;
+ bool GetButtonForSendable(int button) const;
+};
+
+} // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/GenericHID.h b/wpilibc/src/main/native/include/frc/GenericHID.h
index 7317b3bdd0..0f89a59714 100644
--- a/wpilibc/src/main/native/include/frc/GenericHID.h
+++ b/wpilibc/src/main/native/include/frc/GenericHID.h
@@ -106,7 +106,7 @@ class GenericHID {
* since the last time this method was called. This is useful if you only
* want to call a function once when you press the button.
*
- * @param button The button index, beginning at 1.
+ * @param button The button index, beginning at 0.
* @return Whether the button was pressed since the last check.
*/
bool GetRawButtonPressed(int button);
@@ -119,7 +119,7 @@ class GenericHID {
* since the last time this method was called. This is useful if you only
* want to call a function once when you release the button.
*
- * @param button The button index, beginning at 1.
+ * @param button The button index, beginning at 0.
* @return Whether the button was released since the last check.
*/
bool GetRawButtonReleased(int button);
@@ -280,26 +280,32 @@ class GenericHID {
BooleanEvent AxisGreaterThan(int axis, double threshold,
EventLoop* loop) const;
+ int GetAxesMaximumIndex() const;
+
/**
* Get the number of axes for the HID.
*
* @return the number of axis for the current HID
*/
- int GetAxisCount() const;
+ int GetAxesAvailable() const;
+
+ int GetPOVsMaximumIndex() const;
/**
* Get the number of POVs for the HID.
*
* @return the number of POVs for the current HID
*/
- int GetPOVCount() const;
+ int GetPOVsAvailable() const;
+
+ int GetButtonsMaximumIndex() const;
/**
* Get the number of buttons for the HID.
*
* @return the number of buttons on the current HID
*/
- int GetButtonCount() const;
+ uint64_t GetButtonsAvailable() const;
/**
* Get if the HID is connected.
@@ -322,13 +328,6 @@ class GenericHID {
*/
std::string GetName() const;
- /**
- * Get the axis type of a joystick axis.
- *
- * @return the axis type of a joystick axis.
- */
- int GetAxisType(int axis) const;
-
/**
* Get the port number of the HID.
*
diff --git a/wpilibc/src/main/native/include/frc/simulation/DriverStationSim.h b/wpilibc/src/main/native/include/frc/simulation/DriverStationSim.h
index 71145afb98..29c1490933 100644
--- a/wpilibc/src/main/native/include/frc/simulation/DriverStationSim.h
+++ b/wpilibc/src/main/native/include/frc/simulation/DriverStationSim.h
@@ -264,10 +264,10 @@ class DriverStationSim {
static int GetJoystickRumble(int stick, int rumbleNum);
/**
- * Sets the state of one joystick button. %Button indexes begin at 1.
+ * Sets the state of one joystick button. %Button indexes begin at 0.
*
* @param stick The joystick number
- * @param button The button index, beginning at 1
+ * @param button The button index, beginning at 0
* @param state The state of the joystick button
*/
static void SetJoystickButton(int stick, int button, bool state);
@@ -292,28 +292,36 @@ class DriverStationSim {
DriverStation::POVDirection value);
/**
- * Sets the state of all the buttons on a joystick.
+ * Sets the number of axes for a joystick.
*
* @param stick The joystick number
- * @param buttons The bitmap state of the buttons on the joystick
+ * @param maximumIndex The number of axes on the indicated joystick
*/
- static void SetJoystickButtons(int stick, uint32_t buttons);
+ static void SetJoystickAxesMaximumIndex(int stick, int maximumIndex);
/**
* Sets the number of axes for a joystick.
*
* @param stick The joystick number
- * @param count The number of axes on the indicated joystick
+ * @param available The number of axes on the indicated joystick
*/
- static void SetJoystickAxisCount(int stick, int count);
+ static void SetJoystickAxesAvailable(int stick, int available);
/**
* Sets the number of POVs for a joystick.
*
* @param stick The joystick number
- * @param count The number of POVs on the indicated joystick
+ * @param maximumIndex The number of POVs on the indicated joystick
*/
- static void SetJoystickPOVCount(int stick, int count);
+ static void SetJoystickPOVsMaximumIndex(int stick, int maximumIndex);
+
+ /**
+ * Sets the number of POVs for a joystick.
+ *
+ * @param stick The joystick number
+ * @param available The number of POVs on the indicated joystick
+ */
+ static void SetJoystickPOVsAvailable(int stick, int available);
/**
* Sets the number of buttons for a joystick.
@@ -321,7 +329,9 @@ class DriverStationSim {
* @param stick The joystick number
* @param count The number of buttons on the indicated joystick
*/
- static void SetJoystickButtonCount(int stick, int count);
+ static void SetJoystickButtonsMaximumIndex(int stick, int count);
+
+ static void SetJoystickButtonsAvailable(int stick, uint64_t available);
/**
* Sets the value of isGamepad for a joystick.
@@ -347,15 +357,6 @@ class DriverStationSim {
*/
static void SetJoystickName(int stick, std::string_view name);
- /**
- * Sets the types of Axes for a joystick.
- *
- * @param stick The joystick number
- * @param axis The target axis
- * @param type The type of axis
- */
- static void SetJoystickAxisType(int stick, int axis, int type);
-
/**
* Sets the game specific message.
*
diff --git a/wpilibc/src/main/native/include/frc/simulation/GamepadSim.h b/wpilibc/src/main/native/include/frc/simulation/GamepadSim.h
new file mode 100644
index 0000000000..b0162684da
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/simulation/GamepadSim.h
@@ -0,0 +1,260 @@
+// 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.
+
+#pragma once
+
+#include "frc/simulation/GenericHIDSim.h"
+
+namespace frc {
+
+class Gamepad;
+
+namespace sim {
+
+/**
+ * Class to control a simulated Gamepad controller.
+ */
+class GamepadSim : public GenericHIDSim {
+ public:
+ /**
+ * Constructs from a Gamepad object.
+ *
+ * @param joystick controller to simulate
+ */
+ explicit GamepadSim(const Gamepad& joystick);
+
+ /**
+ * Constructs from a joystick port number.
+ *
+ * @param port port number
+ */
+ explicit GamepadSim(int port);
+
+ /**
+ * Change the left X value of the controller's joystick.
+ *
+ * @param value the new value
+ */
+ void SetLeftX(double value);
+
+ /**
+ * Change the left Y value of the controller's joystick.
+ *
+ * @param value the new value
+ */
+ void SetLeftY(double value);
+
+ /**
+ * Change the right X value of the controller's joystick.
+ *
+ * @param value the new value
+ */
+ void SetRightX(double value);
+
+ /**
+ * Change the right Y value of the controller's joystick.
+ *
+ * @param value the new value
+ */
+ void SetRightY(double value);
+
+ /**
+ * Change the value of the left trigger axis on the controller.
+ *
+ * @param value the new value
+ */
+ void SetLeftTriggerAxis(double value);
+
+ /**
+ * Change the value of the right trigger axis on the controller.
+ *
+ * @param value the new value
+ */
+ void SetRightTriggerAxis(double value);
+
+ /**
+ * Change the value of the South Face button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetSouthFaceButton(bool value);
+
+ /**
+ * Change the value of the East Face button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetEastFaceButton(bool value);
+
+ /**
+ * Change the value of the West Face button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetWestFaceButton(bool value);
+
+ /**
+ * Change the value of the North Face button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetNorthFacenButton(bool value);
+
+ /**
+ * Change the value of the Back button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetBackButton(bool value);
+
+ /**
+ * Change the value of the Guide button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetGuideButton(bool value);
+
+ /**
+ * Change the value of the Start button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetStartButton(bool value);
+
+ /**
+ * Change the value of the left stick button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetLeftStickButton(bool value);
+
+ /**
+ * Change the value of the right stick button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetRightStickButton(bool value);
+
+ /**
+ * Change the value of the right shoulder button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetLeftShoulderButton(bool value);
+
+ /**
+ * Change the value of the right shoulder button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetRightShoulderButton(bool value);
+
+ /**
+ * Change the value of the D-pad up button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetDpadUpButton(bool value);
+
+ /**
+ * Change the value of the D-pad down button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetDpadDownButton(bool value);
+
+ /**
+ * Change the value of the D-pad left button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetDpadLeftButton(bool value);
+
+ /**
+ * Change the value of the D-pad right button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetDpadRightButton(bool value);
+
+ /**
+ * Change the value of the Miscellaneous 1 button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetMisc1Button(bool value);
+
+ /**
+ * Change the value of the Right Paddle 1 button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetRightPaddle1Button(bool value);
+
+ /**
+ * Change the value of the Left Paddle 1 button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetLeftPaddle1Button(bool value);
+
+ /**
+ * Change the value of the Right Paddle 2 button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetRightPaddle2Button(bool value);
+
+ /**
+ * Change the value of the Left Paddle 2 button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetLeftPaddle2Button(bool value);
+
+ /**
+ * Change the value of the Touchpad button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetTouchpadButton(bool value);
+
+ /**
+ * Change the value of the Miscellaneous 2 button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetMisc2Button(bool value);
+
+ /**
+ * Change the value of the Miscellaneous 3 button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetMisc3Button(bool value);
+
+ /**
+ * Change the value of the Miscellaneous 4 button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetMisc4Button(bool value);
+
+ /**
+ * Change the value of the Miscellaneous 5 button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetMisc5Button(bool value);
+
+ /**
+ * Change the value of the Miscellaneous 6 button on the controller.
+ *
+ * @param value the new value
+ */
+ void SetMisc6Button(bool value);
+};
+
+} // namespace sim
+} // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/simulation/GenericHIDSim.h b/wpilibc/src/main/native/include/frc/simulation/GenericHIDSim.h
index 8ab3064068..31f2098b63 100644
--- a/wpilibc/src/main/native/include/frc/simulation/GenericHIDSim.h
+++ b/wpilibc/src/main/native/include/frc/simulation/GenericHIDSim.h
@@ -70,26 +70,32 @@ class GenericHIDSim {
*/
void SetPOV(DriverStation::POVDirection value);
+ void SetAxesMaximumIndex(int maximumIndex);
+
/**
* Set the axis count of this device.
*
* @param count the new axis count
*/
- void SetAxisCount(int count);
+ void SetAxesAvailable(int count);
+
+ void SetPOVsMaximumIndex(int maximumIndex);
/**
* Set the POV count of this device.
*
* @param count the new POV count
*/
- void SetPOVCount(int count);
+ void SetPOVsAvailable(int count);
+
+ void SetButtonsMaximumIndex(int maximumIndex);
/**
* Set the button count of this device.
*
* @param count the new button count
*/
- void SetButtonCount(int count);
+ void SetButtonsAvailable(uint64_t count);
/**
* Set the type of this device.
diff --git a/wpilibc/src/test/native/cpp/DriverStationTest.cpp b/wpilibc/src/test/native/cpp/DriverStationTest.cpp
index b05023309a..cee8553622 100644
--- a/wpilibc/src/test/native/cpp/DriverStationTest.cpp
+++ b/wpilibc/src/test/native/cpp/DriverStationTest.cpp
@@ -16,10 +16,12 @@ class IsJoystickConnectedParametersTest
: public ::testing::TestWithParam> {};
TEST_P(IsJoystickConnectedParametersTest, IsJoystickConnected) {
- frc::sim::DriverStationSim::SetJoystickAxisCount(1, std::get<0>(GetParam()));
- frc::sim::DriverStationSim::SetJoystickButtonCount(1,
- std::get<1>(GetParam()));
- frc::sim::DriverStationSim::SetJoystickPOVCount(1, std::get<2>(GetParam()));
+ frc::sim::DriverStationSim::SetJoystickAxesMaximumIndex(
+ 1, std::get<0>(GetParam()));
+ frc::sim::DriverStationSim::SetJoystickButtonsMaximumIndex(
+ 1, std::get<1>(GetParam()));
+ frc::sim::DriverStationSim::SetJoystickPOVsMaximumIndex(
+ 1, std::get<2>(GetParam()));
frc::sim::DriverStationSim::NotifyNewData();
ASSERT_EQ(std::get<3>(GetParam()),
@@ -64,13 +66,13 @@ INSTANTIATE_TEST_SUITE_P(
std::make_tuple(false, true, true, ""),
std::make_tuple(
false, false, false,
- "Warning: Joystick Button 1 missing (max 0), check if all "
+ "Warning: Joystick Button 1 missing (available 0), check if all "
"controllers are plugged in\n"),
std::make_tuple(
true, true, false,
- "Warning: Joystick Button 1 missing (max 0), check if all "
+ "Warning: Joystick Button 1 missing (available 0), check if all "
"controllers are plugged in\n"),
std::make_tuple(
true, false, false,
- "Warning: Joystick Button 1 missing (max 0), check if all "
+ "Warning: Joystick Button 1 missing (available 0), check if all "
"controllers are plugged in\n")));
diff --git a/wpilibcExamples/src/test/cpp/examples/PotentiometerPID/cpp/PotentiometerPIDTest.cpp b/wpilibcExamples/src/test/cpp/examples/PotentiometerPID/cpp/PotentiometerPIDTest.cpp
index aa76700def..b9517025e6 100644
--- a/wpilibcExamples/src/test/cpp/examples/PotentiometerPID/cpp/PotentiometerPIDTest.cpp
+++ b/wpilibcExamples/src/test/cpp/examples/PotentiometerPID/cpp/PotentiometerPIDTest.cpp
@@ -70,7 +70,7 @@ class PotentiometerPIDTest : public testing::Test {
frc::sim::PauseTiming();
frc::sim::DriverStationSim::ResetData();
- m_joystickSim.SetButtonCount(12);
+ m_joystickSim.SetButtonsMaximumIndex(12);
m_callback =
HALSIM_RegisterSimPeriodicBeforeCallback(CallSimPeriodicBefore, this);
diff --git a/wpilibj/src/generate/hids.json b/wpilibj/src/generate/hids.json
index 2b8baaf921..9bf8a8f3d1 100644
--- a/wpilibj/src/generate/hids.json
+++ b/wpilibj/src/generate/hids.json
@@ -6,50 +6,50 @@
"buttons": [
{
"name": "a",
- "value": 1,
+ "value": 0,
"DocName": "A"
},
{
"name": "b",
- "value": 2,
+ "value": 1,
"DocName": "B"
},
{
"name": "x",
- "value": 3,
+ "value": 2,
"DocName": "X"
},
{
"name": "y",
- "value": 4,
+ "value": 3,
"DocName": "Y"
},
{
"name": "leftBumper",
- "value": 5,
+ "value": 4,
"DocName": "left bumper"
},
{
"name": "rightBumper",
- "value": 6,
+ "value": 5,
"DocName": "right bumper"
},
{
"name": "back",
- "value": 7
+ "value": 6
},
{
"name": "start",
- "value": 8
+ "value": 7
},
{
"name": "leftStick",
- "value": 9,
+ "value": 8,
"DocName": "left stick"
},
{
"name": "rightStick",
- "value": 10,
+ "value": 9,
"DocName": "right stick"
}
],
@@ -109,66 +109,66 @@
"buttons": [
{
"name": "square",
- "value": 1
+ "value": 0
},
{
"name": "cross",
- "value": 2
+ "value": 1
},
{
"name": "circle",
- "value": 3
+ "value": 2
},
{
"name": "triangle",
- "value": 4
+ "value": 3
},
{
"name": "L1",
- "value": 5,
+ "value": 4,
"DocName": "left trigger 1"
},
{
"name": "R1",
- "value": 6,
+ "value": 5,
"DocName": "right trigger 1"
},
{
"name": "L2",
- "value": 7,
+ "value": 6,
"DocName": "left trigger 2"
},
{
"name": "R2",
- "value": 8,
+ "value": 7,
"DocName": "right trigger 2"
},
{
"name": "share",
- "value": 9
+ "value": 8
},
{
"name": "options",
- "value": 10
+ "value": 9
},
{
"name": "L3",
- "value": 11,
+ "value": 10,
"DocName": "L3 (left stick)"
},
{
"name": "R3",
- "value": 12,
+ "value": 11,
"DocName": "R3 (right stick)"
},
{
"name": "PS",
- "value": 13,
+ "value": 12,
"DocName": "PlayStation"
},
{
"name": "touchpad",
- "value": 14
+ "value": 13
}
],
"sticks": [
@@ -227,66 +227,66 @@
"buttons": [
{
"name": "square",
- "value": 1
+ "value": 0
},
{
"name": "cross",
- "value": 2
+ "value": 1
},
{
"name": "circle",
- "value": 3
+ "value": 2
},
{
"name": "triangle",
- "value": 4
+ "value": 3
},
{
"name": "L1",
- "value": 5,
+ "value": 4,
"DocName": "left trigger 1"
},
{
"name": "R1",
- "value": 6,
+ "value": 5,
"DocName": "right trigger 1"
},
{
"name": "L2",
- "value": 7,
+ "value": 6,
"DocName": "left trigger 2"
},
{
"name": "R2",
- "value": 8,
+ "value": 7,
"DocName": "right trigger 2"
},
{
"name": "create",
- "value": 9
+ "value": 8
},
{
"name": "options",
- "value": 10
+ "value": 9
},
{
"name": "L3",
- "value": 11,
+ "value": 10,
"DocName": "L3 (left stick)"
},
{
"name": "R3",
- "value": 12,
+ "value": 11,
"DocName": "R3 (right stick)"
},
{
"name": "PS",
- "value": 13,
+ "value": 12,
"DocName": "PlayStation"
},
{
"name": "touchpad",
- "value": 14
+ "value": 13
}
],
"sticks": [
@@ -345,73 +345,73 @@
"buttons": [
{
"name": "a",
- "value": 1,
+ "value": 0,
"DocName": "A"
},
{
"name": "b",
- "value": 2,
+ "value": 1,
"DocName": "B"
},
{
"name": "x",
- "value": 3,
+ "value": 2,
"DocName": "X"
},
{
"name": "y",
- "value": 4,
+ "value": 3,
"DocName": "Y"
},
{
"name": "leftBumper",
- "value": 5,
+ "value": 4,
"DocName": "left bumper"
},
{
"name": "rightBumper",
- "value": 6,
+ "value": 5,
"DocName": "right bumper"
},
{
"name": "leftStick",
- "value": 7,
+ "value": 6,
"DocName": "left stick"
},
{
"name": "rightStick",
- "value": 8,
+ "value": 7,
"DocName": "right stick"
},
{
"name": "ellipses",
- "value": 9
+ "value": 8
},
{
"name": "hamburger",
- "value": 10
+ "value": 9
},
{
"name": "stadia",
- "value": 11
+ "value": 10
},
{
"name": "rightTrigger",
- "value": 12,
+ "value": 11,
"DocName": "right trigger"
},
{
"name": "leftTrigger",
- "value": 13,
+ "value": 12,
"DocName": "left trigger"
},
{
"name": "google",
- "value": 14
+ "value": 13
},
{
"name": "frame",
- "value": 15
+ "value": 14
}
],
"sticks": [
diff --git a/wpilibj/src/generate/main/java/hidsim.java.jinja b/wpilibj/src/generate/main/java/hidsim.java.jinja
index fa041ca828..0fb21c8bd2 100644
--- a/wpilibj/src/generate/main/java/hidsim.java.jinja
+++ b/wpilibj/src/generate/main/java/hidsim.java.jinja
@@ -20,9 +20,9 @@ public class {{ ConsoleName }}ControllerSim extends GenericHIDSim {
@SuppressWarnings("this-escape")
public {{ ConsoleName }}ControllerSim({{ ConsoleName }}Controller joystick) {
super(joystick);
- setAxisCount({{ sticks|length + triggers|length }});
- setButtonCount({{ buttons|length }});
- setPOVCount(1);
+ setAxesMaximumIndex({{ sticks|length + triggers|length }});
+ setButtonsMaximumIndex({{ buttons|length }});
+ setPOVsMaximumIndex(1);
}
/**
@@ -33,9 +33,9 @@ public class {{ ConsoleName }}ControllerSim extends GenericHIDSim {
@SuppressWarnings("this-escape")
public {{ ConsoleName }}ControllerSim(int port) {
super(port);
- setAxisCount({{ sticks|length + triggers|length }});
- setButtonCount({{ buttons|length }});
- setPOVCount(1);
+ setAxesMaximumIndex({{ sticks|length + triggers|length }});
+ setButtonsMaximumIndex({{ buttons|length }});
+ setPOVsMaximumIndex(1);
}
{% for stick in sticks %}
/**
diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java
index 8bb6a918b1..2487953caa 100644
--- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java
+++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java
@@ -27,33 +27,33 @@ public class PS4Controller extends GenericHID implements Sendable {
/** Represents a digital button on a PS4Controller. */
public enum Button {
/** Square button. */
- kSquare(1),
+ kSquare(0),
/** Cross button. */
- kCross(2),
+ kCross(1),
/** Circle button. */
- kCircle(3),
+ kCircle(2),
/** Triangle button. */
- kTriangle(4),
+ kTriangle(3),
/** Left trigger 1 button. */
- kL1(5),
+ kL1(4),
/** Right trigger 1 button. */
- kR1(6),
+ kR1(5),
/** Left trigger 2 button. */
- kL2(7),
+ kL2(6),
/** Right trigger 2 button. */
- kR2(8),
+ kR2(7),
/** Share button. */
- kShare(9),
+ kShare(8),
/** Options button. */
- kOptions(10),
+ kOptions(9),
/** L3 (left stick) button. */
- kL3(11),
+ kL3(10),
/** R3 (right stick) button. */
- kR3(12),
+ kR3(11),
/** PlayStation button. */
- kPS(13),
+ kPS(12),
/** Touchpad button. */
- kTouchpad(14);
+ kTouchpad(13);
/** Button value. */
public final int value;
diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java
index 06f82c50a2..6b323c37d7 100644
--- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java
+++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java
@@ -27,33 +27,33 @@ public class PS5Controller extends GenericHID implements Sendable {
/** Represents a digital button on a PS5Controller. */
public enum Button {
/** Square button. */
- kSquare(1),
+ kSquare(0),
/** Cross button. */
- kCross(2),
+ kCross(1),
/** Circle button. */
- kCircle(3),
+ kCircle(2),
/** Triangle button. */
- kTriangle(4),
+ kTriangle(3),
/** Left trigger 1 button. */
- kL1(5),
+ kL1(4),
/** Right trigger 1 button. */
- kR1(6),
+ kR1(5),
/** Left trigger 2 button. */
- kL2(7),
+ kL2(6),
/** Right trigger 2 button. */
- kR2(8),
+ kR2(7),
/** Create button. */
- kCreate(9),
+ kCreate(8),
/** Options button. */
- kOptions(10),
+ kOptions(9),
/** L3 (left stick) button. */
- kL3(11),
+ kL3(10),
/** R3 (right stick) button. */
- kR3(12),
+ kR3(11),
/** PlayStation button. */
- kPS(13),
+ kPS(12),
/** Touchpad button. */
- kTouchpad(14);
+ kTouchpad(13);
/** Button value. */
public final int value;
diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java
index 7dd1afed32..b6e89b3fa5 100644
--- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java
+++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java
@@ -27,35 +27,35 @@ public class StadiaController extends GenericHID implements Sendable {
/** Represents a digital button on a StadiaController. */
public enum Button {
/** A button. */
- kA(1),
+ kA(0),
/** B button. */
- kB(2),
+ kB(1),
/** X button. */
- kX(3),
+ kX(2),
/** Y button. */
- kY(4),
+ kY(3),
/** Left bumper button. */
- kLeftBumper(5),
+ kLeftBumper(4),
/** Right bumper button. */
- kRightBumper(6),
+ kRightBumper(5),
/** Left stick button. */
- kLeftStick(7),
+ kLeftStick(6),
/** Right stick button. */
- kRightStick(8),
+ kRightStick(7),
/** Ellipses button. */
- kEllipses(9),
+ kEllipses(8),
/** Hamburger button. */
- kHamburger(10),
+ kHamburger(9),
/** Stadia button. */
- kStadia(11),
+ kStadia(10),
/** Right trigger button. */
- kRightTrigger(12),
+ kRightTrigger(11),
/** Left trigger button. */
- kLeftTrigger(13),
+ kLeftTrigger(12),
/** Google button. */
- kGoogle(14),
+ kGoogle(13),
/** Frame button. */
- kFrame(15);
+ kFrame(14);
/** Button value. */
public final int value;
diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java
index f888248a84..cd046da504 100644
--- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java
+++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java
@@ -27,25 +27,25 @@ public class XboxController extends GenericHID implements Sendable {
/** Represents a digital button on a XboxController. */
public enum Button {
/** A button. */
- kA(1),
+ kA(0),
/** B button. */
- kB(2),
+ kB(1),
/** X button. */
- kX(3),
+ kX(2),
/** Y button. */
- kY(4),
+ kY(3),
/** Left bumper button. */
- kLeftBumper(5),
+ kLeftBumper(4),
/** Right bumper button. */
- kRightBumper(6),
+ kRightBumper(5),
/** Back button. */
- kBack(7),
+ kBack(6),
/** Start button. */
- kStart(8),
+ kStart(7),
/** Left stick button. */
- kLeftStick(9),
+ kLeftStick(8),
/** Right stick button. */
- kRightStick(10);
+ kRightStick(9);
/** Button value. */
public final int value;
diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/PS4ControllerSim.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/PS4ControllerSim.java
index 889eb18d80..6e23f0510c 100644
--- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/PS4ControllerSim.java
+++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/PS4ControllerSim.java
@@ -18,9 +18,9 @@ public class PS4ControllerSim extends GenericHIDSim {
@SuppressWarnings("this-escape")
public PS4ControllerSim(PS4Controller joystick) {
super(joystick);
- setAxisCount(6);
- setButtonCount(14);
- setPOVCount(1);
+ setAxesMaximumIndex(6);
+ setButtonsMaximumIndex(14);
+ setPOVsMaximumIndex(1);
}
/**
@@ -31,9 +31,9 @@ public class PS4ControllerSim extends GenericHIDSim {
@SuppressWarnings("this-escape")
public PS4ControllerSim(int port) {
super(port);
- setAxisCount(6);
- setButtonCount(14);
- setPOVCount(1);
+ setAxesMaximumIndex(6);
+ setButtonsMaximumIndex(14);
+ setPOVsMaximumIndex(1);
}
/**
diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/PS5ControllerSim.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/PS5ControllerSim.java
index 6e614a327d..32c85a4088 100644
--- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/PS5ControllerSim.java
+++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/PS5ControllerSim.java
@@ -18,9 +18,9 @@ public class PS5ControllerSim extends GenericHIDSim {
@SuppressWarnings("this-escape")
public PS5ControllerSim(PS5Controller joystick) {
super(joystick);
- setAxisCount(6);
- setButtonCount(14);
- setPOVCount(1);
+ setAxesMaximumIndex(6);
+ setButtonsMaximumIndex(14);
+ setPOVsMaximumIndex(1);
}
/**
@@ -31,9 +31,9 @@ public class PS5ControllerSim extends GenericHIDSim {
@SuppressWarnings("this-escape")
public PS5ControllerSim(int port) {
super(port);
- setAxisCount(6);
- setButtonCount(14);
- setPOVCount(1);
+ setAxesMaximumIndex(6);
+ setButtonsMaximumIndex(14);
+ setPOVsMaximumIndex(1);
}
/**
diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/StadiaControllerSim.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/StadiaControllerSim.java
index 4bde45da27..b6665e16d9 100644
--- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/StadiaControllerSim.java
+++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/StadiaControllerSim.java
@@ -18,9 +18,9 @@ public class StadiaControllerSim extends GenericHIDSim {
@SuppressWarnings("this-escape")
public StadiaControllerSim(StadiaController joystick) {
super(joystick);
- setAxisCount(4);
- setButtonCount(15);
- setPOVCount(1);
+ setAxesMaximumIndex(4);
+ setButtonsMaximumIndex(15);
+ setPOVsMaximumIndex(1);
}
/**
@@ -31,9 +31,9 @@ public class StadiaControllerSim extends GenericHIDSim {
@SuppressWarnings("this-escape")
public StadiaControllerSim(int port) {
super(port);
- setAxisCount(4);
- setButtonCount(15);
- setPOVCount(1);
+ setAxesMaximumIndex(4);
+ setButtonsMaximumIndex(15);
+ setPOVsMaximumIndex(1);
}
/**
diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/XboxControllerSim.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/XboxControllerSim.java
index d52fdd84d2..f04d70d745 100644
--- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/XboxControllerSim.java
+++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/simulation/XboxControllerSim.java
@@ -18,9 +18,9 @@ public class XboxControllerSim extends GenericHIDSim {
@SuppressWarnings("this-escape")
public XboxControllerSim(XboxController joystick) {
super(joystick);
- setAxisCount(6);
- setButtonCount(10);
- setPOVCount(1);
+ setAxesMaximumIndex(6);
+ setButtonsMaximumIndex(10);
+ setPOVsMaximumIndex(1);
}
/**
@@ -31,9 +31,9 @@ public class XboxControllerSim extends GenericHIDSim {
@SuppressWarnings("this-escape")
public XboxControllerSim(int port) {
super(port);
- setAxisCount(6);
- setButtonCount(10);
- setPOVCount(1);
+ setAxesMaximumIndex(6);
+ setButtonsMaximumIndex(10);
+ setPOVsMaximumIndex(1);
}
/**
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java
index 937c53484d..39877bf596 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java
@@ -22,9 +22,9 @@ import edu.wpi.first.networktables.StringPublisher;
import edu.wpi.first.networktables.StringTopic;
import edu.wpi.first.util.EventVector;
import edu.wpi.first.util.WPIUtilJNI;
-import java.nio.ByteBuffer;
import java.util.Map;
import java.util.Optional;
+import java.util.OptionalDouble;
import java.util.OptionalInt;
import java.util.concurrent.locks.ReentrantLock;
@@ -33,14 +33,32 @@ public final class DriverStation {
/** Number of Joystick ports. */
public static final int kJoystickPorts = 6;
+ private static final long[] m_metadataCache = new long[4];
+
+ private static int availableToCount(long available) {
+ // Top bit has to be set
+ if (available < 0) {
+ return 64;
+ }
+
+ int count = 0;
+
+ // Top bit not set, we will eventually get a 0 bit
+ while ((available & 0x1) != 0) {
+ count++;
+ available >>= 1;
+ }
+ return count;
+ }
+
private static final class HALJoystickButtons {
- public int m_buttons;
- public byte m_count;
+ public long m_buttons;
+ public long m_available;
}
private static class HALJoystickAxes {
public final float[] m_axes;
- public int m_count;
+ public int m_available;
HALJoystickAxes(int count) {
m_axes = new float[count];
@@ -51,7 +69,7 @@ public final class DriverStation {
public final short[] m_axes;
@SuppressWarnings("unused")
- public int m_count;
+ public int m_available;
HALJoystickAxesRaw(int count) {
m_axes = new short[count];
@@ -60,7 +78,7 @@ public final class DriverStation {
private static class HALJoystickPOVs {
public final byte[] m_povs;
- public int m_count;
+ public int m_available;
HALJoystickPOVs(int count) {
m_povs = new byte[count];
@@ -294,18 +312,18 @@ public final class DriverStation {
public void send(long timestamp) {
HALJoystickButtons buttons = m_joystickButtons[m_stick];
- if (buttons.m_count != m_prevButtons.m_count
+ if (buttons.m_available != m_prevButtons.m_available
|| buttons.m_buttons != m_prevButtons.m_buttons) {
appendButtons(buttons, timestamp);
}
HALJoystickAxes axes = m_joystickAxes[m_stick];
- int count = axes.m_count;
+ int available = axes.m_available;
boolean needToLog = false;
- if (count != m_prevAxes.m_count) {
+ if (available != m_prevAxes.m_available) {
needToLog = true;
} else {
- for (int i = 0; i < count; i++) {
+ for (int i = 0; i < m_prevAxes.m_axes.length; i++) {
if (axes.m_axes[i] != m_prevAxes.m_axes[i]) {
needToLog = true;
break;
@@ -317,12 +335,12 @@ public final class DriverStation {
}
HALJoystickPOVs povs = m_joystickPOVs[m_stick];
- count = m_joystickPOVs[m_stick].m_count;
+ available = m_joystickPOVs[m_stick].m_available;
needToLog = false;
- if (count != m_prevPOVs.m_count) {
+ if (available != m_prevPOVs.m_available) {
needToLog = true;
} else {
- for (int i = 0; i < count; i++) {
+ for (int i = 0; i < m_prevPOVs.m_povs.length; i++) {
if (povs.m_povs[i] != m_prevPOVs.m_povs[i]) {
needToLog = true;
break;
@@ -335,32 +353,32 @@ public final class DriverStation {
}
void appendButtons(HALJoystickButtons buttons, long timestamp) {
- byte count = buttons.m_count;
+ int count = availableToCount(buttons.m_available);
if (m_sizedButtons == null || m_sizedButtons.length != count) {
m_sizedButtons = new boolean[count];
}
- int buttonsValue = buttons.m_buttons;
+ long buttonsValue = buttons.m_buttons;
for (int i = 0; i < count; i++) {
- m_sizedButtons[i] = (buttonsValue & (1 << i)) != 0;
+ m_sizedButtons[i] = (buttonsValue & (1L << i)) != 0;
}
m_logButtons.append(m_sizedButtons, timestamp);
- m_prevButtons.m_count = count;
+ m_prevButtons.m_available = buttons.m_available;
m_prevButtons.m_buttons = buttons.m_buttons;
}
void appendAxes(HALJoystickAxes axes, long timestamp) {
- int count = axes.m_count;
+ int count = availableToCount(axes.m_available);
if (m_sizedAxes == null || m_sizedAxes.length != count) {
m_sizedAxes = new float[count];
}
System.arraycopy(axes.m_axes, 0, m_sizedAxes, 0, count);
m_logAxes.append(m_sizedAxes, timestamp);
- m_prevAxes.m_count = count;
+ m_prevAxes.m_available = axes.m_available;
System.arraycopy(axes.m_axes, 0, m_prevAxes.m_axes, 0, count);
}
void appendPOVs(HALJoystickPOVs povs, long timestamp) {
- int count = povs.m_count;
+ int count = availableToCount(povs.m_available);
if (m_sizedPOVs == null || m_sizedPOVs.length != count) {
m_sizedPOVs = new long[count];
}
@@ -368,7 +386,7 @@ public final class DriverStation {
m_sizedPOVs[i] = povs.m_povs[i];
}
m_logPOVs.append(m_sizedPOVs, timestamp);
- m_prevPOVs.m_count = count;
+ m_prevPOVs.m_available = povs.m_available;
System.arraycopy(povs.m_povs, 0, m_prevPOVs.m_povs, 0, count);
}
@@ -476,11 +494,8 @@ public final class DriverStation {
private static ControlWord m_controlWordCache = new ControlWord();
// Joystick button rising/falling edge flags
- private static int[] m_joystickButtonsPressed = new int[kJoystickPorts];
- private static int[] m_joystickButtonsReleased = new int[kJoystickPorts];
-
- // preallocated byte buffer for button count
- private static final ByteBuffer m_buttonCountBuffer = ByteBuffer.allocateDirect(1);
+ private static long[] m_joystickButtonsPressed = new long[kJoystickPorts];
+ private static long[] m_joystickButtonsReleased = new long[kJoystickPorts];
private static final MatchDataSender m_matchDataSender;
private static DataLogSender m_dataLogSender;
@@ -595,25 +610,26 @@ public final class DriverStation {
}
/**
- * The state of one joystick button. Button indexes begin at 1.
+ * The state of one joystick button.
*
* @param stick The joystick to read.
- * @param button The button index, beginning at 1.
+ * @param button The button index.
* @return The state of the joystick button.
*/
public static boolean getStickButton(final int stick, final int button) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
- if (button <= 0) {
- reportJoystickUnpluggedError("Button indexes begin at 1 in WPILib for C++ and Java\n");
- return false;
+ if (button < 0 || button >= DriverStationJNI.kMaxJoystickButtons) {
+ throw new IllegalArgumentException("Joystick Button is out of range");
}
+ long mask = 1L << button;
+
m_cacheDataMutex.lock();
try {
- if (button <= m_joystickButtons[stick].m_count) {
- return (m_joystickButtons[stick].m_buttons & 1 << (button - 1)) != 0;
+ if ((m_joystickButtons[stick].m_available & mask) != 0) {
+ return (m_joystickButtons[stick].m_buttons & mask) != 0;
}
} finally {
m_cacheDataMutex.unlock();
@@ -629,27 +645,56 @@ public final class DriverStation {
}
/**
- * Whether one joystick button was pressed since the last check. Button indexes begin at 1.
+ * The state of one joystick button if available.
*
* @param stick The joystick to read.
- * @param button The button index, beginning at 1.
- * @return Whether the joystick button was pressed since the last check.
+ * @param button The button index.
+ * @return The state of the joystick button, or false if the button is not available.
*/
- public static boolean getStickButtonPressed(final int stick, final int button) {
- if (button <= 0) {
- reportJoystickUnpluggedError("Button indexes begin at 1 in WPILib for C++ and Java\n");
- return false;
- }
+ public static Optional getStickButtonIfAvailable(final int stick, final int button) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
+ if (button < 0 || button >= DriverStationJNI.kMaxJoystickButtons) {
+ throw new IllegalArgumentException("Joystick Button is out of range");
+ }
+
+ long mask = 1L << button;
m_cacheDataMutex.lock();
try {
- if (button <= m_joystickButtons[stick].m_count) {
+ if ((m_joystickButtons[stick].m_available & mask) != 0) {
+ return Optional.of((m_joystickButtons[stick].m_buttons & mask) != 0);
+ }
+ } finally {
+ m_cacheDataMutex.unlock();
+ }
+ return Optional.empty();
+ }
+
+ /**
+ * Whether one joystick button was pressed since the last check.
+ *
+ * @param stick The joystick to read.
+ * @param button The button index.
+ * @return Whether the joystick button was pressed since the last check.
+ */
+ public static boolean getStickButtonPressed(final int stick, final int button) {
+ if (stick < 0 || stick >= kJoystickPorts) {
+ throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
+ }
+ if (button < 0 || button >= DriverStationJNI.kMaxJoystickButtons) {
+ throw new IllegalArgumentException("Joystick Button is out of range");
+ }
+
+ long mask = 1L << button;
+
+ m_cacheDataMutex.lock();
+ try {
+ if ((m_joystickButtons[stick].m_available & mask) != 0) {
// If button was pressed, clear flag and return true
- if ((m_joystickButtonsPressed[stick] & 1 << (button - 1)) != 0) {
- m_joystickButtonsPressed[stick] &= ~(1 << (button - 1));
+ if ((m_joystickButtonsPressed[stick] & mask) != 0) {
+ m_joystickButtonsPressed[stick] &= ~mask;
return true;
} else {
return false;
@@ -669,27 +714,28 @@ public final class DriverStation {
}
/**
- * Whether one joystick button was released since the last check. Button indexes begin at 1.
+ * Whether one joystick button was released since the last check.
*
* @param stick The joystick to read.
- * @param button The button index, beginning at 1.
+ * @param button The button index, beginning at 0.
* @return Whether the joystick button was released since the last check.
*/
public static boolean getStickButtonReleased(final int stick, final int button) {
- if (button <= 0) {
- reportJoystickUnpluggedError("Button indexes begin at 1 in WPILib for C++ and Java\n");
- return false;
- }
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
+ if (button < 0 || button >= DriverStationJNI.kMaxJoystickButtons) {
+ throw new IllegalArgumentException("Joystick Button is out of range");
+ }
+
+ long mask = 1L << button;
m_cacheDataMutex.lock();
try {
- if (button <= m_joystickButtons[stick].m_count) {
+ if ((m_joystickButtons[stick].m_available & mask) != 0) {
// If button was released, clear flag and return true
- if ((m_joystickButtonsReleased[stick] & 1 << (button - 1)) != 0) {
- m_joystickButtonsReleased[stick] &= ~(1 << (button - 1));
+ if ((m_joystickButtonsReleased[stick] & mask) != 0) {
+ m_joystickButtonsReleased[stick] &= ~mask;
return true;
} else {
return false;
@@ -724,9 +770,11 @@ public final class DriverStation {
throw new IllegalArgumentException("Joystick axis is out of range");
}
+ int mask = 1 << axis;
+
m_cacheDataMutex.lock();
try {
- if (axis < m_joystickAxes[stick].m_count) {
+ if ((m_joystickAxes[stick].m_available & mask) != 0) {
return m_joystickAxes[stick].m_axes[axis];
}
} finally {
@@ -742,6 +790,36 @@ public final class DriverStation {
return 0.0;
}
+ /**
+ * Get the value of the axis on a joystick if available. This depends on the mapping of the
+ * joystick connected to the specified port.
+ *
+ * @param stick The joystick to read.
+ * @param axis The analog axis value to read from the joystick.
+ * @return The value of the axis on the joystick, or 0 if the axis is not available.
+ */
+ public static OptionalDouble getStickAxisIfAvailable(int stick, int axis) {
+ if (stick < 0 || stick >= kJoystickPorts) {
+ throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
+ }
+ if (axis < 0 || axis >= DriverStationJNI.kMaxJoystickAxes) {
+ throw new IllegalArgumentException("Joystick axis is out of range");
+ }
+
+ int mask = 1 << axis;
+
+ m_cacheDataMutex.lock();
+ try {
+ if ((m_joystickAxes[stick].m_available & mask) != 0) {
+ return OptionalDouble.of(m_joystickAxes[stick].m_axes[axis]);
+ }
+ } finally {
+ m_cacheDataMutex.unlock();
+ }
+
+ return OptionalDouble.empty();
+ }
+
/**
* Get the state of a POV on the joystick.
*
@@ -757,9 +835,11 @@ public final class DriverStation {
throw new IllegalArgumentException("Joystick POV is out of range");
}
+ int mask = 1 << pov;
+
m_cacheDataMutex.lock();
try {
- if (pov < m_joystickPOVs[stick].m_count) {
+ if ((m_joystickPOVs[stick].m_available & mask) != 0) {
return POVDirection.of(m_joystickPOVs[stick].m_povs[pov]);
}
} finally {
@@ -781,7 +861,7 @@ public final class DriverStation {
* @param stick The joystick to read.
* @return The state of the buttons on the joystick.
*/
- public static int getStickButtons(final int stick) {
+ public static long getStickButtons(final int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
@@ -795,57 +875,87 @@ public final class DriverStation {
}
/**
- * Returns the number of axes on a given joystick port.
+ * Gets the maximum index of axes on a given joystick port.
*
* @param stick The joystick port number
- * @return The number of axes on the indicated joystick
+ * @return The maximum index of axes on the indicated joystick
*/
- public static int getStickAxisCount(int stick) {
+ public static int getStickAxesMaximumIndex(int stick) {
+ return availableToCount(getStickAxesAvailable(stick));
+ }
+
+ /**
+ * Returns the available bitmask of axes on a given joystick port.
+ *
+ * @param stick The joystick port number
+ * @return The number of axes available on the indicated joystick
+ */
+ public static int getStickAxesAvailable(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
m_cacheDataMutex.lock();
try {
- return m_joystickAxes[stick].m_count;
+ return m_joystickAxes[stick].m_available;
} finally {
m_cacheDataMutex.unlock();
}
}
/**
- * Returns the number of povs on a given joystick port.
+ * Gets the maximum index of povs on a given joystick port.
*
* @param stick The joystick port number
- * @return The number of povs on the indicated joystick
+ * @return The maximum index of povs on the indicated joystick
*/
- public static int getStickPOVCount(int stick) {
+ public static int getStickPOVsMaximumIndex(int stick) {
+ return availableToCount(getStickPOVsAvailable(stick));
+ }
+
+ /**
+ * Returns the available bitmask of povs on a given joystick port.
+ *
+ * @param stick The joystick port number
+ * @return The number of povs available on the indicated joystick
+ */
+ public static int getStickPOVsAvailable(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
m_cacheDataMutex.lock();
try {
- return m_joystickPOVs[stick].m_count;
+ return m_joystickPOVs[stick].m_available;
} finally {
m_cacheDataMutex.unlock();
}
}
/**
- * Gets the number of buttons on a joystick.
+ * Gets the maximum index of buttons on a given joystick port.
*
* @param stick The joystick port number
- * @return The number of buttons on the indicated joystick
+ * @return The maximum index of buttons on the indicated joystick
*/
- public static int getStickButtonCount(int stick) {
+ public static int getStickButtonsMaximumIndex(int stick) {
+ return availableToCount(getStickButtonsAvailable(stick));
+ }
+
+ /**
+ * Gets the bitmask of buttons available.
+ *
+ * @param stick The joystick port number
+ * @return The buttons available on the indicated joystick
+ */
+ public static long getStickButtonsAvailable(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
m_cacheDataMutex.lock();
try {
- return m_joystickButtons[stick].m_count;
+ return m_joystickButtons[stick].m_available;
} finally {
m_cacheDataMutex.unlock();
}
@@ -893,21 +1003,6 @@ public final class DriverStation {
return DriverStationJNI.getJoystickName((byte) stick);
}
- /**
- * Returns the types of Axes on a given joystick port.
- *
- * @param stick The joystick port number
- * @param axis The target axis
- * @return What type of axis the axis is reporting to be
- */
- public static int getJoystickAxisType(int stick, int axis) {
- if (stick < 0 || stick >= kJoystickPorts) {
- throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
- }
-
- return DriverStationJNI.getJoystickAxisType((byte) stick, (byte) axis);
- }
-
/**
* Returns if a joystick is connected to the Driver Station.
*
@@ -918,9 +1013,9 @@ public final class DriverStation {
* @return true if a joystick is connected
*/
public static boolean isJoystickConnected(int stick) {
- return getStickAxisCount(stick) > 0
- || getStickButtonCount(stick) > 0
- || getStickPOVCount(stick) > 0;
+ return getStickAxesAvailable(stick) != 0
+ || getStickButtonsAvailable(stick) != 0
+ || getStickPOVsAvailable(stick) != 0;
}
/**
@@ -1284,15 +1379,17 @@ public final class DriverStation {
// Get the status of all the joysticks
for (byte stick = 0; stick < kJoystickPorts; stick++) {
- m_joystickAxesCache[stick].m_count =
- DriverStationJNI.getJoystickAxes(stick, m_joystickAxesCache[stick].m_axes);
- m_joystickAxesRawCache[stick].m_count =
- DriverStationJNI.getJoystickAxesRaw(stick, m_joystickAxesRawCache[stick].m_axes);
- m_joystickPOVsCache[stick].m_count =
- DriverStationJNI.getJoystickPOVs(stick, m_joystickPOVsCache[stick].m_povs);
- m_joystickButtonsCache[stick].m_buttons =
- DriverStationJNI.getJoystickButtons(stick, m_buttonCountBuffer);
- m_joystickButtonsCache[stick].m_count = m_buttonCountBuffer.get(0);
+ DriverStationJNI.getAllJoystickData(
+ stick,
+ m_joystickAxesCache[stick].m_axes,
+ m_joystickAxesRawCache[stick].m_axes,
+ m_joystickPOVsCache[stick].m_povs,
+ m_metadataCache);
+ m_joystickAxesCache[stick].m_available = (int) m_metadataCache[0];
+ m_joystickAxesRawCache[stick].m_available = (int) m_metadataCache[0];
+ m_joystickPOVsCache[stick].m_available = (int) m_metadataCache[1];
+ m_joystickButtonsCache[stick].m_available = m_metadataCache[2];
+ m_joystickButtonsCache[stick].m_buttons = m_metadataCache[3];
}
DriverStationJNI.getMatchInfo(m_matchInfoCache);
@@ -1369,18 +1466,6 @@ public final class DriverStation {
m_refreshEvents.remove(handle);
}
- /**
- * Reports errors related to unplugged joysticks Throttles the errors so that they don't overwhelm
- * the DS.
- */
- private static void reportJoystickUnpluggedError(String message) {
- double currentTime = Timer.getTimestamp();
- if (currentTime > m_nextMessageTime) {
- reportError(message, false);
- m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL;
- }
- }
-
/**
* Reports errors related to unplugged joysticks Throttles the errors so that they don't overwhelm
* the DS.
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Gamepad.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Gamepad.java
new file mode 100644
index 0000000000..4c235aa1e5
--- /dev/null
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Gamepad.java
@@ -0,0 +1,1311 @@
+// 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;
+
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.util.sendable.Sendable;
+import edu.wpi.first.util.sendable.SendableBuilder;
+import edu.wpi.first.wpilibj.event.BooleanEvent;
+import edu.wpi.first.wpilibj.event.EventLoop;
+
+/**
+ * Handle input from Gamepad controllers connected to the Driver Station.
+ *
+ * This class handles Gamepad input that comes from the Driver Station. Each time a value is
+ * requested the most recent value is returned. There is a single class instance for each controller
+ * and the mapping of ports to hardware buttons depends on the code in the Driver Station.
+ *
+ *
Only first party controllers from Generic are guaranteed to have the correct mapping, and only
+ * through the official NI DS. Sim is not guaranteed to have the same mapping, as well as any 3rd
+ * party controllers.
+ */
+public class Gamepad extends GenericHID implements Sendable {
+ /** Represents a digital button on a Gamepad. */
+ public enum Button {
+ /** South Face button. */
+ kSouthFace(0),
+ /** East Face button. */
+ kEastFace(1),
+ /** West Face button. */
+ kWestFace(2),
+ /** North Face button. */
+ kNorthFacen(3),
+ /** Back button. */
+ kBack(4),
+ /** Guide button. */
+ kGuide(5),
+ /** Start button. */
+ kStart(6),
+ /** Left stick button. */
+ kLeftStick(7),
+ /** Right stick button. */
+ kRightStick(8),
+ /** Right shoulder button. */
+ kLeftShoulder(9),
+ /** Right shoulder button. */
+ kRightShoulder(10),
+ /** D-pad up button. */
+ kDpadUp(11),
+ /** D-pad down button. */
+ kDpadDown(12),
+ /** D-pad left button. */
+ kDpadLeft(13),
+ /** D-pad right button. */
+ kDpadRight(14),
+ /** Miscellaneous 1 button. */
+ kMisc1(15),
+ /** Right Paddle 1 button. */
+ kRightPaddle1(16),
+ /** Left Paddle 1 button. */
+ kLeftPaddle1(17),
+ /** Right Paddle 2 button. */
+ kRightPaddle2(18),
+ /** Left Paddle 2 button. */
+ kLeftPaddle2(19),
+ /** Touchpad button. */
+ kTouchpad(20),
+ /** Miscellaneous 2 button. */
+ kMisc2(21),
+ /** Miscellaneous 3 button. */
+ kMisc3(22),
+ /** Miscellaneous 4 button. */
+ kMisc4(23),
+ /** Miscellaneous 5 button. */
+ kMisc5(24),
+ /** Miscellaneous 6 button. */
+ kMisc6(25);
+
+ /** Button value. */
+ public final int value;
+
+ Button(int value) {
+ this.value = value;
+ }
+
+ /**
+ * Get the human-friendly name of the button, matching the relevant methods. This is done by
+ * stripping the leading `k`, and appending `Button`.
+ *
+ *
Primarily used for automated unit tests.
+ *
+ * @return the human-friendly name of the button.
+ */
+ @Override
+ public String toString() {
+ // Remove leading `k`
+ return this.name().substring(1) + "Button";
+ }
+ }
+
+ /** Represents an axis on an Gamepad. */
+ public enum Axis {
+ /** Left X axis. */
+ kLeftX(0),
+ /** Left Y axis. */
+ kLeftY(1),
+ /** Right X axis. */
+ kRightX(2),
+ /** Right Y axis. */
+ kRightY(3),
+ /** Left trigger. */
+ kLeftTrigger(4),
+ /** Right trigger. */
+ kRightTrigger(5);
+
+ /** Axis value. */
+ public final int value;
+
+ Axis(int value) {
+ this.value = value;
+ }
+
+ /**
+ * Get the human-friendly name of the axis, matching the relevant methods. This is done by
+ * stripping the leading `k`, and appending `Axis` if the name ends with `Trigger`.
+ *
+ *
Primarily used for automated unit tests.
+ *
+ * @return the human-friendly name of the axis.
+ */
+ @Override
+ public String toString() {
+ var name = this.name().substring(1); // Remove leading `k`
+ if (name.endsWith("Trigger")) {
+ return name + "Axis";
+ }
+ return name;
+ }
+ }
+
+ /**
+ * Construct an instance of a controller.
+ *
+ * @param port The port index on the Driver Station that the controller is plugged into (0-5).
+ */
+ public Gamepad(final int port) {
+ super(port);
+ HAL.reportUsage("HID", port, "Gamepad");
+ }
+
+ /**
+ * Get the X axis value of left side of the controller. Right is positive.
+ *
+ * @return The axis value.
+ */
+ public double getLeftX() {
+ return getRawAxis(Axis.kLeftX.value);
+ }
+
+ /**
+ * Get the Y axis value of left side of the controller. Back is positive.
+ *
+ * @return The axis value.
+ */
+ public double getLeftY() {
+ return getRawAxis(Axis.kLeftY.value);
+ }
+
+ /**
+ * Get the X axis value of right side of the controller. Right is positive.
+ *
+ * @return The axis value.
+ */
+ public double getRightX() {
+ return getRawAxis(Axis.kRightX.value);
+ }
+
+ /**
+ * Get the Y axis value of right side of the controller. Back is positive.
+ *
+ * @return The axis value.
+ */
+ public double getRightY() {
+ return getRawAxis(Axis.kRightY.value);
+ }
+
+ /**
+ * Get the left trigger axis value of the controller. Note that this axis is bound to the range of
+ * [0, 1] as opposed to the usual [-1, 1].
+ *
+ * @return The axis value.
+ */
+ public double getLeftTriggerAxis() {
+ return getRawAxis(Axis.kLeftTrigger.value);
+ }
+
+ /**
+ * Constructs an event instance around the axis value of the left trigger. The returned trigger
+ * will be true when the axis value is greater than {@code threshold}.
+ *
+ * @param threshold the minimum axis value for the returned {@link BooleanEvent} to be true. This
+ * value should be in the range [0, 1] where 0 is the unpressed state of the axis.
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance that is true when the left trigger's axis exceeds the provided
+ * threshold, attached to the given event loop
+ */
+ public BooleanEvent leftTrigger(double threshold, EventLoop loop) {
+ return axisGreaterThan(Axis.kLeftTrigger.value, threshold, loop);
+ }
+
+ /**
+ * Constructs an event instance around the axis value of the left trigger. The returned trigger
+ * will be true when the axis value is greater than 0.5.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance that is true when the left trigger's axis exceeds the provided
+ * threshold, attached to the given event loop
+ */
+ public BooleanEvent leftTrigger(EventLoop loop) {
+ return leftTrigger(0.5, loop);
+ }
+
+ /**
+ * Get the right trigger axis value of the controller. Note that this axis is bound to the range
+ * of [0, 1] as opposed to the usual [-1, 1].
+ *
+ * @return The axis value.
+ */
+ public double getRightTriggerAxis() {
+ return getRawAxis(Axis.kRightTrigger.value);
+ }
+
+ /**
+ * Constructs an event instance around the axis value of the right trigger. The returned trigger
+ * will be true when the axis value is greater than {@code threshold}.
+ *
+ * @param threshold the minimum axis value for the returned {@link BooleanEvent} to be true. This
+ * value should be in the range [0, 1] where 0 is the unpressed state of the axis.
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance that is true when the right trigger's axis exceeds the provided
+ * threshold, attached to the given event loop
+ */
+ public BooleanEvent rightTrigger(double threshold, EventLoop loop) {
+ return axisGreaterThan(Axis.kRightTrigger.value, threshold, loop);
+ }
+
+ /**
+ * Constructs an event instance around the axis value of the right trigger. The returned trigger
+ * will be true when the axis value is greater than 0.5.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance that is true when the right trigger's axis exceeds the provided
+ * threshold, attached to the given event loop
+ */
+ public BooleanEvent rightTrigger(EventLoop loop) {
+ return rightTrigger(0.5, loop);
+ }
+
+ /**
+ * Read the value of the South Face button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getSouthFaceButton() {
+ return getRawButton(Button.kSouthFace.value);
+ }
+
+ /**
+ * Whether the South Face button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getSouthFaceButtonPressed() {
+ return getRawButtonPressed(Button.kSouthFace.value);
+ }
+
+ /**
+ * Whether the South Face button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getSouthFaceButtonReleased() {
+ return getRawButtonReleased(Button.kSouthFace.value);
+ }
+
+ /**
+ * Constructs an event instance around the South Face button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the South Face button's digital signal attached to the
+ * given loop.
+ */
+ public BooleanEvent southFace(EventLoop loop) {
+ return button(Button.kSouthFace.value, loop);
+ }
+
+ /**
+ * Read the value of the East Face button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getEastFaceButton() {
+ return getRawButton(Button.kEastFace.value);
+ }
+
+ /**
+ * Whether the East Face button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getEastFaceButtonPressed() {
+ return getRawButtonPressed(Button.kEastFace.value);
+ }
+
+ /**
+ * Whether the East Face button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getEastFaceButtonReleased() {
+ return getRawButtonReleased(Button.kEastFace.value);
+ }
+
+ /**
+ * Constructs an event instance around the East Face button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the East Face button's digital signal attached to the
+ * given loop.
+ */
+ public BooleanEvent eastFace(EventLoop loop) {
+ return button(Button.kEastFace.value, loop);
+ }
+
+ /**
+ * Read the value of the West Face button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getWestFaceButton() {
+ return getRawButton(Button.kWestFace.value);
+ }
+
+ /**
+ * Whether the West Face button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getWestFaceButtonPressed() {
+ return getRawButtonPressed(Button.kWestFace.value);
+ }
+
+ /**
+ * Whether the West Face button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getWestFaceButtonReleased() {
+ return getRawButtonReleased(Button.kWestFace.value);
+ }
+
+ /**
+ * Constructs an event instance around the West Face button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the West Face button's digital signal attached to the
+ * given loop.
+ */
+ public BooleanEvent westFace(EventLoop loop) {
+ return button(Button.kWestFace.value, loop);
+ }
+
+ /**
+ * Read the value of the North Face button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getNorthFacenButton() {
+ return getRawButton(Button.kNorthFacen.value);
+ }
+
+ /**
+ * Whether the North Face button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getNorthFacenButtonPressed() {
+ return getRawButtonPressed(Button.kNorthFacen.value);
+ }
+
+ /**
+ * Whether the North Face button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getNorthFacenButtonReleased() {
+ return getRawButtonReleased(Button.kNorthFacen.value);
+ }
+
+ /**
+ * Constructs an event instance around the North Face button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the North Face button's digital signal attached to the
+ * given loop.
+ */
+ public BooleanEvent northFacen(EventLoop loop) {
+ return button(Button.kNorthFacen.value, loop);
+ }
+
+ /**
+ * Read the value of the Back button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getBackButton() {
+ return getRawButton(Button.kBack.value);
+ }
+
+ /**
+ * Whether the Back button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getBackButtonPressed() {
+ return getRawButtonPressed(Button.kBack.value);
+ }
+
+ /**
+ * Whether the Back button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getBackButtonReleased() {
+ return getRawButtonReleased(Button.kBack.value);
+ }
+
+ /**
+ * Constructs an event instance around the Back button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Back button's digital signal attached to the given
+ * loop.
+ */
+ public BooleanEvent back(EventLoop loop) {
+ return button(Button.kBack.value, loop);
+ }
+
+ /**
+ * Read the value of the Guide button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getGuideButton() {
+ return getRawButton(Button.kGuide.value);
+ }
+
+ /**
+ * Whether the Guide button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getGuideButtonPressed() {
+ return getRawButtonPressed(Button.kGuide.value);
+ }
+
+ /**
+ * Whether the Guide button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getGuideButtonReleased() {
+ return getRawButtonReleased(Button.kGuide.value);
+ }
+
+ /**
+ * Constructs an event instance around the Guide button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Guide button's digital signal attached to the given
+ * loop.
+ */
+ public BooleanEvent guide(EventLoop loop) {
+ return button(Button.kGuide.value, loop);
+ }
+
+ /**
+ * Read the value of the Start button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getStartButton() {
+ return getRawButton(Button.kStart.value);
+ }
+
+ /**
+ * Whether the Start button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getStartButtonPressed() {
+ return getRawButtonPressed(Button.kStart.value);
+ }
+
+ /**
+ * Whether the Start button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getStartButtonReleased() {
+ return getRawButtonReleased(Button.kStart.value);
+ }
+
+ /**
+ * Constructs an event instance around the Start button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Start button's digital signal attached to the given
+ * loop.
+ */
+ public BooleanEvent start(EventLoop loop) {
+ return button(Button.kStart.value, loop);
+ }
+
+ /**
+ * Read the value of the left stick button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getLeftStickButton() {
+ return getRawButton(Button.kLeftStick.value);
+ }
+
+ /**
+ * Whether the left stick button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getLeftStickButtonPressed() {
+ return getRawButtonPressed(Button.kLeftStick.value);
+ }
+
+ /**
+ * Whether the left stick button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getLeftStickButtonReleased() {
+ return getRawButtonReleased(Button.kLeftStick.value);
+ }
+
+ /**
+ * Constructs an event instance around the left stick button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the left stick button's digital signal attached to the
+ * given loop.
+ */
+ public BooleanEvent leftStick(EventLoop loop) {
+ return button(Button.kLeftStick.value, loop);
+ }
+
+ /**
+ * Read the value of the right stick button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getRightStickButton() {
+ return getRawButton(Button.kRightStick.value);
+ }
+
+ /**
+ * Whether the right stick button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getRightStickButtonPressed() {
+ return getRawButtonPressed(Button.kRightStick.value);
+ }
+
+ /**
+ * Whether the right stick button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getRightStickButtonReleased() {
+ return getRawButtonReleased(Button.kRightStick.value);
+ }
+
+ /**
+ * Constructs an event instance around the right stick button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the right stick button's digital signal attached to the
+ * given loop.
+ */
+ public BooleanEvent rightStick(EventLoop loop) {
+ return button(Button.kRightStick.value, loop);
+ }
+
+ /**
+ * Read the value of the right shoulder button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getLeftShoulderButton() {
+ return getRawButton(Button.kLeftShoulder.value);
+ }
+
+ /**
+ * Whether the right shoulder button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getLeftShoulderButtonPressed() {
+ return getRawButtonPressed(Button.kLeftShoulder.value);
+ }
+
+ /**
+ * Whether the right shoulder button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getLeftShoulderButtonReleased() {
+ return getRawButtonReleased(Button.kLeftShoulder.value);
+ }
+
+ /**
+ * Constructs an event instance around the right shoulder button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the right shoulder button's digital signal attached to
+ * the given loop.
+ */
+ public BooleanEvent leftShoulder(EventLoop loop) {
+ return button(Button.kLeftShoulder.value, loop);
+ }
+
+ /**
+ * Read the value of the right shoulder button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getRightShoulderButton() {
+ return getRawButton(Button.kRightShoulder.value);
+ }
+
+ /**
+ * Whether the right shoulder button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getRightShoulderButtonPressed() {
+ return getRawButtonPressed(Button.kRightShoulder.value);
+ }
+
+ /**
+ * Whether the right shoulder button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getRightShoulderButtonReleased() {
+ return getRawButtonReleased(Button.kRightShoulder.value);
+ }
+
+ /**
+ * Constructs an event instance around the right shoulder button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the right shoulder button's digital signal attached to
+ * the given loop.
+ */
+ public BooleanEvent rightShoulder(EventLoop loop) {
+ return button(Button.kRightShoulder.value, loop);
+ }
+
+ /**
+ * Read the value of the D-pad up button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getDpadUpButton() {
+ return getRawButton(Button.kDpadUp.value);
+ }
+
+ /**
+ * Whether the D-pad up button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getDpadUpButtonPressed() {
+ return getRawButtonPressed(Button.kDpadUp.value);
+ }
+
+ /**
+ * Whether the D-pad up button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getDpadUpButtonReleased() {
+ return getRawButtonReleased(Button.kDpadUp.value);
+ }
+
+ /**
+ * Constructs an event instance around the D-pad up button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the D-pad up button's digital signal attached to the
+ * given loop.
+ */
+ public BooleanEvent dpadUp(EventLoop loop) {
+ return button(Button.kDpadUp.value, loop);
+ }
+
+ /**
+ * Read the value of the D-pad down button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getDpadDownButton() {
+ return getRawButton(Button.kDpadDown.value);
+ }
+
+ /**
+ * Whether the D-pad down button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getDpadDownButtonPressed() {
+ return getRawButtonPressed(Button.kDpadDown.value);
+ }
+
+ /**
+ * Whether the D-pad down button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getDpadDownButtonReleased() {
+ return getRawButtonReleased(Button.kDpadDown.value);
+ }
+
+ /**
+ * Constructs an event instance around the D-pad down button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the D-pad down button's digital signal attached to the
+ * given loop.
+ */
+ public BooleanEvent dpadDown(EventLoop loop) {
+ return button(Button.kDpadDown.value, loop);
+ }
+
+ /**
+ * Read the value of the D-pad left button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getDpadLeftButton() {
+ return getRawButton(Button.kDpadLeft.value);
+ }
+
+ /**
+ * Whether the D-pad left button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getDpadLeftButtonPressed() {
+ return getRawButtonPressed(Button.kDpadLeft.value);
+ }
+
+ /**
+ * Whether the D-pad left button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getDpadLeftButtonReleased() {
+ return getRawButtonReleased(Button.kDpadLeft.value);
+ }
+
+ /**
+ * Constructs an event instance around the D-pad left button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the D-pad left button's digital signal attached to the
+ * given loop.
+ */
+ public BooleanEvent dpadLeft(EventLoop loop) {
+ return button(Button.kDpadLeft.value, loop);
+ }
+
+ /**
+ * Read the value of the D-pad right button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getDpadRightButton() {
+ return getRawButton(Button.kDpadRight.value);
+ }
+
+ /**
+ * Whether the D-pad right button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getDpadRightButtonPressed() {
+ return getRawButtonPressed(Button.kDpadRight.value);
+ }
+
+ /**
+ * Whether the D-pad right button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getDpadRightButtonReleased() {
+ return getRawButtonReleased(Button.kDpadRight.value);
+ }
+
+ /**
+ * Constructs an event instance around the D-pad right button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the D-pad right button's digital signal attached to the
+ * given loop.
+ */
+ public BooleanEvent dpadRight(EventLoop loop) {
+ return button(Button.kDpadRight.value, loop);
+ }
+
+ /**
+ * Read the value of the Miscellaneous 1 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getMisc1Button() {
+ return getRawButton(Button.kMisc1.value);
+ }
+
+ /**
+ * Whether the Miscellaneous 1 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getMisc1ButtonPressed() {
+ return getRawButtonPressed(Button.kMisc1.value);
+ }
+
+ /**
+ * Whether the Miscellaneous 1 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getMisc1ButtonReleased() {
+ return getRawButtonReleased(Button.kMisc1.value);
+ }
+
+ /**
+ * Constructs an event instance around the Miscellaneous 1 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Miscellaneous 1 button's digital signal attached to
+ * the given loop.
+ */
+ public BooleanEvent misc1(EventLoop loop) {
+ return button(Button.kMisc1.value, loop);
+ }
+
+ /**
+ * Read the value of the Right Paddle 1 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getRightPaddle1Button() {
+ return getRawButton(Button.kRightPaddle1.value);
+ }
+
+ /**
+ * Whether the Right Paddle 1 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getRightPaddle1ButtonPressed() {
+ return getRawButtonPressed(Button.kRightPaddle1.value);
+ }
+
+ /**
+ * Whether the Right Paddle 1 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getRightPaddle1ButtonReleased() {
+ return getRawButtonReleased(Button.kRightPaddle1.value);
+ }
+
+ /**
+ * Constructs an event instance around the Right Paddle 1 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Right Paddle 1 button's digital signal attached to
+ * the given loop.
+ */
+ public BooleanEvent rightPaddle1(EventLoop loop) {
+ return button(Button.kRightPaddle1.value, loop);
+ }
+
+ /**
+ * Read the value of the Left Paddle 1 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getLeftPaddle1Button() {
+ return getRawButton(Button.kLeftPaddle1.value);
+ }
+
+ /**
+ * Whether the Left Paddle 1 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getLeftPaddle1ButtonPressed() {
+ return getRawButtonPressed(Button.kLeftPaddle1.value);
+ }
+
+ /**
+ * Whether the Left Paddle 1 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getLeftPaddle1ButtonReleased() {
+ return getRawButtonReleased(Button.kLeftPaddle1.value);
+ }
+
+ /**
+ * Constructs an event instance around the Left Paddle 1 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Left Paddle 1 button's digital signal attached to
+ * the given loop.
+ */
+ public BooleanEvent leftPaddle1(EventLoop loop) {
+ return button(Button.kLeftPaddle1.value, loop);
+ }
+
+ /**
+ * Read the value of the Right Paddle 2 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getRightPaddle2Button() {
+ return getRawButton(Button.kRightPaddle2.value);
+ }
+
+ /**
+ * Whether the Right Paddle 2 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getRightPaddle2ButtonPressed() {
+ return getRawButtonPressed(Button.kRightPaddle2.value);
+ }
+
+ /**
+ * Whether the Right Paddle 2 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getRightPaddle2ButtonReleased() {
+ return getRawButtonReleased(Button.kRightPaddle2.value);
+ }
+
+ /**
+ * Constructs an event instance around the Right Paddle 2 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Right Paddle 2 button's digital signal attached to
+ * the given loop.
+ */
+ public BooleanEvent rightPaddle2(EventLoop loop) {
+ return button(Button.kRightPaddle2.value, loop);
+ }
+
+ /**
+ * Read the value of the Left Paddle 2 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getLeftPaddle2Button() {
+ return getRawButton(Button.kLeftPaddle2.value);
+ }
+
+ /**
+ * Whether the Left Paddle 2 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getLeftPaddle2ButtonPressed() {
+ return getRawButtonPressed(Button.kLeftPaddle2.value);
+ }
+
+ /**
+ * Whether the Left Paddle 2 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getLeftPaddle2ButtonReleased() {
+ return getRawButtonReleased(Button.kLeftPaddle2.value);
+ }
+
+ /**
+ * Constructs an event instance around the Left Paddle 2 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Left Paddle 2 button's digital signal attached to
+ * the given loop.
+ */
+ public BooleanEvent leftPaddle2(EventLoop loop) {
+ return button(Button.kLeftPaddle2.value, loop);
+ }
+
+ /**
+ * Read the value of the Touchpad button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getTouchpadButton() {
+ return getRawButton(Button.kTouchpad.value);
+ }
+
+ /**
+ * Whether the Touchpad button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getTouchpadButtonPressed() {
+ return getRawButtonPressed(Button.kTouchpad.value);
+ }
+
+ /**
+ * Whether the Touchpad button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getTouchpadButtonReleased() {
+ return getRawButtonReleased(Button.kTouchpad.value);
+ }
+
+ /**
+ * Constructs an event instance around the Touchpad button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Touchpad button's digital signal attached to the
+ * given loop.
+ */
+ public BooleanEvent touchpad(EventLoop loop) {
+ return button(Button.kTouchpad.value, loop);
+ }
+
+ /**
+ * Read the value of the Miscellaneous 2 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getMisc2Button() {
+ return getRawButton(Button.kMisc2.value);
+ }
+
+ /**
+ * Whether the Miscellaneous 2 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getMisc2ButtonPressed() {
+ return getRawButtonPressed(Button.kMisc2.value);
+ }
+
+ /**
+ * Whether the Miscellaneous 2 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getMisc2ButtonReleased() {
+ return getRawButtonReleased(Button.kMisc2.value);
+ }
+
+ /**
+ * Constructs an event instance around the Miscellaneous 2 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Miscellaneous 2 button's digital signal attached to
+ * the given loop.
+ */
+ public BooleanEvent misc2(EventLoop loop) {
+ return button(Button.kMisc2.value, loop);
+ }
+
+ /**
+ * Read the value of the Miscellaneous 3 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getMisc3Button() {
+ return getRawButton(Button.kMisc3.value);
+ }
+
+ /**
+ * Whether the Miscellaneous 3 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getMisc3ButtonPressed() {
+ return getRawButtonPressed(Button.kMisc3.value);
+ }
+
+ /**
+ * Whether the Miscellaneous 3 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getMisc3ButtonReleased() {
+ return getRawButtonReleased(Button.kMisc3.value);
+ }
+
+ /**
+ * Constructs an event instance around the Miscellaneous 3 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Miscellaneous 3 button's digital signal attached to
+ * the given loop.
+ */
+ public BooleanEvent misc3(EventLoop loop) {
+ return button(Button.kMisc3.value, loop);
+ }
+
+ /**
+ * Read the value of the Miscellaneous 4 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getMisc4Button() {
+ return getRawButton(Button.kMisc4.value);
+ }
+
+ /**
+ * Whether the Miscellaneous 4 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getMisc4ButtonPressed() {
+ return getRawButtonPressed(Button.kMisc4.value);
+ }
+
+ /**
+ * Whether the Miscellaneous 4 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getMisc4ButtonReleased() {
+ return getRawButtonReleased(Button.kMisc4.value);
+ }
+
+ /**
+ * Constructs an event instance around the Miscellaneous 4 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Miscellaneous 4 button's digital signal attached to
+ * the given loop.
+ */
+ public BooleanEvent misc4(EventLoop loop) {
+ return button(Button.kMisc4.value, loop);
+ }
+
+ /**
+ * Read the value of the Miscellaneous 5 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getMisc5Button() {
+ return getRawButton(Button.kMisc5.value);
+ }
+
+ /**
+ * Whether the Miscellaneous 5 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getMisc5ButtonPressed() {
+ return getRawButtonPressed(Button.kMisc5.value);
+ }
+
+ /**
+ * Whether the Miscellaneous 5 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getMisc5ButtonReleased() {
+ return getRawButtonReleased(Button.kMisc5.value);
+ }
+
+ /**
+ * Constructs an event instance around the Miscellaneous 5 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Miscellaneous 5 button's digital signal attached to
+ * the given loop.
+ */
+ public BooleanEvent misc5(EventLoop loop) {
+ return button(Button.kMisc5.value, loop);
+ }
+
+ /**
+ * Read the value of the Miscellaneous 6 button on the controller.
+ *
+ * @return The state of the button.
+ */
+ public boolean getMisc6Button() {
+ return getRawButton(Button.kMisc6.value);
+ }
+
+ /**
+ * Whether the Miscellaneous 6 button was pressed since the last check.
+ *
+ * @return Whether the button was pressed since the last check.
+ */
+ public boolean getMisc6ButtonPressed() {
+ return getRawButtonPressed(Button.kMisc6.value);
+ }
+
+ /**
+ * Whether the Miscellaneous 6 button was released since the last check.
+ *
+ * @return Whether the button was released since the last check.
+ */
+ public boolean getMisc6ButtonReleased() {
+ return getRawButtonReleased(Button.kMisc6.value);
+ }
+
+ /**
+ * Constructs an event instance around the Miscellaneous 6 button's digital signal.
+ *
+ * @param loop the event loop instance to attach the event to.
+ * @return an event instance representing the Miscellaneous 6 button's digital signal attached to
+ * the given loop.
+ */
+ public BooleanEvent misc6(EventLoop loop) {
+ return button(Button.kMisc6.value, loop);
+ }
+
+ private double getAxisForSendable(int axis) {
+ return DriverStation.getStickAxisIfAvailable(getPort(), axis).orElse(0.0);
+ }
+
+ private boolean getButtonForSendable(int button) {
+ return DriverStation.getStickButtonIfAvailable(getPort(), button).orElse(false);
+ }
+
+ @Override
+ public void initSendable(SendableBuilder builder) {
+ builder.setSmartDashboardType("HID");
+ builder.publishConstString("ControllerType", "Gamepad");
+ builder.addDoubleProperty(
+ "LeftTrigger Axis", () -> getAxisForSendable(Axis.kLeftTrigger.value), null);
+ builder.addDoubleProperty(
+ "RightTrigger Axis", () -> getAxisForSendable(Axis.kRightTrigger.value), null);
+ builder.addDoubleProperty("LeftX", () -> getAxisForSendable(Axis.kLeftX.value), null);
+ builder.addDoubleProperty("LeftY", () -> getAxisForSendable(Axis.kLeftY.value), null);
+ builder.addDoubleProperty("RightX", () -> getAxisForSendable(Axis.kRightX.value), null);
+ builder.addDoubleProperty("RightY", () -> getAxisForSendable(Axis.kRightY.value), null);
+ builder.addBooleanProperty(
+ "SouthFace", () -> getButtonForSendable(Button.kSouthFace.value), null);
+ builder.addBooleanProperty(
+ "EastFace", () -> getButtonForSendable(Button.kEastFace.value), null);
+ builder.addBooleanProperty(
+ "WestFace", () -> getButtonForSendable(Button.kWestFace.value), null);
+ builder.addBooleanProperty(
+ "NorthFacen", () -> getButtonForSendable(Button.kNorthFacen.value), null);
+ builder.addBooleanProperty("Back", () -> getButtonForSendable(Button.kBack.value), null);
+ builder.addBooleanProperty("Guide", () -> getButtonForSendable(Button.kGuide.value), null);
+ builder.addBooleanProperty("Start", () -> getButtonForSendable(Button.kStart.value), null);
+ builder.addBooleanProperty(
+ "LeftStick", () -> getButtonForSendable(Button.kLeftStick.value), null);
+ builder.addBooleanProperty(
+ "RightStick", () -> getButtonForSendable(Button.kRightStick.value), null);
+ builder.addBooleanProperty(
+ "LeftShoulder", () -> getButtonForSendable(Button.kLeftShoulder.value), null);
+ builder.addBooleanProperty(
+ "RightShoulder", () -> getButtonForSendable(Button.kRightShoulder.value), null);
+ builder.addBooleanProperty("DpadUp", () -> getButtonForSendable(Button.kDpadUp.value), null);
+ builder.addBooleanProperty(
+ "DpadDown", () -> getButtonForSendable(Button.kDpadDown.value), null);
+ builder.addBooleanProperty(
+ "DpadLeft", () -> getButtonForSendable(Button.kDpadLeft.value), null);
+ builder.addBooleanProperty(
+ "DpadRight", () -> getButtonForSendable(Button.kDpadRight.value), null);
+ builder.addBooleanProperty("Misc1", () -> getButtonForSendable(Button.kMisc1.value), null);
+ builder.addBooleanProperty(
+ "RightPaddle1", () -> getButtonForSendable(Button.kRightPaddle1.value), null);
+ builder.addBooleanProperty(
+ "LeftPaddle1", () -> getButtonForSendable(Button.kLeftPaddle1.value), null);
+ builder.addBooleanProperty(
+ "RightPaddle2", () -> getButtonForSendable(Button.kRightPaddle2.value), null);
+ builder.addBooleanProperty(
+ "LeftPaddle2", () -> getButtonForSendable(Button.kLeftPaddle2.value), null);
+ builder.addBooleanProperty(
+ "Touchpad", () -> getButtonForSendable(Button.kTouchpad.value), null);
+ builder.addBooleanProperty("Misc2", () -> getButtonForSendable(Button.kMisc2.value), null);
+ builder.addBooleanProperty("Misc3", () -> getButtonForSendable(Button.kMisc3.value), null);
+ builder.addBooleanProperty("Misc4", () -> getButtonForSendable(Button.kMisc4.value), null);
+ builder.addBooleanProperty("Misc5", () -> getButtonForSendable(Button.kMisc5.value), null);
+ builder.addBooleanProperty("Misc6", () -> getButtonForSendable(Button.kMisc6.value), null);
+ }
+}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java
index 78397f2862..475842b533 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java
@@ -136,7 +136,7 @@ public class GenericHID {
* time this method was called. This is useful if you only want to call a function once when you
* press the button.
*
- * @param button The button index, beginning at 1.
+ * @param button The button index, beginning at 0.
* @return Whether the button was pressed since the last check.
*/
public boolean getRawButtonPressed(int button) {
@@ -150,7 +150,7 @@ public class GenericHID {
* time this method was called. This is useful if you only want to call a function once when you
* release the button.
*
- * @param button The button index, beginning at 1.
+ * @param button The button index, beginning at 0.
* @return Whether the button was released since the last check.
*/
public boolean getRawButtonReleased(int button) {
@@ -364,13 +364,31 @@ public class GenericHID {
}
}
+ /**
+ * Get the maximum axis index for the joystick.
+ *
+ * @return the maximum axis index for the joystick
+ */
+ public int getAxesMaximumIndex() {
+ return DriverStation.getStickAxesMaximumIndex(m_port);
+ }
+
/**
* Get the number of axes for the HID.
*
* @return the number of axis for the current HID
*/
- public int getAxisCount() {
- return DriverStation.getStickAxisCount(m_port);
+ public int getAxesAvailable() {
+ return DriverStation.getStickAxesAvailable(m_port);
+ }
+
+ /**
+ * Get the maximum POV index for the joystick.
+ *
+ * @return the maximum POV index for the joystick
+ */
+ public int getPOVsMaximumIndex() {
+ return DriverStation.getStickPOVsMaximumIndex(m_port);
}
/**
@@ -378,8 +396,17 @@ public class GenericHID {
*
* @return the number of POVs for the current HID
*/
- public int getPOVCount() {
- return DriverStation.getStickPOVCount(m_port);
+ public int getPOVsAvailable() {
+ return DriverStation.getStickPOVsAvailable(m_port);
+ }
+
+ /**
+ * Get the maximum button index for the joystick.
+ *
+ * @return the maximum button index for the joystick
+ */
+ public int getButtonsMaximumIndex() {
+ return DriverStation.getStickButtonsMaximumIndex(m_port);
}
/**
@@ -387,8 +414,8 @@ public class GenericHID {
*
* @return the number of buttons for the current HID
*/
- public int getButtonCount() {
- return DriverStation.getStickButtonCount(m_port);
+ public long getButtonsAvailable() {
+ return DriverStation.getStickButtonsAvailable(m_port);
}
/**
@@ -418,16 +445,6 @@ public class GenericHID {
return DriverStation.getJoystickName(m_port);
}
- /**
- * Get the axis type of the provided joystick axis.
- *
- * @param axis The axis to read, starting at 0.
- * @return the axis type of the given joystick axis
- */
- public int getAxisType(int axis) {
- return DriverStation.getJoystickAxisType(m_port, axis);
- }
-
/**
* Get the port number of the HID.
*
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java
index fa7ef78c3b..ded2776cb4 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java
@@ -338,10 +338,10 @@ public final class DriverStationSim {
}
/**
- * Sets the state of one joystick button. Button indexes begin at 1.
+ * Sets the state of one joystick button. Button indexes begin at 0.
*
* @param stick The joystick number
- * @param button The button index, beginning at 1
+ * @param button The button index, beginning at 0
* @param state The state of the joystick button
*/
public static void setJoystickButton(int stick, int button, boolean state) {
@@ -371,13 +371,13 @@ public final class DriverStationSim {
}
/**
- * Sets the state of all the buttons on a joystick.
+ * Sets the maximum index that an axis is available at.
*
* @param stick The joystick number
- * @param buttons The bitmap state of the buttons on the joystick
+ * @param maximumIndex The maximum index an axis is available at.
*/
- public static void setJoystickButtons(int stick, int buttons) {
- DriverStationDataJNI.setJoystickButtonsValue(stick, buttons);
+ public static void setJoystickAxesMaximumIndex(int stick, int maximumIndex) {
+ setJoystickAxesAvailable(stick, (1 << maximumIndex) - 1);
}
/**
@@ -386,8 +386,18 @@ public final class DriverStationSim {
* @param stick The joystick number
* @param count The number of axes on the indicated joystick
*/
- public static void setJoystickAxisCount(int stick, int count) {
- DriverStationDataJNI.setJoystickAxisCount(stick, count);
+ public static void setJoystickAxesAvailable(int stick, int count) {
+ DriverStationDataJNI.setJoystickAxesAvailable(stick, count);
+ }
+
+ /**
+ * Sets the maximum index that a pov is available at.
+ *
+ * @param stick The joystick number
+ * @param maximumIndex The maximum index a pov is available at.
+ */
+ public static void setJoystickPOVsMaximumIndex(int stick, int maximumIndex) {
+ setJoystickPOVsAvailable(stick, (1 << maximumIndex) - 1);
}
/**
@@ -396,8 +406,22 @@ public final class DriverStationSim {
* @param stick The joystick number
* @param count The number of POVs on the indicated joystick
*/
- public static void setJoystickPOVCount(int stick, int count) {
- DriverStationDataJNI.setJoystickPOVCount(stick, count);
+ public static void setJoystickPOVsAvailable(int stick, int count) {
+ DriverStationDataJNI.setJoystickPOVsAvailable(stick, count);
+ }
+
+ /**
+ * Sets the maximum index that a button is available at.
+ *
+ * @param stick The joystick number
+ * @param maximumIndex The maximum index a button is available at.
+ */
+ public static void setJoystickButtonsMaximumIndex(int stick, int maximumIndex) {
+ if (maximumIndex >= 64) {
+ setJoystickButtonsAvailable(stick, 0xFFFFFFFFFFFFFFFFL);
+ } else {
+ setJoystickButtonsAvailable(stick, (1L << maximumIndex) - 1);
+ }
}
/**
@@ -406,8 +430,8 @@ public final class DriverStationSim {
* @param stick The joystick number
* @param count The number of buttons on the indicated joystick
*/
- public static void setJoystickButtonCount(int stick, int count) {
- DriverStationDataJNI.setJoystickButtonCount(stick, count);
+ public static void setJoystickButtonsAvailable(int stick, long count) {
+ DriverStationDataJNI.setJoystickButtonsAvailable(stick, count);
}
/**
@@ -440,17 +464,6 @@ public final class DriverStationSim {
DriverStationDataJNI.setJoystickName(stick, name);
}
- /**
- * Sets the types of Axes for a joystick.
- *
- * @param stick The joystick number
- * @param axis The target axis
- * @param type The type of axis
- */
- public static void setJoystickAxisType(int stick, int axis, int type) {
- DriverStationDataJNI.setJoystickAxisType(stick, axis, type);
- }
-
/**
* Sets the game specific message.
*
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/GamepadSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/GamepadSim.java
new file mode 100644
index 0000000000..3502e1cccc
--- /dev/null
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/GamepadSim.java
@@ -0,0 +1,324 @@
+// 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.simulation;
+
+import edu.wpi.first.wpilibj.Gamepad;
+
+/** Class to control a simulated Gamepad controller. */
+public class GamepadSim extends GenericHIDSim {
+ /**
+ * Constructs from a Gamepad object.
+ *
+ * @param joystick controller to simulate
+ */
+ @SuppressWarnings("this-escape")
+ public GamepadSim(Gamepad joystick) {
+ super(joystick);
+ setAxesMaximumIndex(6);
+ setButtonsMaximumIndex(26);
+ setPOVsMaximumIndex(1);
+ }
+
+ /**
+ * Constructs from a joystick port number.
+ *
+ * @param port port number
+ */
+ @SuppressWarnings("this-escape")
+ public GamepadSim(int port) {
+ super(port);
+ setAxesMaximumIndex(6);
+ setButtonsMaximumIndex(26);
+ setPOVsMaximumIndex(1);
+ }
+
+ /**
+ * Change the left X value of the controller's joystick.
+ *
+ * @param value the new value
+ */
+ public void setLeftX(double value) {
+ setRawAxis(Gamepad.Axis.kLeftX.value, value);
+ }
+
+ /**
+ * Change the left Y value of the controller's joystick.
+ *
+ * @param value the new value
+ */
+ public void setLeftY(double value) {
+ setRawAxis(Gamepad.Axis.kLeftY.value, value);
+ }
+
+ /**
+ * Change the right X value of the controller's joystick.
+ *
+ * @param value the new value
+ */
+ public void setRightX(double value) {
+ setRawAxis(Gamepad.Axis.kRightX.value, value);
+ }
+
+ /**
+ * Change the right Y value of the controller's joystick.
+ *
+ * @param value the new value
+ */
+ public void setRightY(double value) {
+ setRawAxis(Gamepad.Axis.kRightY.value, value);
+ }
+
+ /**
+ * Change the value of the left trigger axis on the controller.
+ *
+ * @param value the new value
+ */
+ public void setLeftTriggerAxis(double value) {
+ setRawAxis(Gamepad.Axis.kLeftTrigger.value, value);
+ }
+
+ /**
+ * Change the value of the right trigger axis on the controller.
+ *
+ * @param value the new value
+ */
+ public void setRightTriggerAxis(double value) {
+ setRawAxis(Gamepad.Axis.kRightTrigger.value, value);
+ }
+
+ /**
+ * Change the value of the South Face button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setSouthFaceButton(boolean value) {
+ setRawButton(Gamepad.Button.kSouthFace.value, value);
+ }
+
+ /**
+ * Change the value of the East Face button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setEastFaceButton(boolean value) {
+ setRawButton(Gamepad.Button.kEastFace.value, value);
+ }
+
+ /**
+ * Change the value of the West Face button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setWestFaceButton(boolean value) {
+ setRawButton(Gamepad.Button.kWestFace.value, value);
+ }
+
+ /**
+ * Change the value of the North Face button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setNorthFacenButton(boolean value) {
+ setRawButton(Gamepad.Button.kNorthFacen.value, value);
+ }
+
+ /**
+ * Change the value of the Back button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setBackButton(boolean value) {
+ setRawButton(Gamepad.Button.kBack.value, value);
+ }
+
+ /**
+ * Change the value of the Guide button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setGuideButton(boolean value) {
+ setRawButton(Gamepad.Button.kGuide.value, value);
+ }
+
+ /**
+ * Change the value of the Start button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setStartButton(boolean value) {
+ setRawButton(Gamepad.Button.kStart.value, value);
+ }
+
+ /**
+ * Change the value of the left stick button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setLeftStickButton(boolean value) {
+ setRawButton(Gamepad.Button.kLeftStick.value, value);
+ }
+
+ /**
+ * Change the value of the right stick button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setRightStickButton(boolean value) {
+ setRawButton(Gamepad.Button.kRightStick.value, value);
+ }
+
+ /**
+ * Change the value of the right shoulder button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setLeftShoulderButton(boolean value) {
+ setRawButton(Gamepad.Button.kLeftShoulder.value, value);
+ }
+
+ /**
+ * Change the value of the right shoulder button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setRightShoulderButton(boolean value) {
+ setRawButton(Gamepad.Button.kRightShoulder.value, value);
+ }
+
+ /**
+ * Change the value of the D-pad up button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setDpadUpButton(boolean value) {
+ setRawButton(Gamepad.Button.kDpadUp.value, value);
+ }
+
+ /**
+ * Change the value of the D-pad down button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setDpadDownButton(boolean value) {
+ setRawButton(Gamepad.Button.kDpadDown.value, value);
+ }
+
+ /**
+ * Change the value of the D-pad left button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setDpadLeftButton(boolean value) {
+ setRawButton(Gamepad.Button.kDpadLeft.value, value);
+ }
+
+ /**
+ * Change the value of the D-pad right button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setDpadRightButton(boolean value) {
+ setRawButton(Gamepad.Button.kDpadRight.value, value);
+ }
+
+ /**
+ * Change the value of the Miscellaneous 1 button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setMisc1Button(boolean value) {
+ setRawButton(Gamepad.Button.kMisc1.value, value);
+ }
+
+ /**
+ * Change the value of the Right Paddle 1 button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setRightPaddle1Button(boolean value) {
+ setRawButton(Gamepad.Button.kRightPaddle1.value, value);
+ }
+
+ /**
+ * Change the value of the Left Paddle 1 button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setLeftPaddle1Button(boolean value) {
+ setRawButton(Gamepad.Button.kLeftPaddle1.value, value);
+ }
+
+ /**
+ * Change the value of the Right Paddle 2 button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setRightPaddle2Button(boolean value) {
+ setRawButton(Gamepad.Button.kRightPaddle2.value, value);
+ }
+
+ /**
+ * Change the value of the Left Paddle 2 button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setLeftPaddle2Button(boolean value) {
+ setRawButton(Gamepad.Button.kLeftPaddle2.value, value);
+ }
+
+ /**
+ * Change the value of the Touchpad button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setTouchpadButton(boolean value) {
+ setRawButton(Gamepad.Button.kTouchpad.value, value);
+ }
+
+ /**
+ * Change the value of the Miscellaneous 2 button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setMisc2Button(boolean value) {
+ setRawButton(Gamepad.Button.kMisc2.value, value);
+ }
+
+ /**
+ * Change the value of the Miscellaneous 3 button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setMisc3Button(boolean value) {
+ setRawButton(Gamepad.Button.kMisc3.value, value);
+ }
+
+ /**
+ * Change the value of the Miscellaneous 4 button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setMisc4Button(boolean value) {
+ setRawButton(Gamepad.Button.kMisc4.value, value);
+ }
+
+ /**
+ * Change the value of the Miscellaneous 5 button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setMisc5Button(boolean value) {
+ setRawButton(Gamepad.Button.kMisc5.value, value);
+ }
+
+ /**
+ * Change the value of the Miscellaneous 6 button on the controller.
+ *
+ * @param value the new value
+ */
+ public void setMisc6Button(boolean value) {
+ setRawButton(Gamepad.Button.kMisc6.value, value);
+ }
+}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/GenericHIDSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/GenericHIDSim.java
index fb0d6211a6..a37d383e75 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/GenericHIDSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/GenericHIDSim.java
@@ -74,13 +74,31 @@ public class GenericHIDSim {
setPOV(0, value);
}
+ /**
+ * Set the maximum axis index for this device.
+ *
+ * @param maximumIndex the new maximum axis index
+ */
+ public void setAxesMaximumIndex(int maximumIndex) {
+ DriverStationSim.setJoystickAxesMaximumIndex(m_port, maximumIndex);
+ }
+
/**
* Set the axis count of this device.
*
* @param count the new axis count
*/
- public void setAxisCount(int count) {
- DriverStationSim.setJoystickAxisCount(m_port, count);
+ public void setAxesAvailable(int count) {
+ DriverStationSim.setJoystickAxesAvailable(m_port, count);
+ }
+
+ /**
+ * Set the maximum POV index for this device.
+ *
+ * @param maximumIndex the new maximum POV index
+ */
+ public void setPOVsMaximumIndex(int maximumIndex) {
+ DriverStationSim.setJoystickPOVsMaximumIndex(m_port, maximumIndex);
}
/**
@@ -88,8 +106,17 @@ public class GenericHIDSim {
*
* @param count the new POV count
*/
- public void setPOVCount(int count) {
- DriverStationSim.setJoystickPOVCount(m_port, count);
+ public void setPOVsAvailable(int count) {
+ DriverStationSim.setJoystickPOVsAvailable(m_port, count);
+ }
+
+ /**
+ * Set the maximum button index for this device.
+ *
+ * @param maximumIndex the new maximum button index
+ */
+ public void setButtonsMaximumIndex(int maximumIndex) {
+ DriverStationSim.setJoystickButtonsMaximumIndex(m_port, maximumIndex);
}
/**
@@ -97,8 +124,8 @@ public class GenericHIDSim {
*
* @param count the new button count
*/
- public void setButtonCount(int count) {
- DriverStationSim.setJoystickButtonCount(m_port, count);
+ public void setButtonsAvailable(long count) {
+ DriverStationSim.setJoystickButtonsAvailable(m_port, count);
}
/**
@@ -119,16 +146,6 @@ public class GenericHIDSim {
DriverStationSim.setJoystickName(m_port, name);
}
- /**
- * Set the type of the provided axis channel.
- *
- * @param axis the axis
- * @param type the type
- */
- public void setAxisType(int axis, int type) {
- DriverStationSim.setJoystickAxisType(m_port, axis, type);
- }
-
/**
* Read the output of a button.
*
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/JoystickSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/JoystickSim.java
index b6f21e313c..7db8009e2b 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/JoystickSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/JoystickSim.java
@@ -20,9 +20,9 @@ public class JoystickSim extends GenericHIDSim {
super(joystick);
m_joystick = joystick;
// default to a reasonable joystick configuration
- setAxisCount(5);
- setButtonCount(12);
- setPOVCount(1);
+ setAxesMaximumIndex(5);
+ setButtonsMaximumIndex(12);
+ setPOVsMaximumIndex(1);
}
/**
@@ -34,9 +34,9 @@ public class JoystickSim extends GenericHIDSim {
public JoystickSim(int port) {
super(port);
// default to a reasonable joystick configuration
- setAxisCount(5);
- setButtonCount(12);
- setPOVCount(1);
+ setAxesMaximumIndex(5);
+ setButtonsMaximumIndex(12);
+ setPOVsMaximumIndex(1);
}
/**
diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/DriverStationTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/DriverStationTest.java
index 5a446159ae..c60ece5e8a 100644
--- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/DriverStationTest.java
+++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/DriverStationTest.java
@@ -17,9 +17,9 @@ class DriverStationTest {
@ParameterizedTest
@MethodSource("isConnectedProvider")
void testIsConnected(int axisCount, int buttonCount, int povCount, boolean expected) {
- DriverStationSim.setJoystickAxisCount(1, axisCount);
- DriverStationSim.setJoystickButtonCount(1, buttonCount);
- DriverStationSim.setJoystickPOVCount(1, povCount);
+ DriverStationSim.setJoystickAxesMaximumIndex(1, axisCount);
+ DriverStationSim.setJoystickButtonsMaximumIndex(1, buttonCount);
+ DriverStationSim.setJoystickPOVsMaximumIndex(1, povCount);
DriverStationSim.notifyNewData();