diff --git a/glass/src/lib/native/cpp/hardware/Accelerometer.cpp b/glass/src/lib/native/cpp/hardware/Accelerometer.cpp deleted file mode 100644 index 6a1cc03a771..00000000000 --- a/glass/src/lib/native/cpp/hardware/Accelerometer.cpp +++ /dev/null @@ -1,50 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "glass/hardware/Accelerometer.h" - -#include "glass/DataSource.h" -#include "glass/other/DeviceTree.h" - -using namespace glass; - -void glass::DisplayAccelerometerDevice(AccelerometerModel* model) { - if (!model->Exists()) { - return; - } - if (BeginDevice("BuiltInAccel")) { - // Range - { - int value = model->GetRange(); - static const char* rangeOptions[] = {"2G", "4G", "8G"}; - DeviceEnum("Range", true, &value, rangeOptions, 3); - } - - // X Accel - if (auto xData = model->GetXData()) { - double value = xData->GetValue(); - if (DeviceDouble("X Accel", false, &value, xData)) { - model->SetX(value); - } - } - - // Y Accel - if (auto yData = model->GetYData()) { - double value = yData->GetValue(); - if (DeviceDouble("Y Accel", false, &value, yData)) { - model->SetY(value); - } - } - - // Z Accel - if (auto zData = model->GetZData()) { - double value = zData->GetValue(); - if (DeviceDouble("Z Accel", false, &value, zData)) { - model->SetZ(value); - } - } - - EndDevice(); - } -} diff --git a/glass/src/lib/native/include/glass/hardware/Accelerometer.h b/glass/src/lib/native/include/glass/hardware/Accelerometer.h deleted file mode 100644 index a5d38d525c2..00000000000 --- a/glass/src/lib/native/include/glass/hardware/Accelerometer.h +++ /dev/null @@ -1,29 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include "glass/Model.h" - -namespace glass { - -class DoubleSource; - -class AccelerometerModel : public Model { - public: - virtual DoubleSource* GetXData() = 0; - virtual DoubleSource* GetYData() = 0; - virtual DoubleSource* GetZData() = 0; - - virtual int GetRange() = 0; - - virtual void SetX(double val) = 0; - virtual void SetY(double val) = 0; - virtual void SetZ(double val) = 0; - virtual void SetRange(int val) = 0; -}; - -void DisplayAccelerometerDevice(AccelerometerModel* model); - -} // namespace glass diff --git a/hal/src/main/java/edu/wpi/first/hal/AccelerometerJNI.java b/hal/src/main/java/edu/wpi/first/hal/AccelerometerJNI.java deleted file mode 100644 index fc1bbb588f8..00000000000 --- a/hal/src/main/java/edu/wpi/first/hal/AccelerometerJNI.java +++ /dev/null @@ -1,65 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package edu.wpi.first.hal; - -/** - * Accelerometer HAL JNI methods. - * - * @see "hal/Accelerometer.h" - */ -public class AccelerometerJNI extends JNIWrapper { - /** - * Sets the accelerometer to active or standby mode. - * - *

It must be in standby mode to change any configuration. - * - * @see "HAL_SetAccelerometerActive" - * @param active true to set to active, false for standby - */ - public static native void setAccelerometerActive(boolean active); - - /** - * Sets the range of values that can be measured (either 2, 4, or 8 g-forces). - * - *

The accelerometer should be in standby mode when this is called. - * - * @see "HAL_SetAccelerometerRange(int range)" - * @param range the accelerometer range - */ - public static native void setAccelerometerRange(int range); - - /** - * Gets the x-axis acceleration. - * - *

This is a floating point value in units of 1 g-force. - * - * @see "HAL_GetAccelerometerX()" - * @return the X acceleration - */ - public static native double getAccelerometerX(); - - /** - * Gets the y-axis acceleration. - * - *

This is a floating point value in units of 1 g-force. - * - * @see "HAL_GetAccelerometerY()" - * @return the Y acceleration - */ - public static native double getAccelerometerY(); - - /** - * Gets the z-axis acceleration. - * - *

This is a floating point value in units of 1 g-force. - * - * @see "HAL_GetAccelerometerZ()" - * @return the Z acceleration - */ - public static native double getAccelerometerZ(); - - /** Utility class. */ - private AccelerometerJNI() {} -} diff --git a/hal/src/main/java/edu/wpi/first/hal/simulation/AccelerometerDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/simulation/AccelerometerDataJNI.java deleted file mode 100644 index 26975c08404..00000000000 --- a/hal/src/main/java/edu/wpi/first/hal/simulation/AccelerometerDataJNI.java +++ /dev/null @@ -1,68 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package edu.wpi.first.hal.simulation; - -import edu.wpi.first.hal.JNIWrapper; - -/** JNI for accelerometer data. */ -public class AccelerometerDataJNI extends JNIWrapper { - /** - * Register a callback to be run when this accelerometer activates. - * - * @param index the index - * @param callback the callback - * @param initialNotify whether to run the callback with the initial state - * @return the CallbackStore object associated with this callback - */ - public static native int registerActiveCallback( - int index, NotifyCallback callback, boolean initialNotify); - - public static native void cancelActiveCallback(int index, int uid); - - public static native boolean getActive(int index); - - public static native void setActive(int index, boolean active); - - public static native int registerRangeCallback( - int index, NotifyCallback callback, boolean initialNotify); - - public static native void cancelRangeCallback(int index, int uid); - - public static native int getRange(int index); - - public static native void setRange(int index, int range); - - public static native int registerXCallback( - int index, NotifyCallback callback, boolean initialNotify); - - public static native void cancelXCallback(int index, int uid); - - public static native double getX(int index); - - public static native void setX(int index, double x); - - public static native int registerYCallback( - int index, NotifyCallback callback, boolean initialNotify); - - public static native void cancelYCallback(int index, int uid); - - public static native double getY(int index); - - public static native void setY(int index, double y); - - public static native int registerZCallback( - int index, NotifyCallback callback, boolean initialNotify); - - public static native void cancelZCallback(int index, int uid); - - public static native double getZ(int index); - - public static native void setZ(int index, double z); - - public static native void resetData(int index); - - /** Utility class. */ - private AccelerometerDataJNI() {} -} diff --git a/hal/src/main/native/cpp/jni/AccelerometerJNI.cpp b/hal/src/main/native/cpp/jni/AccelerometerJNI.cpp deleted file mode 100644 index d2c107ec19f..00000000000 --- a/hal/src/main/native/cpp/jni/AccelerometerJNI.cpp +++ /dev/null @@ -1,72 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include - -#include "edu_wpi_first_hal_AccelerometerJNI.h" -#include "hal/Accelerometer.h" - -extern "C" { - -/* - * Class: edu_wpi_first_hal_AccelerometerJNI - * Method: setAccelerometerActive - * Signature: (Z)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_AccelerometerJNI_setAccelerometerActive - (JNIEnv*, jclass, jboolean active) -{ - HAL_SetAccelerometerActive(active); -} - -/* - * Class: edu_wpi_first_hal_AccelerometerJNI - * Method: setAccelerometerRange - * Signature: (I)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_AccelerometerJNI_setAccelerometerRange - (JNIEnv*, jclass, jint range) -{ - HAL_SetAccelerometerRange((HAL_AccelerometerRange)range); -} - -/* - * Class: edu_wpi_first_hal_AccelerometerJNI - * Method: getAccelerometerX - * Signature: ()D - */ -JNIEXPORT jdouble JNICALL -Java_edu_wpi_first_hal_AccelerometerJNI_getAccelerometerX - (JNIEnv*, jclass) -{ - return HAL_GetAccelerometerX(); -} - -/* - * Class: edu_wpi_first_hal_AccelerometerJNI - * Method: getAccelerometerY - * Signature: ()D - */ -JNIEXPORT jdouble JNICALL -Java_edu_wpi_first_hal_AccelerometerJNI_getAccelerometerY - (JNIEnv*, jclass) -{ - return HAL_GetAccelerometerY(); -} - -/* - * Class: edu_wpi_first_hal_AccelerometerJNI - * Method: getAccelerometerZ - * Signature: ()D - */ -JNIEXPORT jdouble JNICALL -Java_edu_wpi_first_hal_AccelerometerJNI_getAccelerometerZ - (JNIEnv*, jclass) -{ - return HAL_GetAccelerometerZ(); -} - -} // extern "C" diff --git a/hal/src/main/native/cpp/jni/simulation/AccelerometerDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/AccelerometerDataJNI.cpp deleted file mode 100644 index bc0b499d855..00000000000 --- a/hal/src/main/native/cpp/jni/simulation/AccelerometerDataJNI.cpp +++ /dev/null @@ -1,278 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include - -#include "CallbackStore.h" -#include "edu_wpi_first_hal_simulation_AccelerometerDataJNI.h" -#include "hal/simulation/AccelerometerData.h" - -using namespace hal; - -extern "C" { - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: registerActiveCallback - * Signature: (ILjava/lang/Object;Z)I - */ -JNIEXPORT jint JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_registerActiveCallback - (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify) -{ - return sim::AllocateCallback(env, index, callback, initialNotify, - &HALSIM_RegisterAccelerometerActiveCallback); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: cancelActiveCallback - * Signature: (II)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_cancelActiveCallback - (JNIEnv* env, jclass, jint index, jint handle) -{ - return sim::FreeCallback(env, handle, index, - &HALSIM_CancelAccelerometerActiveCallback); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: getActive - * Signature: (I)Z - */ -JNIEXPORT jboolean JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_getActive - (JNIEnv*, jclass, jint index) -{ - return HALSIM_GetAccelerometerActive(index); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: setActive - * Signature: (IZ)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_setActive - (JNIEnv*, jclass, jint index, jboolean value) -{ - HALSIM_SetAccelerometerActive(index, value); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: registerRangeCallback - * Signature: (ILjava/lang/Object;Z)I - */ -JNIEXPORT jint JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_registerRangeCallback - (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify) -{ - return sim::AllocateCallback(env, index, callback, initialNotify, - &HALSIM_RegisterAccelerometerRangeCallback); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: cancelRangeCallback - * Signature: (II)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_cancelRangeCallback - (JNIEnv* env, jclass, jint index, jint handle) -{ - return sim::FreeCallback(env, handle, index, - &HALSIM_CancelAccelerometerRangeCallback); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: getRange - * Signature: (I)I - */ -JNIEXPORT jint JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_getRange - (JNIEnv*, jclass, jint index) -{ - return HALSIM_GetAccelerometerRange(index); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: setRange - * Signature: (II)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_setRange - (JNIEnv*, jclass, jint index, jint value) -{ - HALSIM_SetAccelerometerRange(index, - static_cast(value)); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: registerXCallback - * Signature: (ILjava/lang/Object;Z)I - */ -JNIEXPORT jint JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_registerXCallback - (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify) -{ - return sim::AllocateCallback(env, index, callback, initialNotify, - &HALSIM_RegisterAccelerometerXCallback); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: cancelXCallback - * Signature: (II)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_cancelXCallback - (JNIEnv* env, jclass, jint index, jint handle) -{ - return sim::FreeCallback(env, handle, index, - &HALSIM_CancelAccelerometerXCallback); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: getX - * Signature: (I)D - */ -JNIEXPORT jdouble JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_getX - (JNIEnv*, jclass, jint index) -{ - return HALSIM_GetAccelerometerX(index); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: setX - * Signature: (ID)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_setX - (JNIEnv*, jclass, jint index, jdouble value) -{ - HALSIM_SetAccelerometerX(index, value); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: registerYCallback - * Signature: (ILjava/lang/Object;Z)I - */ -JNIEXPORT jint JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_registerYCallback - (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify) -{ - return sim::AllocateCallback(env, index, callback, initialNotify, - &HALSIM_RegisterAccelerometerYCallback); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: cancelYCallback - * Signature: (II)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_cancelYCallback - (JNIEnv* env, jclass, jint index, jint handle) -{ - return sim::FreeCallback(env, handle, index, - &HALSIM_CancelAccelerometerYCallback); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: getY - * Signature: (I)D - */ -JNIEXPORT jdouble JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_getY - (JNIEnv*, jclass, jint index) -{ - return HALSIM_GetAccelerometerY(index); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: setY - * Signature: (ID)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_setY - (JNIEnv*, jclass, jint index, jdouble value) -{ - HALSIM_SetAccelerometerY(index, value); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: registerZCallback - * Signature: (ILjava/lang/Object;Z)I - */ -JNIEXPORT jint JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_registerZCallback - (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify) -{ - return sim::AllocateCallback(env, index, callback, initialNotify, - &HALSIM_RegisterAccelerometerZCallback); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: cancelZCallback - * Signature: (II)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_cancelZCallback - (JNIEnv* env, jclass, jint index, jint handle) -{ - return sim::FreeCallback(env, handle, index, - &HALSIM_CancelAccelerometerZCallback); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: getZ - * Signature: (I)D - */ -JNIEXPORT jdouble JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_getZ - (JNIEnv*, jclass, jint index) -{ - return HALSIM_GetAccelerometerZ(index); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: setZ - * Signature: (ID)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_setZ - (JNIEnv*, jclass, jint index, jdouble value) -{ - HALSIM_SetAccelerometerZ(index, value); -} - -/* - * Class: edu_wpi_first_hal_simulation_AccelerometerDataJNI - * Method: resetData - * Signature: (I)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AccelerometerDataJNI_resetData - (JNIEnv*, jclass, jint index) -{ - HALSIM_ResetAccelerometerData(index); -} - -} // extern "C" diff --git a/hal/src/main/native/include/hal/Accelerometer.h b/hal/src/main/native/include/hal/Accelerometer.h deleted file mode 100644 index ab48ca53fe5..00000000000 --- a/hal/src/main/native/include/hal/Accelerometer.h +++ /dev/null @@ -1,74 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include "hal/Types.h" - -/** - * @defgroup hal_accelerometer Accelerometer Functions - * @ingroup hal_capi - * @{ - */ - -/** - * The acceptable accelerometer ranges. - */ -HAL_ENUM(HAL_AccelerometerRange) { - HAL_AccelerometerRange_k2G = 0, - HAL_AccelerometerRange_k4G = 1, - HAL_AccelerometerRange_k8G = 2, -}; - -#ifdef __cplusplus -extern "C" { -#endif -/** - * Sets the accelerometer to active or standby mode. - * - * It must be in standby mode to change any configuration. - * - * @param active true to set to active, false for standby - */ -void HAL_SetAccelerometerActive(HAL_Bool active); - -/** - * Sets the range of values that can be measured (either 2, 4, or 8 g-forces). - * - * The accelerometer should be in standby mode when this is called. - * - * @param range the accelerometer range - */ -void HAL_SetAccelerometerRange(HAL_AccelerometerRange range); - -/** - * Gets the x-axis acceleration. - * - * This is a floating point value in units of 1 g-force. - * - * @return the X acceleration - */ -double HAL_GetAccelerometerX(void); - -/** - * Gets the y-axis acceleration. - * - * This is a floating point value in units of 1 g-force. - * - * @return the Y acceleration - */ -double HAL_GetAccelerometerY(void); - -/** - * Gets the z-axis acceleration. - * - * This is a floating point value in units of 1 g-force. - * - * @return the Z acceleration - */ -double HAL_GetAccelerometerZ(void); -#ifdef __cplusplus -} // extern "C" -/** @} */ -#endif diff --git a/hal/src/main/native/include/hal/HAL.h b/hal/src/main/native/include/hal/HAL.h index 041fdd93024..4072b4a64d6 100644 --- a/hal/src/main/native/include/hal/HAL.h +++ b/hal/src/main/native/include/hal/HAL.h @@ -6,7 +6,6 @@ #include -#include "hal/Accelerometer.h" #include "hal/AnalogInput.h" #include "hal/AnalogTrigger.h" #include "hal/CAN.h" diff --git a/hal/src/main/native/include/hal/simulation/AccelerometerData.h b/hal/src/main/native/include/hal/simulation/AccelerometerData.h deleted file mode 100644 index 70cee615e26..00000000000 --- a/hal/src/main/native/include/hal/simulation/AccelerometerData.h +++ /dev/null @@ -1,63 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include "hal/Accelerometer.h" -#include "hal/Types.h" -#include "hal/simulation/NotifyListener.h" - -#ifdef __cplusplus -extern "C" { -#endif - -void HALSIM_ResetAccelerometerData(int32_t index); -int32_t HALSIM_RegisterAccelerometerActiveCallback(int32_t index, - HAL_NotifyCallback callback, - void* param, - HAL_Bool initialNotify); -void HALSIM_CancelAccelerometerActiveCallback(int32_t index, int32_t uid); -HAL_Bool HALSIM_GetAccelerometerActive(int32_t index); -void HALSIM_SetAccelerometerActive(int32_t index, HAL_Bool active); - -int32_t HALSIM_RegisterAccelerometerRangeCallback(int32_t index, - HAL_NotifyCallback callback, - void* param, - HAL_Bool initialNotify); -void HALSIM_CancelAccelerometerRangeCallback(int32_t index, int32_t uid); -HAL_AccelerometerRange HALSIM_GetAccelerometerRange(int32_t index); -void HALSIM_SetAccelerometerRange(int32_t index, HAL_AccelerometerRange range); - -int32_t HALSIM_RegisterAccelerometerXCallback(int32_t index, - HAL_NotifyCallback callback, - void* param, - HAL_Bool initialNotify); -void HALSIM_CancelAccelerometerXCallback(int32_t index, int32_t uid); -double HALSIM_GetAccelerometerX(int32_t index); -void HALSIM_SetAccelerometerX(int32_t index, double x); - -int32_t HALSIM_RegisterAccelerometerYCallback(int32_t index, - HAL_NotifyCallback callback, - void* param, - HAL_Bool initialNotify); -void HALSIM_CancelAccelerometerYCallback(int32_t index, int32_t uid); -double HALSIM_GetAccelerometerY(int32_t index); -void HALSIM_SetAccelerometerY(int32_t index, double y); - -int32_t HALSIM_RegisterAccelerometerZCallback(int32_t index, - HAL_NotifyCallback callback, - void* param, - HAL_Bool initialNotify); -void HALSIM_CancelAccelerometerZCallback(int32_t index, int32_t uid); -double HALSIM_GetAccelerometerZ(int32_t index); -void HALSIM_SetAccelerometerZ(int32_t index, double z); - -void HALSIM_RegisterAccelerometerAllCallbacks(int32_t index, - HAL_NotifyCallback callback, - void* param, - HAL_Bool initialNotify); - -#ifdef __cplusplus -} // extern "C" -#endif diff --git a/hal/src/main/native/sim/Accelerometer.cpp b/hal/src/main/native/sim/Accelerometer.cpp deleted file mode 100644 index 2756c9958c5..00000000000 --- a/hal/src/main/native/sim/Accelerometer.cpp +++ /dev/null @@ -1,32 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "hal/Accelerometer.h" - -#include "mockdata/AccelerometerDataInternal.h" - -using namespace hal; - -namespace hal::init { -void InitializeAccelerometer() {} -} // namespace hal::init - -extern "C" { -void HAL_SetAccelerometerActive(HAL_Bool active) { - SimAccelerometerData[0].active = active; -} - -void HAL_SetAccelerometerRange(HAL_AccelerometerRange range) { - SimAccelerometerData[0].range = range; -} -double HAL_GetAccelerometerX(void) { - return SimAccelerometerData[0].x; -} -double HAL_GetAccelerometerY(void) { - return SimAccelerometerData[0].y; -} -double HAL_GetAccelerometerZ(void) { - return SimAccelerometerData[0].z; -} -} // extern "C" diff --git a/hal/src/main/native/sim/HAL.cpp b/hal/src/main/native/sim/HAL.cpp index d69422e9375..26e97c68294 100644 --- a/hal/src/main/native/sim/HAL.cpp +++ b/hal/src/main/native/sim/HAL.cpp @@ -66,7 +66,6 @@ void InitializeDriverStation(); namespace hal::init { void InitializeHAL() { - InitializeAccelerometerData(); InitializeAddressableLEDData(); InitializeAnalogInData(); InitializeAnalogTriggerData(); @@ -84,7 +83,6 @@ void InitializeHAL() { InitializePWMData(); InitializeRoboRioData(); InitializeSimDeviceData(); - InitializeAccelerometer(); InitializeAddressableLED(); InitializeAnalogInput(); InitializeAnalogInternal(); diff --git a/hal/src/main/native/sim/HALInitializer.h b/hal/src/main/native/sim/HALInitializer.h index 4ccc10e8786..53841bbe452 100644 --- a/hal/src/main/native/sim/HALInitializer.h +++ b/hal/src/main/native/sim/HALInitializer.h @@ -16,7 +16,6 @@ inline void CheckInit() { RunInitialize(); } -extern void InitializeAccelerometerData(); extern void InitializeAddressableLEDData(); extern void InitializeAnalogInData(); extern void InitializeAnalogTriggerData(); @@ -35,7 +34,6 @@ extern void InitializePowerDistributionData(); extern void InitializePWMData(); extern void InitializeRoboRioData(); extern void InitializeSimDeviceData(); -extern void InitializeAccelerometer(); extern void InitializeAddressableLED(); extern void InitializeAnalogInput(); extern void InitializeAnalogInternal(); diff --git a/hal/src/main/native/sim/mockdata/AccelerometerData.cpp b/hal/src/main/native/sim/mockdata/AccelerometerData.cpp deleted file mode 100644 index 92848309a37..00000000000 --- a/hal/src/main/native/sim/mockdata/AccelerometerData.cpp +++ /dev/null @@ -1,55 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "../PortsInternal.h" -#include "AccelerometerDataInternal.h" - -using namespace hal; - -namespace hal::init { -void InitializeAccelerometerData() { - static AccelerometerData sad[kAccelerometers]; - ::hal::SimAccelerometerData = sad; -} -} // namespace hal::init - -AccelerometerData* hal::SimAccelerometerData; -void AccelerometerData::ResetData() { - active.Reset(false); - range.Reset(static_cast(0)); - x.Reset(0.0); - y.Reset(0.0); - z.Reset(0.0); -} - -extern "C" { -void HALSIM_ResetAccelerometerData(int32_t index) { - SimAccelerometerData[index].ResetData(); -} - -#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME) \ - HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, Accelerometer##CAPINAME, \ - SimAccelerometerData, LOWERNAME) - -DEFINE_CAPI(HAL_Bool, Active, active) -DEFINE_CAPI(HAL_AccelerometerRange, Range, range) -DEFINE_CAPI(double, X, x) -DEFINE_CAPI(double, Y, y) -DEFINE_CAPI(double, Z, z) - -#define REGISTER(NAME) \ - SimAccelerometerData[index].NAME.RegisterCallback(callback, param, \ - initialNotify) - -void HALSIM_RegisterAccelerometerAllCallbacks(int32_t index, - HAL_NotifyCallback callback, - void* param, - HAL_Bool initialNotify) { - REGISTER(active); - REGISTER(range); - REGISTER(x); - REGISTER(y); - REGISTER(z); -} -} // extern "C" diff --git a/hal/src/main/native/sim/mockdata/AccelerometerDataInternal.h b/hal/src/main/native/sim/mockdata/AccelerometerDataInternal.h deleted file mode 100644 index 24be83e029e..00000000000 --- a/hal/src/main/native/sim/mockdata/AccelerometerDataInternal.h +++ /dev/null @@ -1,33 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include "hal/simulation/AccelerometerData.h" -#include "hal/simulation/SimDataValue.h" - -namespace hal { -class AccelerometerData { - HAL_SIMDATAVALUE_DEFINE_NAME(Active) - HAL_SIMDATAVALUE_DEFINE_NAME(Range) - HAL_SIMDATAVALUE_DEFINE_NAME(X) - HAL_SIMDATAVALUE_DEFINE_NAME(Y) - HAL_SIMDATAVALUE_DEFINE_NAME(Z) - - static inline HAL_Value MakeRangeValue(HAL_AccelerometerRange value) { - return HAL_MakeEnum(value); - } - - public: - SimDataValue active{false}; - SimDataValue range{ - static_cast(0)}; - SimDataValue x{0.0}; - SimDataValue y{0.0}; - SimDataValue z{0.0}; - - virtual void ResetData(); -}; -extern AccelerometerData* SimAccelerometerData; -} // namespace hal diff --git a/hal/src/main/native/sim/mockdata/Reset.cpp b/hal/src/main/native/sim/mockdata/Reset.cpp index 776aeafdf08..0bd9fb12e41 100644 --- a/hal/src/main/native/sim/mockdata/Reset.cpp +++ b/hal/src/main/native/sim/mockdata/Reset.cpp @@ -2,7 +2,6 @@ // 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 #include #include #include @@ -23,10 +22,6 @@ #include "../PortsInternal.h" extern "C" void HALSIM_ResetAllSimData(void) { - for (int32_t i = 0; i < hal::kAccelerometers; i++) { - HALSIM_ResetAccelerometerData(i); - } - for (int32_t i = 0; i < hal::kNumAddressableLEDs; i++) { HALSIM_ResetAddressableLEDData(i); } diff --git a/hal/src/main/native/systemcore/Accelerometer.cpp b/hal/src/main/native/systemcore/Accelerometer.cpp deleted file mode 100644 index b94de603bba..00000000000 --- a/hal/src/main/native/systemcore/Accelerometer.cpp +++ /dev/null @@ -1,58 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "hal/Accelerometer.h" - -#include - -#include -#include -#include - -#include "HALInitializer.h" -#include "hal/HAL.h" - -using namespace hal; - -namespace hal::init { -void InitializeAccelerometer() {} -} // namespace hal::init - -namespace hal { - -/** - * Initialize the accelerometer. - */ -static void initializeAccelerometer() { - hal::init::CheckInit(); -} - -} // namespace hal - -extern "C" { - -void HAL_SetAccelerometerActive(HAL_Bool active) { - initializeAccelerometer(); -} - -void HAL_SetAccelerometerRange(HAL_AccelerometerRange range) { - initializeAccelerometer(); -} - -double HAL_GetAccelerometerX(void) { - initializeAccelerometer(); - return 0.0; -} - -double HAL_GetAccelerometerY(void) { - initializeAccelerometer(); - return 0.0; -} - -double HAL_GetAccelerometerZ(void) { - initializeAccelerometer(); - return 0.0; -} - -} // extern "C" diff --git a/hal/src/main/native/systemcore/HAL.cpp b/hal/src/main/native/systemcore/HAL.cpp index 2f7ccd5af53..0e347c3bef0 100644 --- a/hal/src/main/native/systemcore/HAL.cpp +++ b/hal/src/main/native/systemcore/HAL.cpp @@ -49,7 +49,6 @@ void InitializeHAL() { InitializeCTREPCM(); InitializeREVPH(); InitializeAddressableLED(); - InitializeAccelerometer(); InitializeAnalogInput(); InitializeAnalogTrigger(); InitializeCAN(); diff --git a/hal/src/main/native/systemcore/HALInitializer.h b/hal/src/main/native/systemcore/HALInitializer.h index 5fb929bc4c0..e4c2d3e83d9 100644 --- a/hal/src/main/native/systemcore/HALInitializer.h +++ b/hal/src/main/native/systemcore/HALInitializer.h @@ -18,7 +18,6 @@ inline void CheckInit() { extern void InitializeCTREPCM(); extern void InitializeREVPH(); -extern void InitializeAccelerometer(); extern void InitializeAddressableLED(); extern void InitializeAnalogInput(); extern void InitializeAnalogInternal(); diff --git a/hal/src/main/native/systemcore/mockdata/AccelerometerData.cpp b/hal/src/main/native/systemcore/mockdata/AccelerometerData.cpp deleted file mode 100644 index e097a24b61a..00000000000 --- a/hal/src/main/native/systemcore/mockdata/AccelerometerData.cpp +++ /dev/null @@ -1,25 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "hal/simulation/AccelerometerData.h" - -#include "hal/simulation/SimDataValue.h" - -extern "C" { -void HALSIM_ResetAccelerometerData(int32_t index) {} - -#define DEFINE_CAPI(TYPE, CAPINAME, RETURN) \ - HAL_SIMDATAVALUE_STUB_CAPI(TYPE, HALSIM, Accelerometer##CAPINAME, RETURN) - -DEFINE_CAPI(HAL_Bool, Active, false) -DEFINE_CAPI(HAL_AccelerometerRange, Range, HAL_AccelerometerRange_k2G) -DEFINE_CAPI(double, X, 0) -DEFINE_CAPI(double, Y, 0) -DEFINE_CAPI(double, Z, 0) - -void HALSIM_RegisterAccelerometerAllCallbacks(int32_t index, - HAL_NotifyCallback callback, - void* param, - HAL_Bool initialNotify) {} -} // extern "C" diff --git a/simulation/halsim_gui/src/main/native/cpp/AccelerometerSimGui.cpp b/simulation/halsim_gui/src/main/native/cpp/AccelerometerSimGui.cpp deleted file mode 100644 index b7f4e40cb52..00000000000 --- a/simulation/halsim_gui/src/main/native/cpp/AccelerometerSimGui.cpp +++ /dev/null @@ -1,63 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "AccelerometerSimGui.h" - -#include - -#include -#include -#include -#include - -#include "HALDataSource.h" -#include "HALSimGui.h" -#include "SimDeviceGui.h" - -using namespace glass; -using namespace halsimgui; - -namespace { -HALSIMGUI_DATASOURCE_DOUBLE_INDEXED(AccelerometerX, "X Accel"); -HALSIMGUI_DATASOURCE_DOUBLE_INDEXED(AccelerometerY, "Y Accel"); -HALSIMGUI_DATASOURCE_DOUBLE_INDEXED(AccelerometerZ, "Z Accel"); - -class AccelerometerSimModel : public glass::AccelerometerModel { - public: - explicit AccelerometerSimModel(int32_t index) - : m_index{index}, m_xData{m_index}, m_yData{m_index}, m_zData{m_index} {} - - void Update() override {} - - bool Exists() override { return HALSIM_GetAccelerometerActive(m_index); } - - glass::DoubleSource* GetXData() override { return &m_xData; } - glass::DoubleSource* GetYData() override { return &m_yData; } - glass::DoubleSource* GetZData() override { return &m_zData; } - - int GetRange() override { return HALSIM_GetAccelerometerRange(m_index); } - - void SetX(double val) override { HALSIM_SetAccelerometerX(m_index, val); } - void SetY(double val) override { HALSIM_SetAccelerometerY(m_index, val); } - void SetZ(double val) override { HALSIM_SetAccelerometerZ(m_index, val); } - void SetRange(int val) override { - HALSIM_SetAccelerometerRange(m_index, - static_cast(val)); - } - - private: - int32_t m_index; - AccelerometerXSource m_xData; - AccelerometerYSource m_yData; - AccelerometerZSource m_zData; -}; -} // namespace - -void AccelerometerSimGui::Initialize() { - SimDeviceGui::GetDeviceTree().Add( - std::make_unique(0), [](glass::Model* model) { - glass::DisplayAccelerometerDevice( - static_cast(model)); - }); -} diff --git a/simulation/halsim_gui/src/main/native/cpp/AccelerometerSimGui.h b/simulation/halsim_gui/src/main/native/cpp/AccelerometerSimGui.h deleted file mode 100644 index 9028324c453..00000000000 --- a/simulation/halsim_gui/src/main/native/cpp/AccelerometerSimGui.h +++ /dev/null @@ -1,14 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -namespace halsimgui { - -class AccelerometerSimGui { - public: - static void Initialize(); -}; - -} // namespace halsimgui diff --git a/simulation/halsim_gui/src/main/native/cpp/main.cpp b/simulation/halsim_gui/src/main/native/cpp/main.cpp index 2a5f57a9c24..2a0c92d9f30 100644 --- a/simulation/halsim_gui/src/main/native/cpp/main.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/main.cpp @@ -15,7 +15,6 @@ #include #include -#include "AccelerometerSimGui.h" #include "AddressableLEDGui.h" #include "AnalogInputSimGui.h" #include "DIOSimGui.h" @@ -73,7 +72,6 @@ __declspec(dllexport) EncoderSimGui::Initialize(); SimDeviceGui::Initialize(); - AccelerometerSimGui::Initialize(); AddressableLEDGui::Initialize(); AnalogInputSimGui::Initialize(); DIOSimGui::Initialize(); diff --git a/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClient.cpp b/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClient.cpp index 00f51b83270..68dd286f95c 100644 --- a/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClient.cpp +++ b/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClient.cpp @@ -9,7 +9,6 @@ #include #include #include -#include #include #include #include @@ -40,7 +39,6 @@ bool HALSimWSClient::Initialize() { HALSimWSProviderAddressableLED::Initialize(registerFunc); HALSimWSProviderAnalogIn::Initialize(registerFunc); - HALSimWSProviderBuiltInAccelerometer::Initialize(registerFunc); HALSimWSProviderDIO::Initialize(registerFunc); HALSimWSProviderDigitalPWM::Initialize(registerFunc); HALSimWSProviderDriverStation::Initialize(registerFunc); diff --git a/simulation/halsim_ws_core/doc/hardware_ws_api.md b/simulation/halsim_ws_core/doc/hardware_ws_api.md index 2fca74a0c17..2822f6534ef 100644 --- a/simulation/halsim_ws_core/doc/hardware_ws_api.md +++ b/simulation/halsim_ws_core/doc/hardware_ws_api.md @@ -76,7 +76,6 @@ The “hardware“ (which might be a full-fledged 3D simulation engine, a physic | Type value | Description | Device value | | ----------------------- | -------------------------- | ------------------------- | -| [``"Accel"``][] | Accelerometer | Arbitrary device name | | [``"AddressableLED"``][]| Addressable LED Strip | Arbitrary device number | | [``"AI"``][] | Analog input | Port index, e.g. "1", "2" | | [``"AO"``][] | Analog output | Port index, e.g. "1", "2" | @@ -92,22 +91,6 @@ The “hardware“ (which might be a full-fledged 3D simulation engine, a physic | [``"PWM"``][] | PWM output | Port index, e.g. "1", "2" | | [``"Solenoid"``][] | Solenoid output | Module +Port index, e.g. "0,1", "2,5" | -#### Accelerometer ("Accel") - -[``"Accel"``]:#accelerometer-accel - -A 3-axis accelerometer. - -C++/Java implementation note: these are created as either BuiltInAccelerometer or SimDevice nodes where the device name is prefixed by ``"Accel:"``. For example, the device ``"Accel:ADXL362[1]"`` would have a device value of ``ADXL362[1]``. The BuiltInAccelerometer uses a device name of ``"BuiltInAccel"``. - -| Data Key | Type | Description | -| ------------ | ------- | ---------------------------------------------------- | -| ``"x"`` | Float | Acceleration in G’s | -| ``">y"`` | Float | Acceleration in G’s | -| ``">z"`` | Float | Acceleration in G’s | - #### Addressable LED Strip ("AddressableLED") [``"AddressableLED"``]:#addressable-led-strip-addressableled diff --git a/simulation/halsim_ws_core/doc/wpilib-ws.yaml b/simulation/halsim_ws_core/doc/wpilib-ws.yaml index c8a3bb383ff..c98ea1220a5 100644 --- a/simulation/halsim_ws_core/doc/wpilib-ws.yaml +++ b/simulation/halsim_ws_core/doc/wpilib-ws.yaml @@ -65,39 +65,6 @@ components: - $ref: "#/components/schemas/simdeviceData" schemas: - accelData: - type: object - required: - - type - - device - properties: - type: - type: string - description: Device Type (e.g. DIO/AI/PWM/Encoder etc) - const: Accel - device: - type: string - description: Arbitrary device name - data: - type: object - description: "Accelerometer Data (type: Accelerometer, device: channel number)" - properties: - x": - type: number - description: "Acceleration in G’s " - ">y": - type: number - description: "Acceleration in G’s " - ">z": - type: number - description: "Acceleration in G’s " - addressableLEDData: type: object required: diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_BuiltInAccelerometer.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_BuiltInAccelerometer.cpp deleted file mode 100644 index 1928b5df3ac..00000000000 --- a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_BuiltInAccelerometer.cpp +++ /dev/null @@ -1,96 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "WSProvider_BuiltInAccelerometer.h" - -#include - -#include -#include - -#define REGISTER(halsim, jsonid, ctype, haltype) \ - HALSIM_RegisterAccelerometer##halsim##Callback( \ - 0, \ - [](const char* name, void* param, const struct HAL_Value* value) { \ - static_cast(param) \ - ->ProcessHalCallback( \ - {{jsonid, static_cast(value->data.v_##haltype)}}); \ - }, \ - this, true) -namespace wpilibws { -HALSimWSProviderBuiltInAccelerometer::HALSimWSProviderBuiltInAccelerometer() - : HALSimWSHalProvider("Accel/BuiltInAccel", "Accel") { - m_deviceId = "BuiltInAccel"; -} - -void HALSimWSProviderBuiltInAccelerometer::Initialize( - WSRegisterFunc webRegisterFunc) { - webRegisterFunc("Accel/BuiltInAccel", - std::make_unique()); -} - -HALSimWSProviderBuiltInAccelerometer::~HALSimWSProviderBuiltInAccelerometer() { - DoCancelCallbacks(); -} - -void HALSimWSProviderBuiltInAccelerometer::RegisterCallbacks() { - m_activeCbKey = REGISTER(Active, "data.v_int) { - case 0: - range = 2; - break; - case 1: - range = 4; - break; - case 2: - default: - range = 8; - break; - } - static_cast(param) - ->ProcessHalCallback({{"x", double, double); - m_yCbKey = REGISTER(Y, ">y", double, double); - m_zCbKey = REGISTER(Z, ">z", double, double); -} - -void HALSimWSProviderBuiltInAccelerometer::CancelCallbacks() { - DoCancelCallbacks(); -} - -void HALSimWSProviderBuiltInAccelerometer::DoCancelCallbacks() { - HALSIM_CancelAccelerometerActiveCallback(0, m_activeCbKey); - HALSIM_CancelAccelerometerRangeCallback(0, m_rangeCbKey); - HALSIM_CancelAccelerometerXCallback(0, m_xCbKey); - HALSIM_CancelAccelerometerYCallback(0, m_yCbKey); - HALSIM_CancelAccelerometerZCallback(0, m_zCbKey); - - m_activeCbKey = 0; - m_rangeCbKey = 0; - m_xCbKey = 0; - m_yCbKey = 0; - m_zCbKey = 0; -} - -void HALSimWSProviderBuiltInAccelerometer::OnNetValueChanged( - const wpi::json& json) { - wpi::json::const_iterator it; - if ((it = json.find(">x")) != json.end()) { - HALSIM_SetAccelerometerX(0, it.value()); - } - if ((it = json.find(">y")) != json.end()) { - HALSIM_SetAccelerometerY(0, it.value()); - } - if ((it = json.find(">z")) != json.end()) { - HALSIM_SetAccelerometerZ(0, it.value()); - } -} - -} // namespace wpilibws diff --git a/simulation/halsim_ws_core/src/main/native/include/WSProvider_BuiltInAccelerometer.h b/simulation/halsim_ws_core/src/main/native/include/WSProvider_BuiltInAccelerometer.h deleted file mode 100644 index 62568e7e9d5..00000000000 --- a/simulation/halsim_ws_core/src/main/native/include/WSProvider_BuiltInAccelerometer.h +++ /dev/null @@ -1,32 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include "WSHalProviders.h" - -namespace wpilibws { -class HALSimWSProviderBuiltInAccelerometer : public HALSimWSHalProvider { - public: - HALSimWSProviderBuiltInAccelerometer(); - static void Initialize(WSRegisterFunc webRegisterFunc); - - using HALSimWSHalProvider::HALSimWSHalProvider; - ~HALSimWSProviderBuiltInAccelerometer() override; - - void OnNetValueChanged(const wpi::json& json) override; - - protected: - void RegisterCallbacks() override; - void CancelCallbacks() override; - void DoCancelCallbacks(); - - private: - int32_t m_activeCbKey = 0; - int32_t m_rangeCbKey = 0; - int32_t m_xCbKey = 0; - int32_t m_yCbKey = 0; - int32_t m_zCbKey = 0; -}; -} // namespace wpilibws diff --git a/simulation/halsim_ws_server/src/main/native/cpp/HALSimWSServer.cpp b/simulation/halsim_ws_server/src/main/native/cpp/HALSimWSServer.cpp index 32a1e8aae8e..a78c64bb703 100644 --- a/simulation/halsim_ws_server/src/main/native/cpp/HALSimWSServer.cpp +++ b/simulation/halsim_ws_server/src/main/native/cpp/HALSimWSServer.cpp @@ -9,7 +9,6 @@ #include #include #include -#include #include #include #include @@ -39,7 +38,6 @@ bool HALSimWSServer::Initialize() { HALSimWSProviderAddressableLED::Initialize(registerFunc); HALSimWSProviderAnalogIn::Initialize(registerFunc); - HALSimWSProviderBuiltInAccelerometer::Initialize(registerFunc); HALSimWSProviderDIO::Initialize(registerFunc); HALSimWSProviderDigitalPWM::Initialize(registerFunc); HALSimWSProviderDriverStation::Initialize(registerFunc); diff --git a/simulation/halsim_xrp/README.md b/simulation/halsim_xrp/README.md index 6358dd32c64..def8e1fb244 100644 --- a/simulation/halsim_xrp/README.md +++ b/simulation/halsim_xrp/README.md @@ -44,7 +44,6 @@ Utilizing tagged data blocks allows us to send multiple pieces of data in a sing | 0x14 | [DIO](#dio) | | 0x15 | [AnalogIn](#analogin) | | 0x16 | [XRPGyro](#xrpgyro) | -| 0x17 | [BuiltInAccel](#builtinaccel) | | 0x18 | [Encoder](#encoder) | @@ -101,14 +100,6 @@ IDs: | 4 | _float_ | angle_y (deg) | | 5 | _float_ | angle_z (deg) | -#### BuiltInAccel - -| Order | Data Type | Description | -|-------|-----------|-------------| -| 0 | _float_ | accel_x (g) | -| 1 | _float_ | accel_y (g) | -| 2 | _float_ | accel_z (g) | - #### Encoder | Order | Data Type | Description | diff --git a/simulation/halsim_xrp/src/main/native/cpp/HALSimXRPClient.cpp b/simulation/halsim_xrp/src/main/native/cpp/HALSimXRPClient.cpp index adc4e26a46c..50f3772a1be 100644 --- a/simulation/halsim_xrp/src/main/native/cpp/HALSimXRPClient.cpp +++ b/simulation/halsim_xrp/src/main/native/cpp/HALSimXRPClient.cpp @@ -8,7 +8,6 @@ #include #include -#include #include #include #include @@ -35,7 +34,6 @@ bool HALSimXRPClient::Initialize() { // Minimized set of HAL providers HALSimWSProviderAnalogIn::Initialize(registerFunc); - HALSimWSProviderBuiltInAccelerometer::Initialize(registerFunc); HALSimWSProviderDIO::Initialize(registerFunc); HALSimWSProviderDriverStation::Initialize(registerFunc); HALSimWSProviderEncoder::Initialize(registerFunc); diff --git a/simulation/halsim_xrp/src/main/native/cpp/XRP.cpp b/simulation/halsim_xrp/src/main/native/cpp/XRP.cpp index 812ebacb9bd..952a630d0d7 100644 --- a/simulation/halsim_xrp/src/main/native/cpp/XRP.cpp +++ b/simulation/halsim_xrp/src/main/native/cpp/XRP.cpp @@ -81,9 +81,6 @@ void XRP::HandleXRPUpdate(std::span packet) { case XRP_TAG_GYRO: ReadGyroTag(tagPacket); break; - case XRP_TAG_ACCEL: - ReadAccelTag(tagPacket); - break; case XRP_TAG_DIO: ReadDIOTag(tagPacket); break; @@ -307,28 +304,6 @@ void XRP::ReadGyroTag(std::span packet) { m_wpilib_update_func(gyroJson); } -void XRP::ReadAccelTag(std::span packet) { - if (packet.size() < 14) { - return; // size(1) + tag(1) + 3x 4 byte - } - - packet = packet.subspan(2); // Skip past the size and tag - float accel_x = - std::bit_cast(wpi::support::endian::read32be(&packet[0])); - float accel_y = - std::bit_cast(wpi::support::endian::read32be(&packet[4])); - float accel_z = - std::bit_cast(wpi::support::endian::read32be(&packet[8])); - - wpi::json accelJson; - accelJson["type"] = "Accel"; - accelJson["device"] = "BuiltInAccel"; - accelJson["data"] = {{">x", accel_x}, {">y", accel_y}, {">z", accel_z}}; - - // Update WPILib - m_wpilib_update_func(accelJson); -} - void XRP::ReadDIOTag(std::span packet) { if (packet.size() < 4) { return; // size(1) + tag(1) + id(1) + value(1) diff --git a/simulation/halsim_xrp/src/main/native/include/XRP.h b/simulation/halsim_xrp/src/main/native/include/XRP.h index 2eaf2b0aa67..eb776898105 100644 --- a/simulation/halsim_xrp/src/main/native/include/XRP.h +++ b/simulation/halsim_xrp/src/main/native/include/XRP.h @@ -54,7 +54,6 @@ class XRP { // XRP Packet Update Handlers void ReadGyroTag(std::span packet); - void ReadAccelTag(std::span packet); void ReadDIOTag(std::span packet); void ReadEncoderTag(std::span packet); void ReadAnalogTag(std::span packet); diff --git a/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp b/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp deleted file mode 100644 index 2189863241f..00000000000 --- a/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp +++ /dev/null @@ -1,47 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "frc/BuiltInAccelerometer.h" - -#include -#include -#include -#include - -#include "frc/Errors.h" - -using namespace frc; - -BuiltInAccelerometer::BuiltInAccelerometer(Range range) { - SetRange(range); - - HAL_Report(HALUsageReporting::kResourceType_Accelerometer, 0, 0, - "Built-in accelerometer"); - wpi::SendableRegistry::AddLW(this, "BuiltInAccel"); -} - -void BuiltInAccelerometer::SetRange(Range range) { - HAL_SetAccelerometerActive(false); - HAL_SetAccelerometerRange(static_cast(range)); - HAL_SetAccelerometerActive(true); -} - -double BuiltInAccelerometer::GetX() { - return HAL_GetAccelerometerX(); -} - -double BuiltInAccelerometer::GetY() { - return HAL_GetAccelerometerY(); -} - -double BuiltInAccelerometer::GetZ() { - return HAL_GetAccelerometerZ(); -} - -void BuiltInAccelerometer::InitSendable(wpi::SendableBuilder& builder) { - builder.SetSmartDashboardType("3AxisAccelerometer"); - builder.AddDoubleProperty("X", [=, this] { return GetX(); }, nullptr); - builder.AddDoubleProperty("Y", [=, this] { return GetY(); }, nullptr); - builder.AddDoubleProperty("Z", [=, this] { return GetZ(); }, nullptr); -} diff --git a/wpilibc/src/main/native/cpp/simulation/BuiltInAccelerometerSim.cpp b/wpilibc/src/main/native/cpp/simulation/BuiltInAccelerometerSim.cpp deleted file mode 100644 index 58f3efb901f..00000000000 --- a/wpilibc/src/main/native/cpp/simulation/BuiltInAccelerometerSim.cpp +++ /dev/null @@ -1,108 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "frc/simulation/BuiltInAccelerometerSim.h" - -#include - -#include - -#include "frc/BuiltInAccelerometer.h" - -using namespace frc; -using namespace frc::sim; - -BuiltInAccelerometerSim::BuiltInAccelerometerSim() : m_index{0} {} - -BuiltInAccelerometerSim::BuiltInAccelerometerSim(const BuiltInAccelerometer&) - : m_index{0} {} - -std::unique_ptr BuiltInAccelerometerSim::RegisterActiveCallback( - NotifyCallback callback, bool initialNotify) { - auto store = std::make_unique( - m_index, -1, callback, &HALSIM_CancelAccelerometerActiveCallback); - store->SetUid(HALSIM_RegisterAccelerometerActiveCallback( - m_index, &CallbackStoreThunk, store.get(), initialNotify)); - return store; -} - -bool BuiltInAccelerometerSim::GetActive() const { - return HALSIM_GetAccelerometerActive(m_index); -} - -void BuiltInAccelerometerSim::SetActive(bool active) { - HALSIM_SetAccelerometerActive(m_index, active); -} - -std::unique_ptr BuiltInAccelerometerSim::RegisterRangeCallback( - NotifyCallback callback, bool initialNotify) { - auto store = std::make_unique( - m_index, -1, callback, &HALSIM_CancelAccelerometerRangeCallback); - store->SetUid(HALSIM_RegisterAccelerometerRangeCallback( - m_index, &CallbackStoreThunk, store.get(), initialNotify)); - return store; -} - -HAL_AccelerometerRange BuiltInAccelerometerSim::GetRange() const { - return HALSIM_GetAccelerometerRange(m_index); -} - -void BuiltInAccelerometerSim::SetRange(HAL_AccelerometerRange range) { - HALSIM_SetAccelerometerRange(m_index, range); -} - -std::unique_ptr BuiltInAccelerometerSim::RegisterXCallback( - NotifyCallback callback, bool initialNotify) { - auto store = std::make_unique( - m_index, -1, callback, &HALSIM_CancelAccelerometerXCallback); - store->SetUid(HALSIM_RegisterAccelerometerXCallback( - m_index, &CallbackStoreThunk, store.get(), initialNotify)); - return store; -} - -double BuiltInAccelerometerSim::GetX() const { - return HALSIM_GetAccelerometerX(m_index); -} - -void BuiltInAccelerometerSim::SetX(double x) { - HALSIM_SetAccelerometerX(m_index, x); -} - -std::unique_ptr BuiltInAccelerometerSim::RegisterYCallback( - NotifyCallback callback, bool initialNotify) { - auto store = std::make_unique( - m_index, -1, callback, &HALSIM_CancelAccelerometerYCallback); - store->SetUid(HALSIM_RegisterAccelerometerYCallback( - m_index, &CallbackStoreThunk, store.get(), initialNotify)); - return store; -} - -double BuiltInAccelerometerSim::GetY() const { - return HALSIM_GetAccelerometerY(m_index); -} - -void BuiltInAccelerometerSim::SetY(double y) { - HALSIM_SetAccelerometerY(m_index, y); -} - -std::unique_ptr BuiltInAccelerometerSim::RegisterZCallback( - NotifyCallback callback, bool initialNotify) { - auto store = std::make_unique( - m_index, -1, callback, &HALSIM_CancelAccelerometerZCallback); - store->SetUid(HALSIM_RegisterAccelerometerZCallback( - m_index, &CallbackStoreThunk, store.get(), initialNotify)); - return store; -} - -double BuiltInAccelerometerSim::GetZ() const { - return HALSIM_GetAccelerometerZ(m_index); -} - -void BuiltInAccelerometerSim::SetZ(double z) { - HALSIM_SetAccelerometerZ(m_index, z); -} - -void BuiltInAccelerometerSim::ResetData() { - HALSIM_ResetAccelerometerData(m_index); -} diff --git a/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h b/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h deleted file mode 100644 index 270ed80d55c..00000000000 --- a/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h +++ /dev/null @@ -1,68 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include -#include - -namespace frc { - -/** - * Built-in accelerometer. - * - * This class allows access to the roboRIO's internal accelerometer. - */ -class BuiltInAccelerometer : public wpi::Sendable, - public wpi::SendableHelper { - public: - /** - * Accelerometer range. - */ - enum Range { - /// 2 Gs max. - kRange_2G = 0, - /// 4 Gs max. - kRange_4G = 1, - /// 8 Gs max. - kRange_8G = 2 - }; - - /** - * Constructor. - * - * @param range The range the accelerometer will measure - */ - explicit BuiltInAccelerometer(Range range = kRange_8G); - - BuiltInAccelerometer(BuiltInAccelerometer&&) = default; - BuiltInAccelerometer& operator=(BuiltInAccelerometer&&) = default; - - /** - * Set the measuring range of the accelerometer. - * - * @param range The maximum acceleration, positive or negative, that the - * accelerometer will measure. - */ - void SetRange(Range range); - - /** - * @return The acceleration of the roboRIO along the X axis in g-forces - */ - double GetX(); - - /** - * @return The acceleration of the roboRIO along the Y axis in g-forces - */ - double GetY(); - - /** - * @return The acceleration of the roboRIO along the Z axis in g-forces - */ - double GetZ(); - - void InitSendable(wpi::SendableBuilder& builder) override; -}; - -} // namespace frc diff --git a/wpilibc/src/main/native/include/frc/simulation/BuiltInAccelerometerSim.h b/wpilibc/src/main/native/include/frc/simulation/BuiltInAccelerometerSim.h deleted file mode 100644 index 74a4f161b61..00000000000 --- a/wpilibc/src/main/native/include/frc/simulation/BuiltInAccelerometerSim.h +++ /dev/null @@ -1,170 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include - -#include - -#include "frc/simulation/CallbackStore.h" - -namespace frc { - -class BuiltInAccelerometer; - -namespace sim { - -/** - * Class to control a simulated built-in accelerometer. - */ -class BuiltInAccelerometerSim { - public: - /** - * Constructs for the first built-in accelerometer. - */ - BuiltInAccelerometerSim(); - - /** - * Constructs from a BuiltInAccelerometer object. - * - * @param accel BuiltInAccelerometer to simulate - */ - explicit BuiltInAccelerometerSim(const BuiltInAccelerometer& accel); - - /** - * Register a callback to be run when this accelerometer activates. - * - * @param callback the callback - * @param initialNotify whether to run the callback with the initial state - * @return the CallbackStore object associated with this callback - */ - [[nodiscard]] - std::unique_ptr RegisterActiveCallback(NotifyCallback callback, - bool initialNotify); - - /** - * Check whether the accelerometer is active. - * - * @return true if active - */ - bool GetActive() const; - - /** - * Define whether this accelerometer is active. - * - * @param active the new state - */ - void SetActive(bool active); - - /** - * Register a callback to be run whenever the range changes. - * - * @param callback the callback - * @param initialNotify whether to call the callback with the initial state - * @return the CallbackStore object associated with this callback - */ - [[nodiscard]] - std::unique_ptr RegisterRangeCallback(NotifyCallback callback, - bool initialNotify); - - /** - * Check the range of this accelerometer. - * - * @return the accelerometer range - */ - HAL_AccelerometerRange GetRange() const; - - /** - * Change the range of this accelerometer. - * - * @param range the new accelerometer range - */ - void SetRange(HAL_AccelerometerRange range); - - /** - * Register a callback to be run whenever the X axis value changes. - * - * @param callback the callback - * @param initialNotify whether to call the callback with the initial state - * @return the CallbackStore object associated with this callback - */ - [[nodiscard]] - std::unique_ptr RegisterXCallback(NotifyCallback callback, - bool initialNotify); - - /** - * Measure the X axis value. - * - * @return the X axis measurement - */ - double GetX() const; - - /** - * Change the X axis value of the accelerometer. - * - * @param x the new reading of the X axis - */ - void SetX(double x); - - /** - * Register a callback to be run whenever the Y axis value changes. - * - * @param callback the callback - * @param initialNotify whether to call the callback with the initial state - * @return the CallbackStore object associated with this callback - */ - [[nodiscard]] - std::unique_ptr RegisterYCallback(NotifyCallback callback, - bool initialNotify); - - /** - * Measure the Y axis value. - * - * @return the Y axis measurement - */ - double GetY() const; - - /** - * Change the Y axis value of the accelerometer. - * - * @param y the new reading of the Y axis - */ - void SetY(double y); - - /** - * Register a callback to be run whenever the Z axis value changes. - * - * @param callback the callback - * @param initialNotify whether to call the callback with the initial state - * @return the CallbackStore object associated with this callback - */ - [[nodiscard]] - std::unique_ptr RegisterZCallback(NotifyCallback callback, - bool initialNotify); - - /** - * Measure the Z axis value. - * - * @return the Z axis measurement - */ - double GetZ() const; - - /** - * Change the Z axis value of the accelerometer. - * - * @param z the new reading of the Z axis - */ - void SetZ(double z); - - /** - * Reset all simulation data of this object. - */ - void ResetData(); - - private: - int m_index; -}; -} // namespace sim -} // namespace frc diff --git a/wpilibc/src/test/native/cpp/simulation/AccelerometerSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/AccelerometerSimTest.cpp deleted file mode 100644 index 6a29b800dfb..00000000000 --- a/wpilibc/src/test/native/cpp/simulation/AccelerometerSimTest.cpp +++ /dev/null @@ -1,133 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "frc/simulation/BuiltInAccelerometerSim.h" // NOLINT(build/include_order) - -#include -#include -#include - -#include "callback_helpers/TestCallbackHelpers.h" -#include "frc/BuiltInAccelerometer.h" - -namespace frc::sim { - -TEST(AccelerometerSimTest, ActiveCallback) { - HAL_Initialize(500, 0); - - BuiltInAccelerometerSim sim; - - sim.ResetData(); - - bool wasTriggered = false; - bool lastValue = false; - - auto cb = sim.RegisterActiveCallback( - [&](std::string_view name, const HAL_Value* value) { - wasTriggered = true; - lastValue = value->data.v_boolean; - }, - false); - - EXPECT_FALSE(wasTriggered); - - HAL_SetAccelerometerActive(true); - - EXPECT_TRUE(wasTriggered); - EXPECT_TRUE(lastValue); - EXPECT_TRUE(sim.GetActive()); -} - -TEST(AccelerometerSimTest, SetX) { - HAL_Initialize(500, 0); - BuiltInAccelerometerSim sim; - sim.ResetData(); - - DoubleCallback callback; - constexpr double kTestValue = 1.91; - - BuiltInAccelerometer accel; - auto cb = sim.RegisterXCallback(callback.GetCallback(), false); - sim.SetX(kTestValue); - EXPECT_EQ(kTestValue, accel.GetX()); - EXPECT_EQ(kTestValue, sim.GetX()); - EXPECT_TRUE(callback.WasTriggered()); - EXPECT_EQ(kTestValue, callback.GetLastValue()); -} - -TEST(AccelerometerSimTest, SetY) { - HAL_Initialize(500, 0); - BuiltInAccelerometerSim sim; - sim.ResetData(); - - DoubleCallback callback; - constexpr double kTestValue = 2.29; - - BuiltInAccelerometer accel; - auto cb = sim.RegisterYCallback(callback.GetCallback(), false); - sim.SetY(kTestValue); - EXPECT_EQ(kTestValue, accel.GetY()); - EXPECT_EQ(kTestValue, sim.GetY()); - EXPECT_TRUE(callback.WasTriggered()); - EXPECT_EQ(kTestValue, callback.GetLastValue()); -} - -TEST(AccelerometerSimTest, SetZ) { - HAL_Initialize(500, 0); - - BuiltInAccelerometer accel; - BuiltInAccelerometerSim sim(accel); - sim.ResetData(); - - DoubleCallback callback; - constexpr double kTestValue = 3.405; - - auto cb = sim.RegisterZCallback(callback.GetCallback(), false); - sim.SetZ(kTestValue); - EXPECT_EQ(kTestValue, accel.GetZ()); - EXPECT_EQ(kTestValue, sim.GetZ()); - EXPECT_TRUE(callback.WasTriggered()); - EXPECT_EQ(kTestValue, callback.GetLastValue()); -} - -TEST(AccelerometerSimTest, SetRange) { - HAL_Initialize(500, 0); - - BuiltInAccelerometerSim sim; - sim.ResetData(); - - EnumCallback callback; - - BuiltInAccelerometer::Range range = BuiltInAccelerometer::kRange_4G; - auto cb = sim.RegisterRangeCallback(callback.GetCallback(), false); - BuiltInAccelerometer accel(range); - EXPECT_TRUE(callback.WasTriggered()); - EXPECT_EQ(static_cast(range), sim.GetRange()); - EXPECT_EQ(static_cast(range), callback.GetLastValue()); - - // 2G - callback.Reset(); - range = BuiltInAccelerometer::kRange_2G; - accel.SetRange(range); - EXPECT_TRUE(callback.WasTriggered()); - EXPECT_EQ(static_cast(range), sim.GetRange()); - EXPECT_EQ(static_cast(range), callback.GetLastValue()); - - // 4G - callback.Reset(); - range = BuiltInAccelerometer::kRange_4G; - accel.SetRange(range); - EXPECT_TRUE(callback.WasTriggered()); - EXPECT_EQ(static_cast(range), sim.GetRange()); - EXPECT_EQ(static_cast(range), callback.GetLastValue()); - - // 8G - callback.Reset(); - range = BuiltInAccelerometer::kRange_8G; - accel.SetRange(range); - EXPECT_TRUE(callback.WasTriggered()); - EXPECT_EQ(static_cast(range), sim.GetRange()); - EXPECT_EQ(static_cast(range), callback.GetLastValue()); -} -} // namespace frc::sim diff --git a/wpilibc/src/test/native/cpp/simulation/SimInitializationTest.cpp b/wpilibc/src/test/native/cpp/simulation/SimInitializationTest.cpp index 7c850b3017f..7096849e998 100644 --- a/wpilibc/src/test/native/cpp/simulation/SimInitializationTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/SimInitializationTest.cpp @@ -10,7 +10,6 @@ #include "frc/simulation/AddressableLEDSim.h" #include "frc/simulation/AnalogInputSim.h" #include "frc/simulation/AnalogTriggerSim.h" -#include "frc/simulation/BuiltInAccelerometerSim.h" #include "frc/simulation/CTREPCMSim.h" #include "frc/simulation/DIOSim.h" #include "frc/simulation/DigitalPWMSim.h" @@ -25,7 +24,6 @@ using namespace frc::sim; TEST(SimInitializationTest, AllInitialize) { HAL_Initialize(500, 0); - BuiltInAccelerometerSim biacsim; AnalogInputSim aisim{0}; EXPECT_THROW(AnalogTriggerSim::CreateForChannel(0), std::out_of_range); EXPECT_THROW(DigitalPWMSim::CreateForChannel(0), std::out_of_range); diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp index 7afc2d77df1..4f5d87ced2f 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp @@ -63,18 +63,6 @@ units::meter_t Drivetrain::GetAverageDistance() { return (GetLeftDistance() + GetRightDistance()) / 2.0; } -units::meters_per_second_squared_t Drivetrain::GetAccelX() { - return units::meters_per_second_squared_t{m_accelerometer.GetX()}; -} - -units::meters_per_second_squared_t Drivetrain::GetAccelY() { - return units::meters_per_second_squared_t{m_accelerometer.GetY()}; -} - -units::meters_per_second_squared_t Drivetrain::GetAccelZ() { - return units::meters_per_second_squared_t{m_accelerometer.GetZ()}; -} - units::radian_t Drivetrain::GetGyroAngleX() { return m_gyro.GetAngleX(); } diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h index 3b55c9e8347..acd6bbf9746 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h @@ -4,7 +4,6 @@ #pragma once -#include #include #include #include @@ -74,27 +73,6 @@ class Drivetrain : public frc2::SubsystemBase { */ units::meter_t GetAverageDistance(); - /** - * The acceleration in the X-axis. - * - * @return The acceleration of the Romi along the X-axis. - */ - units::meters_per_second_squared_t GetAccelX(); - - /** - * The acceleration in the Y-axis. - * - * @return The acceleration of the Romi along the Y-axis. - */ - units::meters_per_second_squared_t GetAccelY(); - - /** - * The acceleration in the Z-axis. - * - * @return The acceleration of the Romi along the Z-axis. - */ - units::meters_per_second_squared_t GetAccelZ(); - /** * Current angle of the Romi around the X-axis. * @@ -133,5 +111,4 @@ class Drivetrain : public frc2::SubsystemBase { [&](double output) { m_rightMotor.Set(output); }}; frc::RomiGyro m_gyro; - frc::BuiltInAccelerometer m_accelerometer; }; diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp index 1a46f59b883..548716c88f1 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp @@ -63,18 +63,6 @@ units::meter_t Drivetrain::GetAverageDistance() { return (GetLeftDistance() + GetRightDistance()) / 2.0; } -units::meters_per_second_squared_t Drivetrain::GetAccelX() { - return units::meters_per_second_squared_t{m_accelerometer.GetX()}; -} - -units::meters_per_second_squared_t Drivetrain::GetAccelY() { - return units::meters_per_second_squared_t{m_accelerometer.GetY()}; -} - -units::meters_per_second_squared_t Drivetrain::GetAccelZ() { - return units::meters_per_second_squared_t{m_accelerometer.GetZ()}; -} - units::radian_t Drivetrain::GetGyroAngleX() { return m_gyro.GetAngleX(); } diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.h index 5a5c550861f..1c05c55de79 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.h @@ -4,7 +4,6 @@ #pragma once -#include #include #include #include @@ -78,27 +77,6 @@ class Drivetrain : public frc2::SubsystemBase { */ units::meter_t GetAverageDistance(); - /** - * The acceleration in the X-axis. - * - * @return The acceleration of the XRP along the X-axis. - */ - units::meters_per_second_squared_t GetAccelX(); - - /** - * The acceleration in the Y-axis. - * - * @return The acceleration of the XRP along the Y-axis. - */ - units::meters_per_second_squared_t GetAccelY(); - - /** - * The acceleration in the Z-axis. - * - * @return The acceleration of the XRP along the Z-axis. - */ - units::meters_per_second_squared_t GetAccelZ(); - /** * Current angle of the XRP around the X-axis. * @@ -137,5 +115,4 @@ class Drivetrain : public frc2::SubsystemBase { [&](double output) { m_rightMotor.Set(output); }}; frc::XRPGyro m_gyro; - frc::BuiltInAccelerometer m_accelerometer; }; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java deleted file mode 100644 index a84e47eac80..00000000000 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java +++ /dev/null @@ -1,106 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package edu.wpi.first.wpilibj; - -import edu.wpi.first.hal.AccelerometerJNI; -import edu.wpi.first.hal.FRCNetComm.tResourceType; -import edu.wpi.first.hal.HAL; -import edu.wpi.first.util.sendable.Sendable; -import edu.wpi.first.util.sendable.SendableBuilder; -import edu.wpi.first.util.sendable.SendableRegistry; - -/** - * Built-in accelerometer. - * - *

This class allows access to the roboRIO's internal accelerometer. - */ -public class BuiltInAccelerometer implements Sendable, AutoCloseable { - /** Accelerometer range. */ - public enum Range { - /** 2 Gs max. */ - k2G, - /** 4 Gs max. */ - k4G, - /** 8 Gs max. */ - k8G - } - - /** - * Constructor. - * - * @param range The range the accelerometer will measure - */ - @SuppressWarnings("this-escape") - public BuiltInAccelerometer(Range range) { - setRange(range); - HAL.report(tResourceType.kResourceType_Accelerometer, 0, 0, "Built-in accelerometer"); - SendableRegistry.addLW(this, "BuiltInAccel", 0); - } - - /** Constructor. The accelerometer will measure +/-8 g-forces */ - public BuiltInAccelerometer() { - this(Range.k8G); - } - - @Override - public void close() { - SendableRegistry.remove(this); - } - - /** - * Set the measuring range of the accelerometer. - * - * @param range The maximum acceleration, positive or negative, that the accelerometer will - * measure. - */ - public final void setRange(Range range) { - AccelerometerJNI.setAccelerometerActive(false); - - int rangeValue = - switch (range) { - case k2G -> 0; - case k4G -> 1; - case k8G -> 2; - }; - - AccelerometerJNI.setAccelerometerRange(rangeValue); - AccelerometerJNI.setAccelerometerActive(true); - } - - /** - * The acceleration in the X axis. - * - * @return The acceleration of the roboRIO along the X axis in g-forces - */ - public double getX() { - return AccelerometerJNI.getAccelerometerX(); - } - - /** - * The acceleration in the Y axis. - * - * @return The acceleration of the roboRIO along the Y axis in g-forces - */ - public double getY() { - return AccelerometerJNI.getAccelerometerY(); - } - - /** - * The acceleration in the Z axis. - * - * @return The acceleration of the roboRIO along the Z axis in g-forces - */ - public double getZ() { - return AccelerometerJNI.getAccelerometerZ(); - } - - @Override - public void initSendable(SendableBuilder builder) { - builder.setSmartDashboardType("3AxisAccelerometer"); - builder.addDoubleProperty("X", this::getX, null); - builder.addDoubleProperty("Y", this::getY, null); - builder.addDoubleProperty("Z", this::getZ, null); - } -} diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java index 2dba3ec0a26..47c6cf821f9 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java @@ -321,13 +321,6 @@ public enum BuiltInWidgets implements WidgetType { /** * Displays an accelerometer with a number bar displaying the magnitude of the acceleration and * text displaying the exact value.
- * Supported types: - * - *

- * - *
* Custom properties: * * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/BuiltInAccelerometerSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/BuiltInAccelerometerSim.java deleted file mode 100644 index b8ebd84c88b..00000000000 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/BuiltInAccelerometerSim.java +++ /dev/null @@ -1,184 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package edu.wpi.first.wpilibj.simulation; - -import edu.wpi.first.hal.simulation.AccelerometerDataJNI; -import edu.wpi.first.hal.simulation.NotifyCallback; -import edu.wpi.first.wpilibj.BuiltInAccelerometer; - -/** Class to control a simulated built-in accelerometer. */ -public class BuiltInAccelerometerSim { - private final int m_index; - - /** Constructs for the first built-in accelerometer. */ - public BuiltInAccelerometerSim() { - m_index = 0; - } - - /** - * Constructs from a BuiltInAccelerometer object. - * - * @param accel BuiltInAccelerometer to simulate - */ - @SuppressWarnings("PMD.UnusedFormalParameter") - public BuiltInAccelerometerSim(BuiltInAccelerometer accel) { - m_index = 0; - } - - /** - * Register a callback to be run when this accelerometer activates. - * - * @param callback the callback - * @param initialNotify whether to run the callback with the initial state - * @return the {@link CallbackStore} object associated with this callback. - */ - public CallbackStore registerActiveCallback(NotifyCallback callback, boolean initialNotify) { - int uid = AccelerometerDataJNI.registerActiveCallback(m_index, callback, initialNotify); - return new CallbackStore(m_index, uid, AccelerometerDataJNI::cancelActiveCallback); - } - - /** - * Check whether the accelerometer is active. - * - * @return true if active - */ - public boolean getActive() { - return AccelerometerDataJNI.getActive(m_index); - } - - /** - * Define whether this accelerometer is active. - * - * @param active the new state - */ - public void setActive(boolean active) { - AccelerometerDataJNI.setActive(m_index, active); - } - - /** - * Register a callback to be run whenever the range changes. - * - * @param callback the callback - * @param initialNotify whether to call the callback with the initial state - * @return the {@link CallbackStore} object associated with this callback. - */ - public CallbackStore registerRangeCallback(NotifyCallback callback, boolean initialNotify) { - int uid = AccelerometerDataJNI.registerRangeCallback(m_index, callback, initialNotify); - return new CallbackStore(m_index, uid, AccelerometerDataJNI::cancelRangeCallback); - } - - /** - * Check the range of this accelerometer. - * - * @return the accelerometer range - */ - public int getRange() { - return AccelerometerDataJNI.getRange(m_index); - } - - /** - * Change the range of this accelerometer. - * - * @param range the new accelerometer range - */ - public void setRange(int range) { - AccelerometerDataJNI.setRange(m_index, range); - } - - /** - * Register a callback to be run whenever the X axis value changes. - * - * @param callback the callback - * @param initialNotify whether to call the callback with the initial state - * @return the {@link CallbackStore} object associated with this callback. - */ - public CallbackStore registerXCallback(NotifyCallback callback, boolean initialNotify) { - int uid = AccelerometerDataJNI.registerXCallback(m_index, callback, initialNotify); - return new CallbackStore(m_index, uid, AccelerometerDataJNI::cancelXCallback); - } - - /** - * Measure the X axis value. - * - * @return the X axis measurement - */ - public double getX() { - return AccelerometerDataJNI.getX(m_index); - } - - /** - * Change the X axis value of the accelerometer. - * - * @param x the new reading of the X axis - */ - public void setX(double x) { - AccelerometerDataJNI.setX(m_index, x); - } - - /** - * Register a callback to be run whenever the Y axis value changes. - * - * @param callback the callback - * @param initialNotify whether to call the callback with the initial state - * @return the {@link CallbackStore} object associated with this callback. - */ - public CallbackStore registerYCallback(NotifyCallback callback, boolean initialNotify) { - int uid = AccelerometerDataJNI.registerYCallback(m_index, callback, initialNotify); - return new CallbackStore(m_index, uid, AccelerometerDataJNI::cancelYCallback); - } - - /** - * Measure the Y axis value. - * - * @return the Y axis measurement - */ - public double getY() { - return AccelerometerDataJNI.getY(m_index); - } - - /** - * Change the Y axis value of the accelerometer. - * - * @param y the new reading of the Y axis - */ - public void setY(double y) { - AccelerometerDataJNI.setY(m_index, y); - } - - /** - * Register a callback to be run whenever the Z axis value changes. - * - * @param callback the callback - * @param initialNotify whether to call the callback with the initial state - * @return the {@link CallbackStore} object associated with this callback. - */ - public CallbackStore registerZCallback(NotifyCallback callback, boolean initialNotify) { - int uid = AccelerometerDataJNI.registerZCallback(m_index, callback, initialNotify); - return new CallbackStore(m_index, uid, AccelerometerDataJNI::cancelZCallback); - } - - /** - * Measure the Z axis value. - * - * @return the Z axis measurement - */ - public double getZ() { - return AccelerometerDataJNI.getZ(m_index); - } - - /** - * Change the Z axis value of the accelerometer. - * - * @param z the new reading of the Z axis - */ - public void setZ(double z) { - AccelerometerDataJNI.setZ(m_index, z); - } - - /** Reset all simulation data of this object. */ - public void resetData() { - AccelerometerDataJNI.resetData(m_index); - } -} diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AccelerometerSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AccelerometerSimTest.java deleted file mode 100644 index d4baaed6424..00000000000 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AccelerometerSimTest.java +++ /dev/null @@ -1,135 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package edu.wpi.first.wpilibj.simulation; - -import static org.junit.jupiter.api.Assertions.assertEquals; -import static org.junit.jupiter.api.Assertions.assertFalse; -import static org.junit.jupiter.api.Assertions.assertTrue; - -import edu.wpi.first.hal.HAL; -import edu.wpi.first.wpilibj.BuiltInAccelerometer; -import edu.wpi.first.wpilibj.simulation.testutils.BooleanCallback; -import edu.wpi.first.wpilibj.simulation.testutils.DoubleCallback; -import edu.wpi.first.wpilibj.simulation.testutils.EnumCallback; -import org.junit.jupiter.api.Test; - -class AccelerometerSimTest { - @Test - void testCallbacks() { - HAL.initialize(500, 0); - BuiltInAccelerometerSim sim = new BuiltInAccelerometerSim(); - sim.resetData(); - - BooleanCallback store = new BooleanCallback(); - - try (CallbackStore cb = sim.registerActiveCallback(store, false)) { - assertFalse(store.wasTriggered()); - sim.setActive(true); - assertTrue(sim.getActive()); - assertTrue(store.wasTriggered()); - assertTrue(store.getSetValue()); - } - } - - @Test - void testX() { - HAL.initialize(500, 0); - BuiltInAccelerometerSim sim = new BuiltInAccelerometerSim(); - sim.resetData(); - - DoubleCallback callback = new DoubleCallback(); - final double kTestValue = 1.91; - - try (BuiltInAccelerometer accel = new BuiltInAccelerometer(); - CallbackStore cb = sim.registerXCallback(callback, false)) { - sim.setX(kTestValue); - assertEquals(kTestValue, accel.getX()); - assertEquals(kTestValue, sim.getX()); - assertTrue(callback.wasTriggered()); - assertEquals(kTestValue, callback.getSetValue()); - } - } - - @Test - void testY() { - HAL.initialize(500, 0); - BuiltInAccelerometerSim sim = new BuiltInAccelerometerSim(); - sim.resetData(); - - DoubleCallback callback = new DoubleCallback(); - final double kTestValue = 2.29; - - try (BuiltInAccelerometer accel = new BuiltInAccelerometer(); - CallbackStore cb = sim.registerYCallback(callback, false)) { - sim.setY(kTestValue); - assertEquals(kTestValue, accel.getY()); - assertEquals(kTestValue, sim.getY()); - assertTrue(callback.wasTriggered()); - assertEquals(kTestValue, callback.getSetValue()); - } - } - - @Test - void testZ() { - HAL.initialize(500, 0); - - BuiltInAccelerometerSim sim = new BuiltInAccelerometerSim(); - sim.resetData(); - - DoubleCallback callback = new DoubleCallback(); - final double kTestValue = 3.405; - - try (BuiltInAccelerometer accel = new BuiltInAccelerometer(); - CallbackStore cb = sim.registerZCallback(callback, false)) { - sim.setZ(kTestValue); - assertEquals(kTestValue, accel.getZ()); - assertEquals(kTestValue, sim.getZ()); - assertTrue(callback.wasTriggered()); - assertEquals(kTestValue, callback.getSetValue()); - } - } - - @Test - void testRange() { - HAL.initialize(500, 0); - - BuiltInAccelerometerSim sim = new BuiltInAccelerometerSim(); - sim.resetData(); - - EnumCallback callback = new EnumCallback(); - - BuiltInAccelerometer.Range range = BuiltInAccelerometer.Range.k4G; - try (CallbackStore cb = sim.registerRangeCallback(callback, false); - BuiltInAccelerometer accel = new BuiltInAccelerometer(range)) { - assertTrue(callback.wasTriggered()); - assertEquals(range.ordinal(), sim.getRange()); - assertEquals(range.ordinal(), callback.getSetValue()); - - // 2G - callback.reset(); - range = BuiltInAccelerometer.Range.k2G; - accel.setRange(range); - assertTrue(callback.wasTriggered()); - assertEquals(range.ordinal(), sim.getRange()); - assertEquals(range.ordinal(), callback.getSetValue()); - - // 4G - callback.reset(); - range = BuiltInAccelerometer.Range.k4G; - accel.setRange(range); - assertTrue(callback.wasTriggered()); - assertEquals(range.ordinal(), sim.getRange()); - assertEquals(range.ordinal(), callback.getSetValue()); - - // 8G - callback.reset(); - range = BuiltInAccelerometer.Range.k8G; - accel.setRange(range); - assertTrue(callback.wasTriggered()); - assertEquals(range.ordinal(), sim.getRange()); - assertEquals(range.ordinal(), callback.getSetValue()); - } - } -} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java index 42cf45eef8c..2d2b757df56 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java @@ -5,7 +5,6 @@ package edu.wpi.first.wpilibj.examples.romireference.subsystems; import edu.wpi.first.util.sendable.SendableRegistry; -import edu.wpi.first.wpilibj.BuiltInAccelerometer; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.motorcontrol.Spark; @@ -33,9 +32,6 @@ public class Drivetrain extends SubsystemBase { // Set up the RomiGyro private final RomiGyro m_gyro = new RomiGyro(); - // Set up the BuiltInAccelerometer - private final BuiltInAccelerometer m_accelerometer = new BuiltInAccelerometer(); - /** Creates a new Drivetrain. */ public Drivetrain() { SendableRegistry.addChild(m_diffDrive, m_leftMotor); @@ -81,33 +77,6 @@ public double getAverageDistanceInch() { return (getLeftDistanceInch() + getRightDistanceInch()) / 2.0; } - /** - * The acceleration in the X-axis. - * - * @return The acceleration of the Romi along the X-axis in Gs - */ - public double getAccelX() { - return m_accelerometer.getX(); - } - - /** - * The acceleration in the Y-axis. - * - * @return The acceleration of the Romi along the Y-axis in Gs - */ - public double getAccelY() { - return m_accelerometer.getY(); - } - - /** - * The acceleration in the Z-axis. - * - * @return The acceleration of the Romi along the Z-axis in Gs - */ - public double getAccelZ() { - return m_accelerometer.getZ(); - } - /** * Current angle of the Romi around the X-axis. * diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/subsystems/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/subsystems/Drivetrain.java index 87b985d6522..e596b92905b 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/subsystems/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/subsystems/Drivetrain.java @@ -5,7 +5,6 @@ package edu.wpi.first.wpilibj.examples.xrpreference.subsystems; import edu.wpi.first.util.sendable.SendableRegistry; -import edu.wpi.first.wpilibj.BuiltInAccelerometer; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.xrp.XRPGyro; @@ -36,9 +35,6 @@ public class Drivetrain extends SubsystemBase { // Set up the XRPGyro private final XRPGyro m_gyro = new XRPGyro(); - // Set up the BuiltInAccelerometer - private final BuiltInAccelerometer m_accelerometer = new BuiltInAccelerometer(); - /** Creates a new Drivetrain. */ public Drivetrain() { SendableRegistry.addChild(m_diffDrive, m_leftMotor); @@ -84,33 +80,6 @@ public double getAverageDistanceInch() { return (getLeftDistanceInch() + getRightDistanceInch()) / 2.0; } - /** - * The acceleration in the X-axis. - * - * @return The acceleration of the XRP along the X-axis in Gs - */ - public double getAccelX() { - return m_accelerometer.getX(); - } - - /** - * The acceleration in the Y-axis. - * - * @return The acceleration of the XRP along the Y-axis in Gs - */ - public double getAccelY() { - return m_accelerometer.getY(); - } - - /** - * The acceleration in the Z-axis. - * - * @return The acceleration of the XRP along the Z-axis in Gs - */ - public double getAccelZ() { - return m_accelerometer.getZ(); - } - /** * Current angle of the XRP around the X-axis. *