From ff1b2a205e32a5336866e4f9bc591c1bec5a3bbd Mon Sep 17 00:00:00 2001 From: Thad House Date: Thu, 16 Jan 2025 23:20:44 -0800 Subject: [PATCH] [hal, wpilib] Remove analog output (#7696) --- .../lib/native/cpp/hardware/AnalogOutput.cpp | 55 -------- .../include/glass/hardware/AnalogOutput.h | 30 ----- .../java/edu/wpi/first/hal/AnalogJNI.java | 48 ------- .../main/java/edu/wpi/first/hal/PortsJNI.java | 8 -- .../hal/simulation/AnalogOutDataJNI.java | 33 ----- hal/src/main/native/cpp/jni/AnalogJNI.cpp | 74 ---------- hal/src/main/native/cpp/jni/PortsJNI.cpp | 13 -- .../cpp/jni/simulation/AnalogOutDataJNI.cpp | 127 ------------------ .../main/native/include/hal/AnalogOutput.h | 72 ---------- hal/src/main/native/include/hal/HAL.h | 1 - hal/src/main/native/include/hal/Ports.h | 7 - .../include/hal/simulation/AnalogOutData.h | 37 ----- hal/src/main/native/sim/AnalogOutput.cpp | 111 --------------- hal/src/main/native/sim/HAL.cpp | 2 - hal/src/main/native/sim/HALInitializer.h | 2 - hal/src/main/native/sim/Ports.cpp | 3 - .../native/sim/mockdata/AnalogOutData.cpp | 44 ------ .../sim/mockdata/AnalogOutDataInternal.h | 22 --- hal/src/main/native/sim/mockdata/Reset.cpp | 5 - .../main/native/systemcore/AnalogOutput.cpp | 51 ------- hal/src/main/native/systemcore/HAL.cpp | 1 - .../main/native/systemcore/HALInitializer.h | 1 - hal/src/main/native/systemcore/Ports.cpp | 3 - .../systemcore/mockdata/AnalogOutData.cpp | 22 --- .../native/cpp/mockdata/AnalogOutDataTest.cpp | 88 ------------ .../main/native/cpp/AnalogOutputSimGui.cpp | 92 ------------- .../src/main/native/cpp/AnalogOutputSimGui.h | 14 -- .../halsim_gui/src/main/native/cpp/main.cpp | 2 - .../src/main/native/cpp/HALSimWSClient.cpp | 1 - .../src/main/native/cpp/WSProvider_Analog.cpp | 32 ----- .../main/native/include/WSProvider_Analog.h | 17 --- .../src/main/native/cpp/HALSimWSServer.cpp | 1 - wpilibc/src/main/native/cpp/AnalogOutput.cpp | 61 --------- wpilibc/src/main/native/cpp/SensorUtil.cpp | 9 -- .../native/cpp/simulation/AnalogOutputSim.cpp | 57 -------- .../main/native/include/frc/AnalogOutput.h | 60 --------- .../src/main/native/include/frc/SensorUtil.h | 11 -- .../include/frc/simulation/AnalogOutputSim.h | 95 ------------- .../cpp/simulation/AnalogOutputSimTest.cpp | 89 ------------ .../cpp/simulation/SimInitializationTest.cpp | 2 - .../edu/wpi/first/wpilibj/AnalogOutput.java | 76 ----------- .../edu/wpi/first/wpilibj/SensorUtil.java | 20 --- .../wpilibj/simulation/AnalogOutputSim.java | 97 ------------- .../edu/wpi/first/wpilibj/SensorUtilTest.java | 5 - .../simulation/AnalogOutputSimTest.java | 84 ------------ 45 files changed, 1685 deletions(-) delete mode 100644 glass/src/lib/native/cpp/hardware/AnalogOutput.cpp delete mode 100644 glass/src/lib/native/include/glass/hardware/AnalogOutput.h delete mode 100644 hal/src/main/java/edu/wpi/first/hal/simulation/AnalogOutDataJNI.java delete mode 100644 hal/src/main/native/cpp/jni/simulation/AnalogOutDataJNI.cpp delete mode 100644 hal/src/main/native/include/hal/AnalogOutput.h delete mode 100644 hal/src/main/native/include/hal/simulation/AnalogOutData.h delete mode 100644 hal/src/main/native/sim/AnalogOutput.cpp delete mode 100644 hal/src/main/native/sim/mockdata/AnalogOutData.cpp delete mode 100644 hal/src/main/native/sim/mockdata/AnalogOutDataInternal.h delete mode 100644 hal/src/main/native/systemcore/AnalogOutput.cpp delete mode 100644 hal/src/main/native/systemcore/mockdata/AnalogOutData.cpp delete mode 100644 hal/src/test/native/cpp/mockdata/AnalogOutDataTest.cpp delete mode 100644 simulation/halsim_gui/src/main/native/cpp/AnalogOutputSimGui.cpp delete mode 100644 simulation/halsim_gui/src/main/native/cpp/AnalogOutputSimGui.h delete mode 100644 wpilibc/src/main/native/cpp/AnalogOutput.cpp delete mode 100644 wpilibc/src/main/native/cpp/simulation/AnalogOutputSim.cpp delete mode 100644 wpilibc/src/main/native/include/frc/AnalogOutput.h delete mode 100644 wpilibc/src/main/native/include/frc/simulation/AnalogOutputSim.h delete mode 100644 wpilibc/src/test/native/cpp/simulation/AnalogOutputSimTest.cpp delete mode 100644 wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java delete mode 100644 wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogOutputSim.java delete mode 100644 wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AnalogOutputSimTest.java diff --git a/glass/src/lib/native/cpp/hardware/AnalogOutput.cpp b/glass/src/lib/native/cpp/hardware/AnalogOutput.cpp deleted file mode 100644 index 11790f8ca8..0000000000 --- a/glass/src/lib/native/cpp/hardware/AnalogOutput.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 "glass/hardware/AnalogOutput.h" - -#include - -#include - -#include "glass/Context.h" -#include "glass/DataSource.h" -#include "glass/Storage.h" -#include "glass/other/DeviceTree.h" - -using namespace glass; - -void glass::DisplayAnalogOutputsDevice(AnalogOutputsModel* model) { - int count = 0; - model->ForEachAnalogOutput([&](auto&, int) { ++count; }); - if (count == 0) { - return; - } - - if (BeginDevice("Analog Outputs")) { - model->ForEachAnalogOutput([&](auto& analogOut, int i) { - auto analogOutData = analogOut.GetVoltageData(); - if (!analogOutData) { - return; - } - PushID(i); - - // build label - std::string& name = GetStorage().GetString("name"); - char label[128]; - if (!name.empty()) { - wpi::format_to_n_c_str(label, sizeof(label), "{} [{}]###name", name, i); - } else { - wpi::format_to_n_c_str(label, sizeof(label), "Out[{}]###name", i); - } - - double value = analogOutData->GetValue(); - DeviceDouble(label, true, &value, analogOutData); - - if (PopupEditName("name", &name)) { - if (analogOutData) { - analogOutData->SetName(name); - } - } - PopID(); - }); - - EndDevice(); - } -} diff --git a/glass/src/lib/native/include/glass/hardware/AnalogOutput.h b/glass/src/lib/native/include/glass/hardware/AnalogOutput.h deleted file mode 100644 index da24384ba3..0000000000 --- a/glass/src/lib/native/include/glass/hardware/AnalogOutput.h +++ /dev/null @@ -1,30 +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 "glass/Model.h" - -namespace glass { - -class DoubleSource; - -class AnalogOutputModel : public Model { - public: - virtual DoubleSource* GetVoltageData() = 0; - - virtual void SetVoltage(double val) = 0; -}; - -class AnalogOutputsModel : public Model { - public: - virtual void ForEachAnalogOutput( - wpi::function_ref func) = 0; -}; - -void DisplayAnalogOutputsDevice(AnalogOutputsModel* model); - -} // namespace glass diff --git a/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java b/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java index f2996f60c2..9398deb8ea 100644 --- a/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java +++ b/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java @@ -8,7 +8,6 @@ package edu.wpi.first.hal; * Analog Input / Output / Accumulator / Trigger JNI Functions. * * @see "hal/AnalogInput.h" - * @see "hal/AnalogOutput.h" * @see "hal/AnalogAccumulator.h" * @see "hal/AnalogTrigger.h" */ @@ -48,23 +47,6 @@ public class AnalogJNI extends JNIWrapper { */ public static native void freeAnalogInputPort(int portHandle); - /** - * Initializes the analog output port using the given port object. - * - * @param halPortHandle handle to the port - * @return the created analog output handle - * @see "HAL_InitializeAnalogOutputPort" - */ - public static native int initializeAnalogOutputPort(int halPortHandle); - - /** - * Frees an analog output port. - * - * @param portHandle the analog output handle - * @see "HAL_FreeAnalogOutputPort" - */ - public static native void freeAnalogOutputPort(int portHandle); - /** * Checks that the analog module number is valid. * @@ -84,18 +66,6 @@ public class AnalogJNI extends JNIWrapper { */ public static native boolean checkAnalogInputChannel(int channel); - /** - * Checks that the analog output channel number is valid. - * - *

Verifies that the analog channel number is one of the legal channel numbers. Channel numbers - * are 0-based. - * - * @param channel The analog output channel number. - * @return Analog channel is valid - * @see "HAL_CheckAnalogOutputChannel" - */ - public static native boolean checkAnalogOutputChannel(int channel); - /** * Indicates the analog input is used by a simulated device. * @@ -105,24 +75,6 @@ public class AnalogJNI extends JNIWrapper { */ public static native void setAnalogInputSimDevice(int handle, int device); - /** - * Sets an analog output value. - * - * @param portHandle the analog output handle - * @param voltage the voltage (0-5v) to output - * @see "HAL_SetAnalogOutput" - */ - public static native void setAnalogOutput(int portHandle, double voltage); - - /** - * Gets the current analog output value. - * - * @param portHandle the analog output handle - * @return the current output voltage (0-5v) - * @see "HAL_GetAnalogOutput" - */ - public static native double getAnalogOutput(int portHandle); - /** * Sets the sample rate. * diff --git a/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java b/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java index 949c0bf8f0..57ee0fdd2d 100644 --- a/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java +++ b/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java @@ -34,14 +34,6 @@ public class PortsJNI extends JNIWrapper { */ public static native int getNumAnalogInputs(); - /** - * Gets the number of analog outputs in the current system. - * - * @return the number of analog outputs - * @see "HAL_GetNumAnalogOutputs" - */ - public static native int getNumAnalogOutputs(); - /** * Gets the number of counters in the current system. * diff --git a/hal/src/main/java/edu/wpi/first/hal/simulation/AnalogOutDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/simulation/AnalogOutDataJNI.java deleted file mode 100644 index f8e4eeccd1..0000000000 --- a/hal/src/main/java/edu/wpi/first/hal/simulation/AnalogOutDataJNI.java +++ /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. - -package edu.wpi.first.hal.simulation; - -import edu.wpi.first.hal.JNIWrapper; - -/** JNI for analog output data. */ -public class AnalogOutDataJNI extends JNIWrapper { - public static native int registerVoltageCallback( - int index, NotifyCallback callback, boolean initialNotify); - - public static native void cancelVoltageCallback(int index, int uid); - - public static native double getVoltage(int index); - - public static native void setVoltage(int index, double voltage); - - public static native int registerInitializedCallback( - int index, NotifyCallback callback, boolean initialNotify); - - public static native void cancelInitializedCallback(int index, int uid); - - public static native boolean getInitialized(int index); - - public static native void setInitialized(int index, boolean initialized); - - public static native void resetData(int index); - - /** Utility class. */ - private AnalogOutDataJNI() {} -} diff --git a/hal/src/main/native/cpp/jni/AnalogJNI.cpp b/hal/src/main/native/cpp/jni/AnalogJNI.cpp index 24d48f39c8..b911104dab 100644 --- a/hal/src/main/native/cpp/jni/AnalogJNI.cpp +++ b/hal/src/main/native/cpp/jni/AnalogJNI.cpp @@ -12,7 +12,6 @@ #include "edu_wpi_first_hal_AnalogJNI.h" #include "hal/AnalogAccumulator.h" #include "hal/AnalogInput.h" -#include "hal/AnalogOutput.h" #include "hal/AnalogTrigger.h" #include "hal/Ports.h" #include "hal/handles/HandlesInternal.h" @@ -52,37 +51,6 @@ Java_edu_wpi_first_hal_AnalogJNI_freeAnalogInputPort } } -/* - * Class: edu_wpi_first_hal_AnalogJNI - * Method: initializeAnalogOutputPort - * Signature: (I)I - */ -JNIEXPORT jint JNICALL -Java_edu_wpi_first_hal_AnalogJNI_initializeAnalogOutputPort - (JNIEnv* env, jclass, jint id) -{ - int32_t status = 0; - auto stack = wpi::java::GetJavaStackTrace(env, "edu.wpi.first"); - HAL_AnalogOutputHandle analog = HAL_InitializeAnalogOutputPort( - (HAL_PortHandle)id, stack.c_str(), &status); - CheckStatusForceThrow(env, status); - return (jlong)analog; -} - -/* - * Class: edu_wpi_first_hal_AnalogJNI - * Method: freeAnalogOutputPort - * Signature: (I)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_AnalogJNI_freeAnalogOutputPort - (JNIEnv* env, jclass, jint id) -{ - if (id != HAL_kInvalidHandle) { - HAL_FreeAnalogOutputPort((HAL_AnalogOutputHandle)id); - } -} - /* * Class: edu_wpi_first_hal_AnalogJNI * Method: checkAnalogModule @@ -109,19 +77,6 @@ Java_edu_wpi_first_hal_AnalogJNI_checkAnalogInputChannel return returnValue; } -/* - * Class: edu_wpi_first_hal_AnalogJNI - * Method: checkAnalogOutputChannel - * Signature: (I)Z - */ -JNIEXPORT jboolean JNICALL -Java_edu_wpi_first_hal_AnalogJNI_checkAnalogOutputChannel - (JNIEnv*, jclass, jint value) -{ - jboolean returnValue = HAL_CheckAnalogOutputChannel(value); - return returnValue; -} - /* * Class: edu_wpi_first_hal_AnalogJNI * Method: setAnalogInputSimDevice @@ -135,35 +90,6 @@ Java_edu_wpi_first_hal_AnalogJNI_setAnalogInputSimDevice (HAL_SimDeviceHandle)device); } -/* - * Class: edu_wpi_first_hal_AnalogJNI - * Method: setAnalogOutput - * Signature: (ID)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_AnalogJNI_setAnalogOutput - (JNIEnv* env, jclass, jint id, jdouble voltage) -{ - int32_t status = 0; - HAL_SetAnalogOutput((HAL_AnalogOutputHandle)id, voltage, &status); - CheckStatus(env, status); -} - -/* - * Class: edu_wpi_first_hal_AnalogJNI - * Method: getAnalogOutput - * Signature: (I)D - */ -JNIEXPORT jdouble JNICALL -Java_edu_wpi_first_hal_AnalogJNI_getAnalogOutput - (JNIEnv* env, jclass, jint id) -{ - int32_t status = 0; - double val = HAL_GetAnalogOutput((HAL_AnalogOutputHandle)id, &status); - CheckStatus(env, status); - return val; -} - /* * Class: edu_wpi_first_hal_AnalogJNI * Method: setAnalogSampleRate diff --git a/hal/src/main/native/cpp/jni/PortsJNI.cpp b/hal/src/main/native/cpp/jni/PortsJNI.cpp index 9ee10781bb..1042de6db4 100644 --- a/hal/src/main/native/cpp/jni/PortsJNI.cpp +++ b/hal/src/main/native/cpp/jni/PortsJNI.cpp @@ -52,19 +52,6 @@ Java_edu_wpi_first_hal_PortsJNI_getNumAnalogInputs return value; } -/* - * Class: edu_wpi_first_hal_PortsJNI - * Method: getNumAnalogOutputs - * Signature: ()I - */ -JNIEXPORT jint JNICALL -Java_edu_wpi_first_hal_PortsJNI_getNumAnalogOutputs - (JNIEnv* env, jclass) -{ - jint value = HAL_GetNumAnalogOutputs(); - return value; -} - /* * Class: edu_wpi_first_hal_PortsJNI * Method: getNumCounters diff --git a/hal/src/main/native/cpp/jni/simulation/AnalogOutDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/AnalogOutDataJNI.cpp deleted file mode 100644 index ce74fad648..0000000000 --- a/hal/src/main/native/cpp/jni/simulation/AnalogOutDataJNI.cpp +++ /dev/null @@ -1,127 +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_AnalogOutDataJNI.h" -#include "hal/simulation/AnalogOutData.h" - -using namespace hal; - -extern "C" { - -/* - * Class: edu_wpi_first_hal_simulation_AnalogOutDataJNI - * Method: registerVoltageCallback - * Signature: (ILjava/lang/Object;Z)I - */ -JNIEXPORT jint JNICALL -Java_edu_wpi_first_hal_simulation_AnalogOutDataJNI_registerVoltageCallback - (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify) -{ - return sim::AllocateCallback(env, index, callback, initialNotify, - &HALSIM_RegisterAnalogOutVoltageCallback); -} - -/* - * Class: edu_wpi_first_hal_simulation_AnalogOutDataJNI - * Method: cancelVoltageCallback - * Signature: (II)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AnalogOutDataJNI_cancelVoltageCallback - (JNIEnv* env, jclass, jint index, jint handle) -{ - return sim::FreeCallback(env, handle, index, - &HALSIM_CancelAnalogOutVoltageCallback); -} - -/* - * Class: edu_wpi_first_hal_simulation_AnalogOutDataJNI - * Method: getVoltage - * Signature: (I)D - */ -JNIEXPORT jdouble JNICALL -Java_edu_wpi_first_hal_simulation_AnalogOutDataJNI_getVoltage - (JNIEnv*, jclass, jint index) -{ - return HALSIM_GetAnalogOutVoltage(index); -} - -/* - * Class: edu_wpi_first_hal_simulation_AnalogOutDataJNI - * Method: setVoltage - * Signature: (ID)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AnalogOutDataJNI_setVoltage - (JNIEnv*, jclass, jint index, jdouble value) -{ - HALSIM_SetAnalogOutVoltage(index, value); -} - -/* - * Class: edu_wpi_first_hal_simulation_AnalogOutDataJNI - * Method: registerInitializedCallback - * Signature: (ILjava/lang/Object;Z)I - */ -JNIEXPORT jint JNICALL -Java_edu_wpi_first_hal_simulation_AnalogOutDataJNI_registerInitializedCallback - (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify) -{ - return sim::AllocateCallback(env, index, callback, initialNotify, - &HALSIM_RegisterAnalogOutInitializedCallback); -} - -/* - * Class: edu_wpi_first_hal_simulation_AnalogOutDataJNI - * Method: cancelInitializedCallback - * Signature: (II)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AnalogOutDataJNI_cancelInitializedCallback - (JNIEnv* env, jclass, jint index, jint handle) -{ - return sim::FreeCallback(env, handle, index, - &HALSIM_CancelAnalogOutInitializedCallback); -} - -/* - * Class: edu_wpi_first_hal_simulation_AnalogOutDataJNI - * Method: getInitialized - * Signature: (I)Z - */ -JNIEXPORT jboolean JNICALL -Java_edu_wpi_first_hal_simulation_AnalogOutDataJNI_getInitialized - (JNIEnv*, jclass, jint index) -{ - return HALSIM_GetAnalogOutInitialized(index); -} - -/* - * Class: edu_wpi_first_hal_simulation_AnalogOutDataJNI - * Method: setInitialized - * Signature: (IZ)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AnalogOutDataJNI_setInitialized - (JNIEnv*, jclass, jint index, jboolean value) -{ - HALSIM_SetAnalogOutInitialized(index, value); -} - -/* - * Class: edu_wpi_first_hal_simulation_AnalogOutDataJNI - * Method: resetData - * Signature: (I)V - */ -JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_simulation_AnalogOutDataJNI_resetData - (JNIEnv*, jclass, jint index) -{ - HALSIM_ResetAnalogOutData(index); -} - -} // extern "C" diff --git a/hal/src/main/native/include/hal/AnalogOutput.h b/hal/src/main/native/include/hal/AnalogOutput.h deleted file mode 100644 index f9a1f3655e..0000000000 --- a/hal/src/main/native/include/hal/AnalogOutput.h +++ /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. - -#pragma once - -#include - -#include "hal/Types.h" - -/** - * @defgroup hal_analogoutput Analog Output Functions - * @ingroup hal_capi - * @{ - */ - -#ifdef __cplusplus -extern "C" { -#endif - -/** - * Initializes the analog output port using the given port object. - * - * @param[in] portHandle handle to the port - * @param[in] allocationLocation the location where the allocation is occurring - * (can be null) - * @param[out] status Error status variable. 0 on success. - * @return the created analog output handle - */ -HAL_AnalogOutputHandle HAL_InitializeAnalogOutputPort( - HAL_PortHandle portHandle, const char* allocationLocation, int32_t* status); - -/** - * Frees an analog output port. - * - * @param analogOutputHandle the analog output handle - */ -void HAL_FreeAnalogOutputPort(HAL_AnalogOutputHandle analogOutputHandle); - -/** - * Sets an analog output value. - * - * @param[in] analogOutputHandle the analog output handle - * @param[in] voltage the voltage (0-5v) to output - * @param[out] status Error status variable. 0 on success. - */ -void HAL_SetAnalogOutput(HAL_AnalogOutputHandle analogOutputHandle, - double voltage, int32_t* status); - -/** - * Gets the current analog output value. - * - * @param[in] analogOutputHandle the analog output handle - * @param[out] status Error status variable. 0 on success. - * @return the current output voltage (0-5v) - */ -double HAL_GetAnalogOutput(HAL_AnalogOutputHandle analogOutputHandle, - int32_t* status); - -/** - * Checks that the analog output channel number is valid. - * - * Verifies that the analog channel number is one of the legal channel numbers. - * Channel numbers are 0-based. - * - * @return Analog channel is valid - */ -HAL_Bool HAL_CheckAnalogOutputChannel(int32_t channel); -#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 4ffbfcea4b..a6b9953d01 100644 --- a/hal/src/main/native/include/hal/HAL.h +++ b/hal/src/main/native/include/hal/HAL.h @@ -10,7 +10,6 @@ #include "hal/AnalogAccumulator.h" #include "hal/AnalogGyro.h" #include "hal/AnalogInput.h" -#include "hal/AnalogOutput.h" #include "hal/AnalogTrigger.h" #include "hal/CAN.h" #include "hal/CANAPI.h" diff --git a/hal/src/main/native/include/hal/Ports.h b/hal/src/main/native/include/hal/Ports.h index 4ba0c6e9dd..edc47d9680 100644 --- a/hal/src/main/native/include/hal/Ports.h +++ b/hal/src/main/native/include/hal/Ports.h @@ -37,13 +37,6 @@ int32_t HAL_GetNumAnalogTriggers(void); */ int32_t HAL_GetNumAnalogInputs(void); -/** - * Gets the number of analog outputs in the current system. - * - * @return the number of analog outputs - */ -int32_t HAL_GetNumAnalogOutputs(void); - /** * Gets the number of counters in the current system. * diff --git a/hal/src/main/native/include/hal/simulation/AnalogOutData.h b/hal/src/main/native/include/hal/simulation/AnalogOutData.h deleted file mode 100644 index 00275c66fc..0000000000 --- a/hal/src/main/native/include/hal/simulation/AnalogOutData.h +++ /dev/null @@ -1,37 +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" -#include "hal/simulation/NotifyListener.h" - -#ifdef __cplusplus -extern "C" { -#endif - -void HALSIM_ResetAnalogOutData(int32_t index); -int32_t HALSIM_RegisterAnalogOutVoltageCallback(int32_t index, - HAL_NotifyCallback callback, - void* param, - HAL_Bool initialNotify); -void HALSIM_CancelAnalogOutVoltageCallback(int32_t index, int32_t uid); -double HALSIM_GetAnalogOutVoltage(int32_t index); -void HALSIM_SetAnalogOutVoltage(int32_t index, double voltage); - -int32_t HALSIM_RegisterAnalogOutInitializedCallback(int32_t index, - HAL_NotifyCallback callback, - void* param, - HAL_Bool initialNotify); -void HALSIM_CancelAnalogOutInitializedCallback(int32_t index, int32_t uid); -HAL_Bool HALSIM_GetAnalogOutInitialized(int32_t index); -void HALSIM_SetAnalogOutInitialized(int32_t index, HAL_Bool initialized); - -void HALSIM_RegisterAnalogOutAllCallbacks(int32_t index, - HAL_NotifyCallback callback, - void* param, HAL_Bool initialNotify); - -#ifdef __cplusplus -} // extern "C" -#endif diff --git a/hal/src/main/native/sim/AnalogOutput.cpp b/hal/src/main/native/sim/AnalogOutput.cpp deleted file mode 100644 index d04224a4a6..0000000000 --- a/hal/src/main/native/sim/AnalogOutput.cpp +++ /dev/null @@ -1,111 +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/AnalogOutput.h" - -#include - -#include "HALInitializer.h" -#include "HALInternal.h" -#include "PortsInternal.h" -#include "hal/Errors.h" -#include "hal/handles/HandlesInternal.h" -#include "hal/handles/IndexedHandleResource.h" -#include "mockdata/AnalogOutDataInternal.h" - -using namespace hal; - -namespace { -struct AnalogOutput { - uint8_t channel; - std::string previousAllocation; -}; -} // namespace - -static IndexedHandleResource* - analogOutputHandles; - -namespace hal::init { -void InitializeAnalogOutput() { - static IndexedHandleResource - aoH; - analogOutputHandles = &aoH; -} -} // namespace hal::init - -extern "C" { -HAL_AnalogOutputHandle HAL_InitializeAnalogOutputPort( - HAL_PortHandle portHandle, const char* allocationLocation, - int32_t* status) { - hal::init::CheckInit(); - int16_t channel = getPortHandleChannel(portHandle); - if (channel == InvalidHandleIndex || channel >= kNumAnalogOutputs) { - *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Analog Output", - 0, kNumAnalogOutputs, channel); - return HAL_kInvalidHandle; - } - - HAL_AnalogOutputHandle handle; - auto port = analogOutputHandles->Allocate(channel, &handle, status); - - if (*status != 0) { - if (port) { - hal::SetLastErrorPreviouslyAllocated(status, "Analog Output", channel, - port->previousAllocation); - } else { - hal::SetLastErrorIndexOutOfRange(status, - "Invalid Index for Analog Output", 0, - kNumAnalogOutputs, channel); - } - return HAL_kInvalidHandle; // failed to allocate. Pass error back. - } - - port->channel = static_cast(channel); - - // Initialize sim analog input - SimAnalogOutData[channel].initialized = true; - - port->previousAllocation = allocationLocation ? allocationLocation : ""; - return handle; -} - -void HAL_FreeAnalogOutputPort(HAL_AnalogOutputHandle analogOutputHandle) { - // no status, so no need to check for a proper free. - auto port = analogOutputHandles->Get(analogOutputHandle); - if (port == nullptr) { - return; - } - analogOutputHandles->Free(analogOutputHandle); - SimAnalogOutData[port->channel].initialized = false; -} - -HAL_Bool HAL_CheckAnalogOutputChannel(int32_t channel) { - return channel < kNumAnalogOutputs && channel >= 0; -} - -void HAL_SetAnalogOutput(HAL_AnalogOutputHandle analogOutputHandle, - double voltage, int32_t* status) { - auto port = analogOutputHandles->Get(analogOutputHandle); - if (port == nullptr) { - *status = HAL_HANDLE_ERROR; - return; - } - - SimAnalogOutData[port->channel].voltage = voltage; -} - -double HAL_GetAnalogOutput(HAL_AnalogOutputHandle analogOutputHandle, - int32_t* status) { - auto port = analogOutputHandles->Get(analogOutputHandle); - if (port == nullptr) { - *status = HAL_HANDLE_ERROR; - return 0.0; - } - - return SimAnalogOutData[port->channel].voltage; -} -} // extern "C" diff --git a/hal/src/main/native/sim/HAL.cpp b/hal/src/main/native/sim/HAL.cpp index 7fed298499..a8385f2591 100644 --- a/hal/src/main/native/sim/HAL.cpp +++ b/hal/src/main/native/sim/HAL.cpp @@ -70,7 +70,6 @@ void InitializeHAL() { InitializeAddressableLEDData(); InitializeAnalogGyroData(); InitializeAnalogInData(); - InitializeAnalogOutData(); InitializeAnalogTriggerData(); InitializeCanData(); InitializeCANAPI(); @@ -94,7 +93,6 @@ void InitializeHAL() { InitializeAnalogGyro(); InitializeAnalogInput(); InitializeAnalogInternal(); - InitializeAnalogOutput(); InitializeAnalogTrigger(); InitializeCAN(); InitializeConstants(); diff --git a/hal/src/main/native/sim/HALInitializer.h b/hal/src/main/native/sim/HALInitializer.h index db3f02ca50..fe675929e0 100644 --- a/hal/src/main/native/sim/HALInitializer.h +++ b/hal/src/main/native/sim/HALInitializer.h @@ -20,7 +20,6 @@ extern void InitializeAccelerometerData(); extern void InitializeAddressableLEDData(); extern void InitializeAnalogGyroData(); extern void InitializeAnalogInData(); -extern void InitializeAnalogOutData(); extern void InitializeAnalogTriggerData(); extern void InitializeCanData(); extern void InitializeCANAPI(); @@ -45,7 +44,6 @@ extern void InitializeAnalogAccumulator(); extern void InitializeAnalogGyro(); extern void InitializeAnalogInput(); extern void InitializeAnalogInternal(); -extern void InitializeAnalogOutput(); extern void InitializeAnalogTrigger(); extern void InitializeCAN(); extern void InitializeConstants(); diff --git a/hal/src/main/native/sim/Ports.cpp b/hal/src/main/native/sim/Ports.cpp index 86118fcaa1..9219b04b7f 100644 --- a/hal/src/main/native/sim/Ports.cpp +++ b/hal/src/main/native/sim/Ports.cpp @@ -22,9 +22,6 @@ int32_t HAL_GetNumAnalogTriggers(void) { int32_t HAL_GetNumAnalogInputs(void) { return kNumAnalogInputs; } -int32_t HAL_GetNumAnalogOutputs(void) { - return kNumAnalogOutputs; -} int32_t HAL_GetNumCounters(void) { return kNumCounters; } diff --git a/hal/src/main/native/sim/mockdata/AnalogOutData.cpp b/hal/src/main/native/sim/mockdata/AnalogOutData.cpp deleted file mode 100644 index 0ec39e0e81..0000000000 --- a/hal/src/main/native/sim/mockdata/AnalogOutData.cpp +++ /dev/null @@ -1,44 +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 "AnalogOutDataInternal.h" - -using namespace hal; - -namespace hal::init { -void InitializeAnalogOutData() { - static AnalogOutData siod[kNumAnalogOutputs]; - ::hal::SimAnalogOutData = siod; -} -} // namespace hal::init - -AnalogOutData* hal::SimAnalogOutData; -void AnalogOutData::ResetData() { - voltage.Reset(0.0); - initialized.Reset(0); -} - -extern "C" { -void HALSIM_ResetAnalogOutData(int32_t index) { - SimAnalogOutData[index].ResetData(); -} - -#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME) \ - HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, AnalogOut##CAPINAME, \ - SimAnalogOutData, LOWERNAME) - -DEFINE_CAPI(double, Voltage, voltage) -DEFINE_CAPI(HAL_Bool, Initialized, initialized) - -#define REGISTER(NAME) \ - SimAnalogOutData[index].NAME.RegisterCallback(callback, param, initialNotify) - -void HALSIM_RegisterAnalogOutAllCallbacks(int32_t index, - HAL_NotifyCallback callback, - void* param, HAL_Bool initialNotify) { - REGISTER(voltage); - REGISTER(initialized); -} -} // extern "C" diff --git a/hal/src/main/native/sim/mockdata/AnalogOutDataInternal.h b/hal/src/main/native/sim/mockdata/AnalogOutDataInternal.h deleted file mode 100644 index d4a61b2067..0000000000 --- a/hal/src/main/native/sim/mockdata/AnalogOutDataInternal.h +++ /dev/null @@ -1,22 +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/AnalogOutData.h" -#include "hal/simulation/SimDataValue.h" - -namespace hal { -class AnalogOutData { - HAL_SIMDATAVALUE_DEFINE_NAME(Voltage) - HAL_SIMDATAVALUE_DEFINE_NAME(Initialized) - - public: - SimDataValue voltage{0.0}; - SimDataValue initialized{0}; - - virtual void ResetData(); -}; -extern AnalogOutData* SimAnalogOutData; -} // namespace hal diff --git a/hal/src/main/native/sim/mockdata/Reset.cpp b/hal/src/main/native/sim/mockdata/Reset.cpp index 2a7e107393..1b1c945ea1 100644 --- a/hal/src/main/native/sim/mockdata/Reset.cpp +++ b/hal/src/main/native/sim/mockdata/Reset.cpp @@ -6,7 +6,6 @@ #include #include #include -#include #include #include #include @@ -43,10 +42,6 @@ extern "C" void HALSIM_ResetAllSimData(void) { HALSIM_ResetAnalogInData(i); } - for (int32_t i = 0; i < hal::kNumAnalogOutputs; i++) { - HALSIM_ResetAnalogOutData(i); - } - for (int32_t i = 0; i < hal::kNumAnalogTriggers; i++) { HALSIM_ResetAnalogTriggerData(i); } diff --git a/hal/src/main/native/systemcore/AnalogOutput.cpp b/hal/src/main/native/systemcore/AnalogOutput.cpp deleted file mode 100644 index fa91841783..0000000000 --- a/hal/src/main/native/systemcore/AnalogOutput.cpp +++ /dev/null @@ -1,51 +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/AnalogOutput.h" - -#include - -#include "HALInitializer.h" -#include "HALInternal.h" -#include "PortsInternal.h" -#include "hal/Errors.h" -#include "hal/handles/HandlesInternal.h" -#include "hal/handles/IndexedHandleResource.h" - -using namespace hal; - -namespace hal::init { -void InitializeAnalogOutput() {} -} // namespace hal::init - -extern "C" { - -HAL_AnalogOutputHandle HAL_InitializeAnalogOutputPort( - HAL_PortHandle portHandle, const char* allocationLocation, - int32_t* status) { - hal::init::CheckInit(); - - *status = HAL_HANDLE_ERROR; - return HAL_kInvalidHandle; -} - -HAL_Bool HAL_CheckAnalogOutputChannel(int32_t channel) { - return channel < kNumAnalogOutputs && channel >= 0; -} - -void HAL_FreeAnalogOutputPort(HAL_AnalogOutputHandle analogOutputHandle) {} - -void HAL_SetAnalogOutput(HAL_AnalogOutputHandle analogOutputHandle, - double voltage, int32_t* status) { - *status = HAL_HANDLE_ERROR; - return; -} - -double HAL_GetAnalogOutput(HAL_AnalogOutputHandle analogOutputHandle, - int32_t* status) { - *status = HAL_HANDLE_ERROR; - return 0; -} - -} // extern "C" diff --git a/hal/src/main/native/systemcore/HAL.cpp b/hal/src/main/native/systemcore/HAL.cpp index 59aba58114..3c3d0750ad 100644 --- a/hal/src/main/native/systemcore/HAL.cpp +++ b/hal/src/main/native/systemcore/HAL.cpp @@ -53,7 +53,6 @@ void InitializeHAL() { InitializeAnalogAccumulator(); InitializeAnalogGyro(); InitializeAnalogInput(); - InitializeAnalogOutput(); InitializeAnalogTrigger(); InitializeCAN(); InitializeCANAPI(); diff --git a/hal/src/main/native/systemcore/HALInitializer.h b/hal/src/main/native/systemcore/HALInitializer.h index 447e0f47fd..0bc618e6da 100644 --- a/hal/src/main/native/systemcore/HALInitializer.h +++ b/hal/src/main/native/systemcore/HALInitializer.h @@ -24,7 +24,6 @@ extern void InitializeAnalogAccumulator(); extern void InitializeAnalogGyro(); extern void InitializeAnalogInput(); extern void InitializeAnalogInternal(); -extern void InitializeAnalogOutput(); extern void InitializeAnalogTrigger(); extern void InitializeCAN(); extern void InitializeCANAPI(); diff --git a/hal/src/main/native/systemcore/Ports.cpp b/hal/src/main/native/systemcore/Ports.cpp index 55407daa7b..a302709bd8 100644 --- a/hal/src/main/native/systemcore/Ports.cpp +++ b/hal/src/main/native/systemcore/Ports.cpp @@ -23,9 +23,6 @@ int32_t HAL_GetNumAnalogTriggers(void) { int32_t HAL_GetNumAnalogInputs(void) { return kNumAnalogInputs; } -int32_t HAL_GetNumAnalogOutputs(void) { - return kNumAnalogOutputs; -} int32_t HAL_GetNumCounters(void) { return kNumCounters; } diff --git a/hal/src/main/native/systemcore/mockdata/AnalogOutData.cpp b/hal/src/main/native/systemcore/mockdata/AnalogOutData.cpp deleted file mode 100644 index e6da2aaf99..0000000000 --- a/hal/src/main/native/systemcore/mockdata/AnalogOutData.cpp +++ /dev/null @@ -1,22 +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/AnalogOutData.h" - -#include "hal/simulation/SimDataValue.h" - -extern "C" { -void HALSIM_ResetAnalogOutData(int32_t index) {} - -#define DEFINE_CAPI(TYPE, CAPINAME, RETURN) \ - HAL_SIMDATAVALUE_STUB_CAPI(TYPE, HALSIM, AnalogOut##CAPINAME, RETURN) - -DEFINE_CAPI(double, Voltage, 0) -DEFINE_CAPI(HAL_Bool, Initialized, false) - -void HALSIM_RegisterAnalogOutAllCallbacks(int32_t index, - HAL_NotifyCallback callback, - void* param, HAL_Bool initialNotify) { -} -} // extern "C" diff --git a/hal/src/test/native/cpp/mockdata/AnalogOutDataTest.cpp b/hal/src/test/native/cpp/mockdata/AnalogOutDataTest.cpp deleted file mode 100644 index 56ed8ba053..0000000000 --- a/hal/src/test/native/cpp/mockdata/AnalogOutDataTest.cpp +++ /dev/null @@ -1,88 +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 - -#include "hal/AnalogOutput.h" -#include "hal/HAL.h" -#include "hal/handles/HandlesInternal.h" -#include "hal/simulation/AnalogOutData.h" - -namespace hal { - -std::string gTestAnalogOutCallbackName; -HAL_Value gTestAnalogOutCallbackValue; - -void TestAnalogOutInitializationCallback(const char* name, void* param, - const struct HAL_Value* value) { - gTestAnalogOutCallbackName = name; - gTestAnalogOutCallbackValue = *value; -} - -TEST(AnalogOutSimTest, AnalogOutInitialization) { - const int INDEX_TO_TEST = 1; - - int callbackParam = 0; - int callbackId = HALSIM_RegisterAnalogOutInitializedCallback( - INDEX_TO_TEST, &TestAnalogOutInitializationCallback, &callbackParam, - false); - ASSERT_TRUE(0 != callbackId); - - int32_t status = 0; - HAL_PortHandle portHandle; - HAL_DigitalHandle analogOutHandle; - - // Use out of range index - portHandle = 8000; - gTestAnalogOutCallbackName = "Unset"; - analogOutHandle = - HAL_InitializeAnalogOutputPort(portHandle, nullptr, &status); - EXPECT_EQ(HAL_kInvalidHandle, analogOutHandle); - EXPECT_EQ(HAL_USE_LAST_ERROR, status); - HAL_GetLastError(&status); - EXPECT_EQ(RESOURCE_OUT_OF_RANGE, status); - EXPECT_STREQ("Unset", gTestAnalogOutCallbackName.c_str()); - - // Successful setup - status = 0; - portHandle = HAL_GetPort(INDEX_TO_TEST); - gTestAnalogOutCallbackName = "Unset"; - analogOutHandle = - HAL_InitializeAnalogOutputPort(portHandle, nullptr, &status); - EXPECT_TRUE(HAL_kInvalidHandle != analogOutHandle); - EXPECT_EQ(0, status); - EXPECT_STREQ("Initialized", gTestAnalogOutCallbackName.c_str()); - - // Double initialize... should fail - status = 0; - portHandle = HAL_GetPort(INDEX_TO_TEST); - gTestAnalogOutCallbackName = "Unset"; - analogOutHandle = - HAL_InitializeAnalogOutputPort(portHandle, nullptr, &status); - EXPECT_EQ(HAL_kInvalidHandle, analogOutHandle); - EXPECT_EQ(HAL_USE_LAST_ERROR, status); - HAL_GetLastError(&status); - EXPECT_EQ(RESOURCE_IS_ALLOCATED, status); - EXPECT_STREQ("Unset", gTestAnalogOutCallbackName.c_str()); - - // Reset, should allow you to re-register - hal::HandleBase::ResetGlobalHandles(); - HALSIM_ResetAnalogOutData(INDEX_TO_TEST); - callbackId = HALSIM_RegisterAnalogOutInitializedCallback( - INDEX_TO_TEST, &TestAnalogOutInitializationCallback, &callbackParam, - false); - - status = 0; - portHandle = HAL_GetPort(INDEX_TO_TEST); - gTestAnalogOutCallbackName = "Unset"; - analogOutHandle = - HAL_InitializeAnalogOutputPort(portHandle, nullptr, &status); - EXPECT_TRUE(HAL_kInvalidHandle != analogOutHandle); - EXPECT_EQ(0, status); - EXPECT_STREQ("Initialized", gTestAnalogOutCallbackName.c_str()); - HALSIM_CancelAnalogOutInitializedCallback(INDEX_TO_TEST, callbackId); -} -} // namespace hal diff --git a/simulation/halsim_gui/src/main/native/cpp/AnalogOutputSimGui.cpp b/simulation/halsim_gui/src/main/native/cpp/AnalogOutputSimGui.cpp deleted file mode 100644 index 0f84cc1bd8..0000000000 --- a/simulation/halsim_gui/src/main/native/cpp/AnalogOutputSimGui.cpp +++ /dev/null @@ -1,92 +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 "AnalogOutputSimGui.h" - -#include -#include - -#include -#include -#include -#include - -#include "HALDataSource.h" -#include "HALSimGui.h" -#include "SimDeviceGui.h" - -using namespace halsimgui; - -namespace { -HALSIMGUI_DATASOURCE_DOUBLE_INDEXED(AnalogOutVoltage, "AOut"); - -class AnalogOutputSimModel : public glass::AnalogOutputModel { - public: - explicit AnalogOutputSimModel(int32_t index) - : m_index{index}, m_voltageData{m_index} {} - - void Update() override {} - - bool Exists() override { return HALSIM_GetAnalogOutInitialized(m_index); } - - glass::DoubleSource* GetVoltageData() override { return &m_voltageData; } - - void SetVoltage(double val) override { - HALSIM_SetAnalogOutVoltage(m_index, val); - } - - private: - int32_t m_index; - AnalogOutVoltageSource m_voltageData; -}; - -class AnalogOutputsSimModel : public glass::AnalogOutputsModel { - public: - AnalogOutputsSimModel() : m_models(HAL_GetNumAnalogOutputs()) {} - - void Update() override; - - bool Exists() override { return true; } - - void ForEachAnalogOutput( - wpi::function_ref func) - override; - - private: - // indexed by channel - std::vector> m_models; -}; -} // namespace - -void AnalogOutputsSimModel::Update() { - for (int32_t i = 0, iend = static_cast(m_models.size()); i < iend; - ++i) { - auto& model = m_models[i]; - if (HALSIM_GetAnalogOutInitialized(i)) { - if (!model) { - model = std::make_unique(i); - } - } else { - model.reset(); - } - } -} - -void AnalogOutputsSimModel::ForEachAnalogOutput( - wpi::function_ref func) { - for (int32_t i = 0, iend = static_cast(m_models.size()); i < iend; - ++i) { - if (auto model = m_models[i].get()) { - func(*model, i); - } - } -} - -void AnalogOutputSimGui::Initialize() { - SimDeviceGui::GetDeviceTree().Add( - std::make_unique(), [](glass::Model* model) { - glass::DisplayAnalogOutputsDevice( - static_cast(model)); - }); -} diff --git a/simulation/halsim_gui/src/main/native/cpp/AnalogOutputSimGui.h b/simulation/halsim_gui/src/main/native/cpp/AnalogOutputSimGui.h deleted file mode 100644 index f7a816b707..0000000000 --- a/simulation/halsim_gui/src/main/native/cpp/AnalogOutputSimGui.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 AnalogOutputSimGui { - 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 601f1b0120..de844b5c63 100644 --- a/simulation/halsim_gui/src/main/native/cpp/main.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/main.cpp @@ -19,7 +19,6 @@ #include "AddressableLEDGui.h" #include "AnalogGyroSimGui.h" #include "AnalogInputSimGui.h" -#include "AnalogOutputSimGui.h" #include "DIOSimGui.h" #include "DriverStationGui.h" #include "EncoderSimGui.h" @@ -79,7 +78,6 @@ __declspec(dllexport) AddressableLEDGui::Initialize(); AnalogGyroSimGui::Initialize(); AnalogInputSimGui::Initialize(); - AnalogOutputSimGui::Initialize(); DIOSimGui::Initialize(); NetworkTablesSimGui::Initialize(); PCMSimGui::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 d4f2abd6dd..00f51b8327 100644 --- a/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClient.cpp +++ b/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClient.cpp @@ -40,7 +40,6 @@ bool HALSimWSClient::Initialize() { HALSimWSProviderAddressableLED::Initialize(registerFunc); HALSimWSProviderAnalogIn::Initialize(registerFunc); - HALSimWSProviderAnalogOut::Initialize(registerFunc); HALSimWSProviderBuiltInAccelerometer::Initialize(registerFunc); HALSimWSProviderDIO::Initialize(registerFunc); HALSimWSProviderDigitalPWM::Initialize(registerFunc); diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Analog.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Analog.cpp index be19a1dfc7..575d1b9f21 100644 --- a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Analog.cpp +++ b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Analog.cpp @@ -6,7 +6,6 @@ #include #include -#include #define REGISTER_AIN(halsim, jsonid, ctype, haltype) \ HALSIM_RegisterAnalogIn##halsim##Callback( \ @@ -26,15 +25,6 @@ }, \ this, true) -#define REGISTER_AOUT(halsim, jsonid, ctype, haltype) \ - HALSIM_RegisterAnalogOut##halsim##Callback( \ - m_channel, \ - [](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 { void HALSimWSProviderAnalogIn::Initialize(WSRegisterFunc webRegisterFunc) { @@ -108,26 +98,4 @@ void HALSimWSProviderAnalogIn::OnNetValueChanged(const wpi::json& json) { } } -void HALSimWSProviderAnalogOut::Initialize(WSRegisterFunc webRegisterFunc) { - CreateProviders("AO", HAL_GetNumAnalogOutputs(), - webRegisterFunc); -} - -HALSimWSProviderAnalogOut::~HALSimWSProviderAnalogOut() { - CancelCallbacks(); -} - -void HALSimWSProviderAnalogOut::RegisterCallbacks() { - m_initCbKey = REGISTER_AOUT(Initialized, " - -#include -#include -#include -#include -#include -#include -#include - -#include "frc/Errors.h" -#include "frc/SensorUtil.h" - -using namespace frc; - -AnalogOutput::AnalogOutput(int channel) { - if (!SensorUtil::CheckAnalogOutputChannel(channel)) { - throw FRC_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel); - } - - m_channel = channel; - - HAL_PortHandle port = HAL_GetPort(m_channel); - int32_t status = 0; - std::string stackTrace = wpi::GetStackTrace(1); - m_port = HAL_InitializeAnalogOutputPort(port, stackTrace.c_str(), &status); - FRC_CheckErrorStatus(status, "Channel {}", channel); - - HAL_Report(HALUsageReporting::kResourceType_AnalogOutput, m_channel + 1); - wpi::SendableRegistry::AddLW(this, "AnalogOutput", m_channel); -} - -void AnalogOutput::SetVoltage(double voltage) { - int32_t status = 0; - HAL_SetAnalogOutput(m_port, voltage, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); -} - -double AnalogOutput::GetVoltage() const { - int32_t status = 0; - double voltage = HAL_GetAnalogOutput(m_port, &status); - FRC_CheckErrorStatus(status, "Channel {}", m_channel); - return voltage; -} - -int AnalogOutput::GetChannel() const { - return m_channel; -} - -void AnalogOutput::InitSendable(wpi::SendableBuilder& builder) { - builder.SetSmartDashboardType("Analog Output"); - builder.AddDoubleProperty( - "Value", [=, this] { return GetVoltage(); }, - [=, this](double value) { SetVoltage(value); }); -} diff --git a/wpilibc/src/main/native/cpp/SensorUtil.cpp b/wpilibc/src/main/native/cpp/SensorUtil.cpp index 42062b4abf..f17c5f7e9b 100644 --- a/wpilibc/src/main/native/cpp/SensorUtil.cpp +++ b/wpilibc/src/main/native/cpp/SensorUtil.cpp @@ -5,7 +5,6 @@ #include "frc/SensorUtil.h" #include -#include #include #include #include @@ -32,10 +31,6 @@ bool SensorUtil::CheckAnalogInputChannel(int channel) { return HAL_CheckAnalogInputChannel(channel); } -bool SensorUtil::CheckAnalogOutputChannel(int channel) { - return HAL_CheckAnalogOutputChannel(channel); -} - int SensorUtil::GetNumDigitalChannels() { return HAL_GetNumDigitalChannels(); } @@ -44,10 +39,6 @@ int SensorUtil::GetNumAnalogInputs() { return HAL_GetNumAnalogInputs(); } -int SensorUtil::GetNumAnalogOuputs() { - return HAL_GetNumAnalogOutputs(); -} - int SensorUtil::GetNumPwmChannels() { return HAL_GetNumPWMChannels(); } diff --git a/wpilibc/src/main/native/cpp/simulation/AnalogOutputSim.cpp b/wpilibc/src/main/native/cpp/simulation/AnalogOutputSim.cpp deleted file mode 100644 index 02692ca37b..0000000000 --- a/wpilibc/src/main/native/cpp/simulation/AnalogOutputSim.cpp +++ /dev/null @@ -1,57 +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/AnalogOutputSim.h" - -#include - -#include - -#include "frc/AnalogOutput.h" - -using namespace frc; -using namespace frc::sim; - -AnalogOutputSim::AnalogOutputSim(const AnalogOutput& analogOutput) - : m_index{analogOutput.GetChannel()} {} - -AnalogOutputSim::AnalogOutputSim(int channel) : m_index{channel} {} - -std::unique_ptr AnalogOutputSim::RegisterVoltageCallback( - NotifyCallback callback, bool initialNotify) { - auto store = std::make_unique( - m_index, -1, callback, &HALSIM_CancelAnalogOutVoltageCallback); - store->SetUid(HALSIM_RegisterAnalogOutVoltageCallback( - m_index, &CallbackStoreThunk, store.get(), initialNotify)); - return store; -} - -double AnalogOutputSim::GetVoltage() const { - return HALSIM_GetAnalogOutVoltage(m_index); -} - -void AnalogOutputSim::SetVoltage(double voltage) { - HALSIM_SetAnalogOutVoltage(m_index, voltage); -} - -std::unique_ptr AnalogOutputSim::RegisterInitializedCallback( - NotifyCallback callback, bool initialNotify) { - auto store = std::make_unique( - m_index, -1, callback, &HALSIM_CancelAnalogOutInitializedCallback); - store->SetUid(HALSIM_RegisterAnalogOutInitializedCallback( - m_index, &CallbackStoreThunk, store.get(), initialNotify)); - return store; -} - -bool AnalogOutputSim::GetInitialized() const { - return HALSIM_GetAnalogOutInitialized(m_index); -} - -void AnalogOutputSim::SetInitialized(bool initialized) { - HALSIM_SetAnalogOutInitialized(m_index, initialized); -} - -void AnalogOutputSim::ResetData() { - HALSIM_ResetAnalogOutData(m_index); -} diff --git a/wpilibc/src/main/native/include/frc/AnalogOutput.h b/wpilibc/src/main/native/include/frc/AnalogOutput.h deleted file mode 100644 index e5c1c59473..0000000000 --- a/wpilibc/src/main/native/include/frc/AnalogOutput.h +++ /dev/null @@ -1,60 +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 -#include - -namespace frc { - -/** - * MXP analog output class. - */ -class AnalogOutput : public wpi::Sendable, - public wpi::SendableHelper { - public: - /** - * Construct an analog output on the given channel. - * - * All analog outputs are located on the MXP port. - * - * @param channel The channel number on the roboRIO to represent. - */ - explicit AnalogOutput(int channel); - - AnalogOutput(AnalogOutput&&) = default; - AnalogOutput& operator=(AnalogOutput&&) = default; - - ~AnalogOutput() override = default; - - /** - * Set the value of the analog output. - * - * @param voltage The output value in Volts, from 0.0 to +5.0. - */ - void SetVoltage(double voltage); - - /** - * Get the voltage of the analog output. - * - * @return The value in Volts, from 0.0 to +5.0. - */ - double GetVoltage() const; - - /** - * Get the channel of this AnalogOutput. - */ - int GetChannel() const; - - void InitSendable(wpi::SendableBuilder& builder) override; - - protected: - int m_channel; - hal::Handle m_port; -}; - -} // namespace frc diff --git a/wpilibc/src/main/native/include/frc/SensorUtil.h b/wpilibc/src/main/native/include/frc/SensorUtil.h index e94a5ef053..bae794a4a4 100644 --- a/wpilibc/src/main/native/include/frc/SensorUtil.h +++ b/wpilibc/src/main/native/include/frc/SensorUtil.h @@ -58,19 +58,8 @@ class SensorUtil final { */ static bool CheckAnalogInputChannel(int channel); - /** - * Check that the analog output number is valid. - * - * Verify that the analog output number is one of the legal channel numbers. - * Channel numbers are 0-based. - * - * @return Analog channel is valid - */ - static bool CheckAnalogOutputChannel(int channel); - static int GetNumDigitalChannels(); static int GetNumAnalogInputs(); - static int GetNumAnalogOuputs(); static int GetNumPwmChannels(); }; diff --git a/wpilibc/src/main/native/include/frc/simulation/AnalogOutputSim.h b/wpilibc/src/main/native/include/frc/simulation/AnalogOutputSim.h deleted file mode 100644 index 42eb6c14b8..0000000000 --- a/wpilibc/src/main/native/include/frc/simulation/AnalogOutputSim.h +++ /dev/null @@ -1,95 +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 "frc/simulation/CallbackStore.h" - -namespace frc { - -class AnalogOutput; - -namespace sim { - -/** - * Class to control a simulated analog output. - */ -class AnalogOutputSim { - public: - /** - * Constructs from an AnalogOutput object. - * - * @param analogOutput AnalogOutput to simulate - */ - explicit AnalogOutputSim(const AnalogOutput& analogOutput); - - /** - * Constructs from an analog output channel number. - * - * @param channel Channel number - */ - explicit AnalogOutputSim(int channel); - - /** - * Register a callback to be run whenever the voltage 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 RegisterVoltageCallback( - NotifyCallback callback, bool initialNotify); - - /** - * Read the analog output voltage. - * - * @return the voltage on this analog output - */ - double GetVoltage() const; - - /** - * Set the analog output voltage. - * - * @param voltage the new voltage on this analog output - */ - void SetVoltage(double voltage); - - /** - * Register a callback to be run when this analog output is initialized. - * - * @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 RegisterInitializedCallback( - NotifyCallback callback, bool initialNotify); - - /** - * Check whether this analog output has been initialized. - * - * @return true if initialized - */ - bool GetInitialized() const; - - /** - * Define whether this analog output has been initialized. - * - * @param initialized whether this object is initialized - */ - void SetInitialized(bool initialized); - - /** - * Reset all simulation data on this object. - */ - void ResetData(); - - private: - int m_index; -}; -} // namespace sim -} // namespace frc diff --git a/wpilibc/src/test/native/cpp/simulation/AnalogOutputSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/AnalogOutputSimTest.cpp deleted file mode 100644 index bbe2b8117e..0000000000 --- a/wpilibc/src/test/native/cpp/simulation/AnalogOutputSimTest.cpp +++ /dev/null @@ -1,89 +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/AnalogOutputSim.h" // NOLINT(build/include_order) - -#include -#include - -#include "callback_helpers/TestCallbackHelpers.h" -#include "frc/AnalogOutput.h" - -namespace frc::sim { - -TEST(AnalogOutputSimTest, Initialize) { - HAL_Initialize(500, 0); - - AnalogOutputSim outputSim{0}; - EXPECT_FALSE(outputSim.GetInitialized()); - - BooleanCallback callback; - - auto cb = - outputSim.RegisterInitializedCallback(callback.GetCallback(), false); - AnalogOutput output(0); - EXPECT_TRUE(outputSim.GetInitialized()); - - EXPECT_TRUE(callback.WasTriggered()); - EXPECT_TRUE(callback.GetLastValue()); -} - -TEST(AnalogOutputSimTest, SetCallback) { - HAL_Initialize(500, 0); - - AnalogOutput output{0}; - output.SetVoltage(0.5); - - AnalogOutputSim outputSim(output); - - DoubleCallback voltageCallback; - - auto cb = - outputSim.RegisterVoltageCallback(voltageCallback.GetCallback(), false); - - EXPECT_FALSE(voltageCallback.WasTriggered()); - - for (int i = 0; i < 50; ++i) { - double voltage = i * .1; - voltageCallback.Reset(); - - output.SetVoltage(0); - - EXPECT_EQ(0, output.GetVoltage()); - EXPECT_EQ(0, outputSim.GetVoltage()); - - // 0 -> 0 isn't a change, so callback not called - if (i > 2) { - EXPECT_TRUE(voltageCallback.WasTriggered()) << " on " << i; - EXPECT_NEAR(voltageCallback.GetLastValue(), 0, 0.001) << " on " << i; - } - - voltageCallback.Reset(); - - output.SetVoltage(voltage); - - EXPECT_EQ(voltage, output.GetVoltage()); - EXPECT_EQ(voltage, outputSim.GetVoltage()); - - // 0 -> 0 isn't a change, so callback not called - if (i != 0) { - EXPECT_TRUE(voltageCallback.WasTriggered()); - EXPECT_NEAR(voltageCallback.GetLastValue(), voltage, 0.001); - } - } -} - -TEST(AnalogOutputSimTest, Reset) { - HAL_Initialize(500, 0); - - AnalogOutputSim outputSim{0}; - - AnalogOutput output{0}; - output.SetVoltage(1.2); - - outputSim.ResetData(); - EXPECT_EQ(0, output.GetVoltage()); - EXPECT_EQ(0, outputSim.GetVoltage()); -} -} // namespace frc::sim diff --git a/wpilibc/src/test/native/cpp/simulation/SimInitializationTest.cpp b/wpilibc/src/test/native/cpp/simulation/SimInitializationTest.cpp index a1180002b3..ff801c8381 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/AnalogGyroSim.h" #include "frc/simulation/AnalogInputSim.h" -#include "frc/simulation/AnalogOutputSim.h" #include "frc/simulation/AnalogTriggerSim.h" #include "frc/simulation/BuiltInAccelerometerSim.h" #include "frc/simulation/CTREPCMSim.h" @@ -31,7 +30,6 @@ TEST(SimInitializationTest, AllInitialize) { BuiltInAccelerometerSim biacsim; AnalogGyroSim agsim{0}; AnalogInputSim aisim{0}; - AnalogOutputSim aosim{0}; EXPECT_THROW(AnalogTriggerSim::CreateForChannel(0), std::out_of_range); EXPECT_THROW(DigitalPWMSim::CreateForChannel(0), std::out_of_range); DIOSim diosim{0}; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java deleted file mode 100644 index 354cedc038..0000000000 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java +++ /dev/null @@ -1,76 +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.AnalogJNI; -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; - -/** Analog output class. */ -public class AnalogOutput implements Sendable, AutoCloseable { - private int m_port; - private int m_channel; - - /** - * Construct an analog output on a specified MXP channel. - * - * @param channel The channel number to represent. - */ - @SuppressWarnings("this-escape") - public AnalogOutput(final int channel) { - SensorUtil.checkAnalogOutputChannel(channel); - m_channel = channel; - - final int portHandle = HAL.getPort((byte) channel); - m_port = AnalogJNI.initializeAnalogOutputPort(portHandle); - - HAL.report(tResourceType.kResourceType_AnalogOutput, channel + 1); - SendableRegistry.addLW(this, "AnalogOutput", channel); - } - - @Override - public void close() { - SendableRegistry.remove(this); - AnalogJNI.freeAnalogOutputPort(m_port); - m_port = 0; - m_channel = 0; - } - - /** - * Get the channel of this AnalogOutput. - * - * @return The channel of this AnalogOutput. - */ - public int getChannel() { - return m_channel; - } - - /** - * Set the value of the analog output. - * - * @param voltage The output value in Volts, from 0.0 to +5.0. - */ - public void setVoltage(double voltage) { - AnalogJNI.setAnalogOutput(m_port, voltage); - } - - /** - * Get the voltage of the analog output. - * - * @return The value in Volts, from 0.0 to +5.0. - */ - public double getVoltage() { - return AnalogJNI.getAnalogOutput(m_port); - } - - @Override - public void initSendable(SendableBuilder builder) { - builder.setSmartDashboardType("Analog Output"); - builder.addDoubleProperty("Value", this::getVoltage, this::setVoltage); - } -} diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java index 832fcc3504..0e6086306e 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java @@ -25,9 +25,6 @@ public final class SensorUtil { /** Number of analog input channels per roboRIO. */ public static final int kAnalogInputChannels = PortsJNI.getNumAnalogInputs(); - /** Number of analog output channels per roboRIO. */ - public static final int kAnalogOutputChannels = PortsJNI.getNumAnalogOutputs(); - /** Number of solenoid channels per module. */ public static final int kCTRESolenoidChannels = PortsJNI.getNumCTRESolenoidChannels(); @@ -100,23 +97,6 @@ public final class SensorUtil { } } - /** - * Check that the analog input number is value. Verify that the analog input number is one of the - * legal channel numbers. Channel numbers are 0-based. - * - * @param channel The channel number to check. - */ - public static void checkAnalogOutputChannel(final int channel) { - if (!AnalogJNI.checkAnalogOutputChannel(channel)) { - String buf = - "Requested analog output channel is out of range. Minimum: 0, Maximum: " - + kAnalogOutputChannels - + ", Requested: " - + channel; - throw new IllegalArgumentException(buf); - } - } - /** * Get the number of the default solenoid module. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogOutputSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogOutputSim.java deleted file mode 100644 index 5623c8eeb0..0000000000 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogOutputSim.java +++ /dev/null @@ -1,97 +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.AnalogOutDataJNI; -import edu.wpi.first.hal.simulation.NotifyCallback; -import edu.wpi.first.wpilibj.AnalogOutput; - -/** Class to control a simulated analog output. */ -public class AnalogOutputSim { - private final int m_index; - - /** - * Constructs from an AnalogOutput object. - * - * @param analogOutput AnalogOutput to simulate - */ - public AnalogOutputSim(AnalogOutput analogOutput) { - m_index = analogOutput.getChannel(); - } - - /** - * Constructs from an analog output channel number. - * - * @param channel Channel number - */ - public AnalogOutputSim(int channel) { - m_index = channel; - } - - /** - * Register a callback to be run whenever the voltage 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 registerVoltageCallback(NotifyCallback callback, boolean initialNotify) { - int uid = AnalogOutDataJNI.registerVoltageCallback(m_index, callback, initialNotify); - return new CallbackStore(m_index, uid, AnalogOutDataJNI::cancelVoltageCallback); - } - - /** - * Read the analog output voltage. - * - * @return the voltage on this analog output - */ - public double getVoltage() { - return AnalogOutDataJNI.getVoltage(m_index); - } - - /** - * Set the analog output voltage. - * - * @param voltage the new voltage on this analog output - */ - public void setVoltage(double voltage) { - AnalogOutDataJNI.setVoltage(m_index, voltage); - } - - /** - * Register a callback to be run when this analog output is initialized. - * - * @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 registerInitializedCallback(NotifyCallback callback, boolean initialNotify) { - int uid = AnalogOutDataJNI.registerInitializedCallback(m_index, callback, initialNotify); - return new CallbackStore(m_index, uid, AnalogOutDataJNI::cancelInitializedCallback); - } - - /** - * Check whether this analog output has been initialized. - * - * @return true if initialized - */ - public boolean getInitialized() { - return AnalogOutDataJNI.getInitialized(m_index); - } - - /** - * Define whether this analog output has been initialized. - * - * @param initialized whether this object is initialized - */ - public void setInitialized(boolean initialized) { - AnalogOutDataJNI.setInitialized(m_index, initialized); - } - - /** Reset all simulation data on this object. */ - public void resetData() { - AnalogOutDataJNI.resetData(m_index); - } -} diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/SensorUtilTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/SensorUtilTest.java index 5c1fcddce3..531a52185d 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/SensorUtilTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/SensorUtilTest.java @@ -15,11 +15,6 @@ class SensorUtilTest { assertThrows(IllegalArgumentException.class, () -> SensorUtil.checkAnalogInputChannel(100)); } - @Test - void checkAnalogOutputChannel() { - assertThrows(IllegalArgumentException.class, () -> SensorUtil.checkAnalogOutputChannel(100)); - } - @Test void testInvalidDigitalChannel() { assertThrows(IllegalArgumentException.class, () -> SensorUtil.checkDigitalChannel(100)); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AnalogOutputSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AnalogOutputSimTest.java deleted file mode 100644 index 85a7494717..0000000000 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AnalogOutputSimTest.java +++ /dev/null @@ -1,84 +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.AnalogOutput; -import edu.wpi.first.wpilibj.simulation.testutils.BooleanCallback; -import edu.wpi.first.wpilibj.simulation.testutils.DoubleCallback; -import org.junit.jupiter.api.Test; - -class AnalogOutputSimTest { - @Test - void testInitialization() { - HAL.initialize(500, 0); - - AnalogOutputSim outputSim = new AnalogOutputSim(0); - assertFalse(outputSim.getInitialized()); - - BooleanCallback callback = new BooleanCallback(); - - try (CallbackStore cb = outputSim.registerInitializedCallback(callback, false); - AnalogOutput output = new AnalogOutput(0)) { - assertTrue(outputSim.getInitialized()); - } - } - - @Test - void setCallbackTest() { - HAL.initialize(500, 0); - - try (AnalogOutput output = new AnalogOutput(0)) { - output.setVoltage(0.5); - - AnalogOutputSim outputSim = new AnalogOutputSim(output); - - DoubleCallback voltageCallback = new DoubleCallback(); - - try (CallbackStore cb = outputSim.registerVoltageCallback(voltageCallback, false)) { - assertFalse(voltageCallback.wasTriggered()); - - for (double i = 0.1; i < 5.0; i += 0.1) { - voltageCallback.reset(); - - output.setVoltage(0); - - assertEquals(0, output.getVoltage()); - assertEquals(0, outputSim.getVoltage()); - assertTrue(voltageCallback.wasTriggered()); - assertEquals(voltageCallback.getSetValue(), 0, 0.001); - - voltageCallback.reset(); - - output.setVoltage(i); - - assertEquals(i, output.getVoltage()); - assertEquals(i, outputSim.getVoltage()); - assertTrue(voltageCallback.wasTriggered()); - assertEquals(voltageCallback.getSetValue(), i, 0.001); - } - } - } - } - - @Test - void testReset() { - HAL.initialize(500, 0); - - AnalogOutputSim outputSim = new AnalogOutputSim(0); - - try (AnalogOutput output = new AnalogOutput(0)) { - output.setVoltage(1.2); - - outputSim.resetData(); - assertEquals(0, output.getVoltage()); - assertEquals(0, outputSim.getVoltage()); - } - } -}