diff --git a/hal/src/main/java/edu/wpi/first/hal/simulation/AddressableLEDDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/simulation/AddressableLEDDataJNI.java index 2f6f8f594a..0aa4d47ee7 100644 --- a/hal/src/main/java/edu/wpi/first/hal/simulation/AddressableLEDDataJNI.java +++ b/hal/src/main/java/edu/wpi/first/hal/simulation/AddressableLEDDataJNI.java @@ -36,4 +36,6 @@ public class AddressableLEDDataJNI extends JNIWrapper { public static native void setData(int index, byte[] data); public static native void resetData(int index); + + public static native int findForChannel(int channel); } diff --git a/hal/src/main/java/edu/wpi/first/hal/simulation/AnalogTriggerDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/simulation/AnalogTriggerDataJNI.java index a8c12495e2..ca89a28de7 100644 --- a/hal/src/main/java/edu/wpi/first/hal/simulation/AnalogTriggerDataJNI.java +++ b/hal/src/main/java/edu/wpi/first/hal/simulation/AnalogTriggerDataJNI.java @@ -26,4 +26,6 @@ public class AnalogTriggerDataJNI extends JNIWrapper { public static native void setTriggerUpperBound(int index, double triggerUpperBound); public static native void resetData(int index); + + public static native int findForChannel(int channel); } diff --git a/hal/src/main/java/edu/wpi/first/hal/simulation/DigitalPWMDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/simulation/DigitalPWMDataJNI.java index 1520ece51e..4e2709fd9d 100644 --- a/hal/src/main/java/edu/wpi/first/hal/simulation/DigitalPWMDataJNI.java +++ b/hal/src/main/java/edu/wpi/first/hal/simulation/DigitalPWMDataJNI.java @@ -26,4 +26,6 @@ public class DigitalPWMDataJNI extends JNIWrapper { public static native void setPin(int index, int pin); public static native void resetData(int index); + + public static native int findForChannel(int channel); } diff --git a/hal/src/main/java/edu/wpi/first/hal/simulation/DutyCycleDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/simulation/DutyCycleDataJNI.java index dccec92505..3228341a57 100644 --- a/hal/src/main/java/edu/wpi/first/hal/simulation/DutyCycleDataJNI.java +++ b/hal/src/main/java/edu/wpi/first/hal/simulation/DutyCycleDataJNI.java @@ -26,4 +26,6 @@ public class DutyCycleDataJNI extends JNIWrapper { public static native void setOutput(int index, double output); public static native void resetData(int index); + + public static native int findForChannel(int channel); } diff --git a/hal/src/main/java/edu/wpi/first/hal/simulation/EncoderDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/simulation/EncoderDataJNI.java index 6df88b8fb5..db78d3ce76 100644 --- a/hal/src/main/java/edu/wpi/first/hal/simulation/EncoderDataJNI.java +++ b/hal/src/main/java/edu/wpi/first/hal/simulation/EncoderDataJNI.java @@ -56,4 +56,6 @@ public class EncoderDataJNI extends JNIWrapper { public static native double getRate(int index); public static native void resetData(int index); + + public static native int findForChannel(int channel); } diff --git a/hal/src/main/native/include/hal/simulation/AddressableLEDData.h b/hal/src/main/native/include/hal/simulation/AddressableLEDData.h index 197dbbf442..91ab30c494 100644 --- a/hal/src/main/native/include/hal/simulation/AddressableLEDData.h +++ b/hal/src/main/native/include/hal/simulation/AddressableLEDData.h @@ -15,6 +15,8 @@ extern "C" { #endif +int32_t HALSIM_FindAddressableLEDForChannel(int32_t channel); + void HALSIM_ResetAddressableLEDData(int32_t index); int32_t HALSIM_RegisterAddressableLEDInitializedCallback( diff --git a/hal/src/main/native/include/hal/simulation/AnalogTriggerData.h b/hal/src/main/native/include/hal/simulation/AnalogTriggerData.h index 9ba3ad4554..74c762c080 100644 --- a/hal/src/main/native/include/hal/simulation/AnalogTriggerData.h +++ b/hal/src/main/native/include/hal/simulation/AnalogTriggerData.h @@ -21,6 +21,8 @@ enum HALSIM_AnalogTriggerMode : int32_t { extern "C" { #endif +int32_t HALSIM_FindAnalogTriggerForChannel(int32_t channel); + void HALSIM_ResetAnalogTriggerData(int32_t index); int32_t HALSIM_RegisterAnalogTriggerInitializedCallback( int32_t index, HAL_NotifyCallback callback, void* param, diff --git a/hal/src/main/native/include/hal/simulation/DigitalPWMData.h b/hal/src/main/native/include/hal/simulation/DigitalPWMData.h index 355565afe9..79428b0104 100644 --- a/hal/src/main/native/include/hal/simulation/DigitalPWMData.h +++ b/hal/src/main/native/include/hal/simulation/DigitalPWMData.h @@ -14,6 +14,8 @@ extern "C" { #endif +int32_t HALSIM_FindDigitalPWMForChannel(int32_t channel); + void HALSIM_ResetDigitalPWMData(int32_t index); int32_t HALSIM_RegisterDigitalPWMInitializedCallback( int32_t index, HAL_NotifyCallback callback, void* param, diff --git a/hal/src/main/native/include/hal/simulation/DutyCycleData.h b/hal/src/main/native/include/hal/simulation/DutyCycleData.h index 1aae35fd04..7b191f28b5 100644 --- a/hal/src/main/native/include/hal/simulation/DutyCycleData.h +++ b/hal/src/main/native/include/hal/simulation/DutyCycleData.h @@ -14,6 +14,8 @@ extern "C" { #endif +int32_t HALSIM_FindDutyCycleForChannel(int32_t channel); + void HALSIM_ResetDutyCycleData(int32_t index); int32_t HALSIM_GetDutyCycleDigitalChannel(int32_t index); diff --git a/hal/src/main/native/include/hal/simulation/EncoderData.h b/hal/src/main/native/include/hal/simulation/EncoderData.h index ca5becef92..80c142dc66 100644 --- a/hal/src/main/native/include/hal/simulation/EncoderData.h +++ b/hal/src/main/native/include/hal/simulation/EncoderData.h @@ -14,6 +14,8 @@ extern "C" { #endif +int32_t HALSIM_FindEncoderForChannel(int32_t channel); + void HALSIM_ResetEncoderData(int32_t index); int32_t HALSIM_GetEncoderDigitalChannelA(int32_t index); int32_t HALSIM_GetEncoderDigitalChannelB(int32_t index); diff --git a/hal/src/main/native/sim/AnalogTrigger.cpp b/hal/src/main/native/sim/AnalogTrigger.cpp index 3ddacee7b7..62bfebc99e 100644 --- a/hal/src/main/native/sim/AnalogTrigger.cpp +++ b/hal/src/main/native/sim/AnalogTrigger.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */ +/* Copyright (c) 2017-2020 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -85,6 +85,7 @@ HAL_AnalogTriggerHandle HAL_InitializeAnalogTrigger( trigger->index = static_cast(getHandleIndex(handle)); SimAnalogTriggerData[trigger->index].initialized = true; + SimAnalogTriggerData[trigger->index].inputPort = analog_port->channel; trigger->trigState = false; diff --git a/hal/src/main/native/sim/jni/AddressableLEDDataJNI.cpp b/hal/src/main/native/sim/jni/AddressableLEDDataJNI.cpp index edab6dd28d..8ac59ec3ef 100644 --- a/hal/src/main/native/sim/jni/AddressableLEDDataJNI.cpp +++ b/hal/src/main/native/sim/jni/AddressableLEDDataJNI.cpp @@ -291,4 +291,16 @@ Java_edu_wpi_first_hal_simulation_AddressableLEDDataJNI_resetData HALSIM_ResetAddressableLEDData(index); } +/* + * Class: edu_wpi_first_hal_simulation_AddressableLEDDataJNI + * Method: findForChannel + * Signature: (I)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_simulation_AddressableLEDDataJNI_findForChannel + (JNIEnv*, jclass, jint channel) +{ + return HALSIM_FindAddressableLEDForChannel(channel); +} + } // extern "C" diff --git a/hal/src/main/native/sim/jni/AnalogTriggerDataJNI.cpp b/hal/src/main/native/sim/jni/AnalogTriggerDataJNI.cpp index c096e52869..be92c6d9db 100644 --- a/hal/src/main/native/sim/jni/AnalogTriggerDataJNI.cpp +++ b/hal/src/main/native/sim/jni/AnalogTriggerDataJNI.cpp @@ -180,4 +180,16 @@ Java_edu_wpi_first_hal_simulation_AnalogTriggerDataJNI_resetData HALSIM_ResetAnalogTriggerData(index); } +/* + * Class: edu_wpi_first_hal_simulation_AnalogTriggerDataJNI + * Method: findForChannel + * Signature: (I)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_simulation_AnalogTriggerDataJNI_findForChannel + (JNIEnv*, jclass, jint channel) +{ + return HALSIM_FindAnalogTriggerForChannel(channel); +} + } // extern "C" diff --git a/hal/src/main/native/sim/jni/DigitalPWMDataJNI.cpp b/hal/src/main/native/sim/jni/DigitalPWMDataJNI.cpp index d4b1ed51a5..ea6bee286a 100644 --- a/hal/src/main/native/sim/jni/DigitalPWMDataJNI.cpp +++ b/hal/src/main/native/sim/jni/DigitalPWMDataJNI.cpp @@ -177,4 +177,16 @@ Java_edu_wpi_first_hal_simulation_DigitalPWMDataJNI_resetData HALSIM_ResetDigitalPWMData(index); } +/* + * Class: edu_wpi_first_hal_simulation_DigitalPWMDataJNI + * Method: findForChannel + * Signature: (I)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_simulation_DigitalPWMDataJNI_findForChannel + (JNIEnv*, jclass, jint channel) +{ + return HALSIM_FindDigitalPWMForChannel(channel); +} + } // extern "C" diff --git a/hal/src/main/native/sim/jni/DutyCycleDataJNI.cpp b/hal/src/main/native/sim/jni/DutyCycleDataJNI.cpp index e230a10fc2..054fa672cf 100644 --- a/hal/src/main/native/sim/jni/DutyCycleDataJNI.cpp +++ b/hal/src/main/native/sim/jni/DutyCycleDataJNI.cpp @@ -177,4 +177,16 @@ Java_edu_wpi_first_hal_simulation_DutyCycleDataJNI_resetData HALSIM_ResetDutyCycleData(index); } +/* + * Class: edu_wpi_first_hal_simulation_DutyCycleDataJNI + * Method: findForChannel + * Signature: (I)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_simulation_DutyCycleDataJNI_findForChannel + (JNIEnv*, jclass, jint channel) +{ + return HALSIM_FindDutyCycleForChannel(channel); +} + } // extern "C" diff --git a/hal/src/main/native/sim/jni/EncoderDataJNI.cpp b/hal/src/main/native/sim/jni/EncoderDataJNI.cpp index 88b94e90af..b97e0fe2f7 100644 --- a/hal/src/main/native/sim/jni/EncoderDataJNI.cpp +++ b/hal/src/main/native/sim/jni/EncoderDataJNI.cpp @@ -475,4 +475,16 @@ Java_edu_wpi_first_hal_simulation_EncoderDataJNI_resetData HALSIM_ResetEncoderData(index); } +/* + * Class: edu_wpi_first_hal_simulation_EncoderDataJNI + * Method: findForChannel + * Signature: (I)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_simulation_EncoderDataJNI_findForChannel + (JNIEnv*, jclass, jint channel) +{ + return HALSIM_FindEncoderForChannel(channel); +} + } // extern "C" diff --git a/hal/src/main/native/sim/mockdata/AddressableLEDData.cpp b/hal/src/main/native/sim/mockdata/AddressableLEDData.cpp index 5b44eaf53b..fe4611e6f4 100644 --- a/hal/src/main/native/sim/mockdata/AddressableLEDData.cpp +++ b/hal/src/main/native/sim/mockdata/AddressableLEDData.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -49,6 +49,16 @@ int32_t AddressableLEDData::GetData(HAL_AddressableLEDData* d) { } extern "C" { + +int32_t HALSIM_FindAddressableLEDForChannel(int32_t channel) { + for (int i = 0; i < kNumAddressableLEDs; ++i) { + if (SimAddressableLEDData[i].initialized && + SimAddressableLEDData[i].outputPort == channel) + return i; + } + return -1; +} + void HALSIM_ResetAddressableLEDData(int32_t index) { SimAddressableLEDData[index].ResetData(); } diff --git a/hal/src/main/native/sim/mockdata/AnalogTriggerData.cpp b/hal/src/main/native/sim/mockdata/AnalogTriggerData.cpp index 64d1a97c09..ba33522390 100644 --- a/hal/src/main/native/sim/mockdata/AnalogTriggerData.cpp +++ b/hal/src/main/native/sim/mockdata/AnalogTriggerData.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2017-2020 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -28,6 +28,16 @@ void AnalogTriggerData::ResetData() { } extern "C" { + +int32_t HALSIM_FindAnalogTriggerForChannel(int32_t channel) { + for (int i = 0; i < kNumAnalogTriggers; ++i) { + if (SimAnalogTriggerData[i].initialized && + SimAnalogTriggerData[i].inputPort == channel) + return i; + } + return -1; +} + void HALSIM_ResetAnalogTriggerData(int32_t index) { SimAnalogTriggerData[index].ResetData(); } diff --git a/hal/src/main/native/sim/mockdata/AnalogTriggerDataInternal.h b/hal/src/main/native/sim/mockdata/AnalogTriggerDataInternal.h index cb63cc9612..74fe5f8788 100644 --- a/hal/src/main/native/sim/mockdata/AnalogTriggerDataInternal.h +++ b/hal/src/main/native/sim/mockdata/AnalogTriggerDataInternal.h @@ -31,6 +31,7 @@ class AnalogTriggerData { SimDataValue triggerMode{static_cast(0)}; + std::atomic inputPort; virtual void ResetData(); }; diff --git a/hal/src/main/native/sim/mockdata/DigitalPWMData.cpp b/hal/src/main/native/sim/mockdata/DigitalPWMData.cpp index 78ee749a5c..541d7cffa3 100644 --- a/hal/src/main/native/sim/mockdata/DigitalPWMData.cpp +++ b/hal/src/main/native/sim/mockdata/DigitalPWMData.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2017-2020 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -27,6 +27,14 @@ void DigitalPWMData::ResetData() { } extern "C" { +int32_t HALSIM_FindDigitalPWMForChannel(int32_t channel) { + for (int i = 0; i < kNumDigitalPWMOutputs; ++i) { + if (SimDigitalPWMData[i].initialized && SimDigitalPWMData[i].pin == channel) + return i; + } + return -1; +} + void HALSIM_ResetDigitalPWMData(int32_t index) { SimDigitalPWMData[index].ResetData(); } diff --git a/hal/src/main/native/sim/mockdata/DutyCycleData.cpp b/hal/src/main/native/sim/mockdata/DutyCycleData.cpp index 04806e016b..660522d746 100644 --- a/hal/src/main/native/sim/mockdata/DutyCycleData.cpp +++ b/hal/src/main/native/sim/mockdata/DutyCycleData.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -30,6 +30,15 @@ void DutyCycleData::ResetData() { } extern "C" { +int32_t HALSIM_FindDutyCycleForChannel(int32_t channel) { + for (int i = 0; i < kNumDutyCycles; ++i) { + if (SimDutyCycleData[i].initialized && + SimDutyCycleData[i].digitalChannel == channel) + return i; + } + return -1; +} + void HALSIM_ResetDutyCycleData(int32_t index) { SimDutyCycleData[index].ResetData(); } diff --git a/hal/src/main/native/sim/mockdata/EncoderData.cpp b/hal/src/main/native/sim/mockdata/EncoderData.cpp index 6a2fb4db63..ed8b6eb6ff 100644 --- a/hal/src/main/native/sim/mockdata/EncoderData.cpp +++ b/hal/src/main/native/sim/mockdata/EncoderData.cpp @@ -36,6 +36,16 @@ void EncoderData::ResetData() { } extern "C" { +int32_t HALSIM_FindEncoderForChannel(int32_t channel) { + for (int i = 0; i < kNumEncoders; ++i) { + if (!SimEncoderData[i].initialized) continue; + if (SimEncoderData[i].digitalChannelA == channel || + SimEncoderData[i].digitalChannelB == channel) + return i; + } + return -1; +} + void HALSIM_ResetEncoderData(int32_t index) { SimEncoderData[index].ResetData(); } diff --git a/wpilibc/src/main/native/cpp/AnalogGyro.cpp b/wpilibc/src/main/native/cpp/AnalogGyro.cpp index c89150648f..877cb62be1 100644 --- a/wpilibc/src/main/native/cpp/AnalogGyro.cpp +++ b/wpilibc/src/main/native/cpp/AnalogGyro.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2020 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -160,3 +160,7 @@ void AnalogGyro::Calibrate() { HAL_CalibrateAnalogGyro(m_gyroHandle, &status); wpi_setHALError(status); } + +std::shared_ptr AnalogGyro::GetAnalogInput() const { + return m_analog; +} diff --git a/wpilibc/src/main/native/cpp/AnalogOutput.cpp b/wpilibc/src/main/native/cpp/AnalogOutput.cpp index bf89c0cb3f..bd8126a031 100644 --- a/wpilibc/src/main/native/cpp/AnalogOutput.cpp +++ b/wpilibc/src/main/native/cpp/AnalogOutput.cpp @@ -65,7 +65,7 @@ double AnalogOutput::GetVoltage() const { return voltage; } -int AnalogOutput::GetChannel() { return m_channel; } +int AnalogOutput::GetChannel() const { return m_channel; } void AnalogOutput::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("Analog Output"); diff --git a/wpilibc/src/main/native/cpp/Compressor.cpp b/wpilibc/src/main/native/cpp/Compressor.cpp index 0dcc483b82..e40758fbf2 100644 --- a/wpilibc/src/main/native/cpp/Compressor.cpp +++ b/wpilibc/src/main/native/cpp/Compressor.cpp @@ -204,6 +204,8 @@ void Compressor::ClearAllPCMStickyFaults() { } } +int Compressor::GetModule() const { return m_module; } + void Compressor::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("Compressor"); builder.AddBooleanProperty( diff --git a/wpilibc/src/main/native/cpp/PowerDistributionPanel.cpp b/wpilibc/src/main/native/cpp/PowerDistributionPanel.cpp index a0ff16d5dc..4070633e66 100644 --- a/wpilibc/src/main/native/cpp/PowerDistributionPanel.cpp +++ b/wpilibc/src/main/native/cpp/PowerDistributionPanel.cpp @@ -25,7 +25,7 @@ PowerDistributionPanel::PowerDistributionPanel() : PowerDistributionPanel(0) {} /** * Initialize the PDP. */ -PowerDistributionPanel::PowerDistributionPanel(int module) { +PowerDistributionPanel::PowerDistributionPanel(int module) : m_module(module) { int32_t status = 0; m_handle = HAL_InitializePDP(module, &status); if (status != 0) { @@ -136,6 +136,8 @@ void PowerDistributionPanel::ClearStickyFaults() { } } +int PowerDistributionPanel::GetModule() const { return m_module; } + void PowerDistributionPanel::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("PowerDistributionPanel"); for (int i = 0; i < SensorUtil::kPDPChannels; ++i) { diff --git a/wpilibc/src/main/native/cpp/simulation/CallbackStore.cpp b/wpilibc/src/main/native/cpp/simulation/CallbackStore.cpp index 6777d9bd77..a9e2de8f3c 100644 --- a/wpilibc/src/main/native/cpp/simulation/CallbackStore.cpp +++ b/wpilibc/src/main/native/cpp/simulation/CallbackStore.cpp @@ -11,3 +11,10 @@ void frc::sim::CallbackStoreThunk(const char* name, void* param, const HAL_Value* value) { reinterpret_cast(param)->callback(name, value); } + +void frc::sim::ConstBufferCallbackStoreThunk(const char* name, void* param, + const unsigned char* buffer, + unsigned int count) { + reinterpret_cast(param)->constBufferCallback(name, buffer, + count); +} diff --git a/wpilibc/src/main/native/include/frc/AnalogGyro.h b/wpilibc/src/main/native/include/frc/AnalogGyro.h index bcc67c96e6..b59df5bf64 100644 --- a/wpilibc/src/main/native/include/frc/AnalogGyro.h +++ b/wpilibc/src/main/native/include/frc/AnalogGyro.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2020 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -186,6 +186,13 @@ class AnalogGyro : public GyroBase { void Calibrate() override; + /** + * Gets the analog input for the gyro. + * + * @return AnalogInput + */ + std::shared_ptr GetAnalogInput() const; + protected: std::shared_ptr m_analog; diff --git a/wpilibc/src/main/native/include/frc/AnalogOutput.h b/wpilibc/src/main/native/include/frc/AnalogOutput.h index 1cecd707bb..026986b408 100644 --- a/wpilibc/src/main/native/include/frc/AnalogOutput.h +++ b/wpilibc/src/main/native/include/frc/AnalogOutput.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */ +/* Copyright (c) 2014-2020 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -55,7 +55,7 @@ class AnalogOutput : public ErrorBase, /** * Get the channel of this AnalogOutput. */ - int GetChannel(); + int GetChannel() const; void InitSendable(SendableBuilder& builder) override; diff --git a/wpilibc/src/main/native/include/frc/Compressor.h b/wpilibc/src/main/native/include/frc/Compressor.h index a5e512c929..d1a4dcac00 100644 --- a/wpilibc/src/main/native/include/frc/Compressor.h +++ b/wpilibc/src/main/native/include/frc/Compressor.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */ +/* Copyright (c) 2014-2020 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -171,6 +171,13 @@ class Compressor : public ErrorBase, */ void ClearAllPCMStickyFaults(); + /** + * Gets module number (CAN ID). + * + * @return Module number + */ + int GetModule() const; + void InitSendable(SendableBuilder& builder) override; protected: diff --git a/wpilibc/src/main/native/include/frc/PowerDistributionPanel.h b/wpilibc/src/main/native/include/frc/PowerDistributionPanel.h index 433874b6f9..9ec00a31bb 100644 --- a/wpilibc/src/main/native/include/frc/PowerDistributionPanel.h +++ b/wpilibc/src/main/native/include/frc/PowerDistributionPanel.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */ +/* Copyright (c) 2014-2020 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -85,10 +85,16 @@ class PowerDistributionPanel : public ErrorBase, */ void ClearStickyFaults(); + /** + * Gets module number (CAN ID). + */ + int GetModule() const; + void InitSendable(SendableBuilder& builder) override; private: hal::Handle m_handle; + int m_module; }; } // namespace frc diff --git a/wpilibc/src/main/native/include/frc/simulation/AddressableLEDSim.h b/wpilibc/src/main/native/include/frc/simulation/AddressableLEDSim.h new file mode 100644 index 0000000000..d5d5fa6828 --- /dev/null +++ b/wpilibc/src/main/native/include/frc/simulation/AddressableLEDSim.h @@ -0,0 +1,154 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2018-2020 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +#pragma once + +#include +#include +#include + +#include +#include + +#include "CallbackStore.h" +#include "frc/AddressableLED.h" + +namespace frc { +namespace sim { + +/** + * Class to control a simulated addressable LED. + */ +class AddressableLEDSim { + public: + /** + * Constructs for the first addressable LED. + */ + AddressableLEDSim() : m_index{0} {} + + /** + * Constructs from an AddressableLED object. + * + * @param addressableLED AddressableLED to simulate + */ + explicit AddressableLEDSim(const AddressableLED& addressableLED) + : m_index{0} {} + + /** + * Creates an AddressableLEDSim for a PWM channel. + * + * @param pwmChannel PWM channel + * @return Simulated object + * @throws std::out_of_range if no AddressableLED is configured for that + * channel + */ + static AddressableLEDSim CreateForChannel(int pwmChannel) { + int index = HALSIM_FindAddressableLEDForChannel(pwmChannel); + if (index < 0) + throw std::out_of_range("no addressable LED found for PWM channel"); + return AddressableLEDSim{index}; + } + + /** + * Creates an AddressableLEDSim for a simulated index. + * The index is incremented for each simulated AddressableLED. + * + * @param index simulator index + * @return Simulated object + */ + static AddressableLEDSim CreateForIndex(int index) { + return AddressableLEDSim{index}; + } + + std::unique_ptr RegisterInitializedCallback( + NotifyCallback callback, bool initialNotify) { + auto store = std::make_unique( + m_index, -1, callback, &HALSIM_CancelAddressableLEDInitializedCallback); + store->SetUid(HALSIM_RegisterAddressableLEDInitializedCallback( + m_index, &CallbackStoreThunk, store.get(), initialNotify)); + return store; + } + + bool GetInitialized() const { + return HALSIM_GetAddressableLEDInitialized(m_index); + } + + void SetInitialized(bool initialized) { + HALSIM_SetAddressableLEDInitialized(m_index, initialized); + } + + std::unique_ptr registerOutputPortCallback( + NotifyCallback callback, bool initialNotify) { + auto store = std::make_unique( + m_index, -1, callback, &HALSIM_CancelAddressableLEDOutputPortCallback); + store->SetUid(HALSIM_RegisterAddressableLEDOutputPortCallback( + m_index, &CallbackStoreThunk, store.get(), initialNotify)); + return store; + } + + int GetOutputPort() const { + return HALSIM_GetAddressableLEDOutputPort(m_index); + } + + void SetOutputPort(int outputPort) { + HALSIM_SetAddressableLEDOutputPort(m_index, outputPort); + } + + std::unique_ptr RegisterLengthCallback(NotifyCallback callback, + bool initialNotify) { + auto store = std::make_unique( + m_index, -1, callback, &HALSIM_CancelAddressableLEDLengthCallback); + store->SetUid(HALSIM_RegisterAddressableLEDLengthCallback( + m_index, &CallbackStoreThunk, store.get(), initialNotify)); + return store; + } + + int GetLength() const { return HALSIM_GetAddressableLEDLength(m_index); } + + void SetLength(int length) { + HALSIM_SetAddressableLEDLength(m_index, length); + } + + std::unique_ptr RegisterRunningCallback( + NotifyCallback callback, bool initialNotify) { + auto store = std::make_unique( + m_index, -1, callback, &HALSIM_CancelAddressableLEDRunningCallback); + store->SetUid(HALSIM_RegisterAddressableLEDRunningCallback( + m_index, &CallbackStoreThunk, store.get(), initialNotify)); + return store; + } + + int GetRunning() const { return HALSIM_GetAddressableLEDRunning(m_index); } + + void SetRunning(bool running) { + HALSIM_SetAddressableLEDRunning(m_index, running); + } + + std::unique_ptr RegisterDataCallback(NotifyCallback callback, + bool initialNotify) { + auto store = std::make_unique( + m_index, -1, callback, &HALSIM_CancelAddressableLEDDataCallback); + store->SetUid(HALSIM_RegisterAddressableLEDDataCallback( + m_index, &ConstBufferCallbackStoreThunk, store.get())); + return store; + } + + int GetData(struct HAL_AddressableLEDData* data) const { + return HALSIM_GetAddressableLEDData(m_index, data); + } + + void SetData(struct HAL_AddressableLEDData* data, int length) { + HALSIM_SetAddressableLEDData(m_index, data, length); + } + + private: + explicit AddressableLEDSim(int index) : m_index{index} {} + + int m_index; +}; +} // namespace sim +} // namespace frc diff --git a/wpilibc/src/main/native/include/frc/simulation/AnalogGyroSim.h b/wpilibc/src/main/native/include/frc/simulation/AnalogGyroSim.h index b37d0c57bd..a1d26c95ca 100644 --- a/wpilibc/src/main/native/include/frc/simulation/AnalogGyroSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/AnalogGyroSim.h @@ -13,12 +13,31 @@ #include #include "CallbackStore.h" +#include "frc/AnalogGyro.h" +#include "frc/AnalogInput.h" namespace frc { namespace sim { + +/** + * Class to control a simulated analog gyro. + */ class AnalogGyroSim { public: - explicit AnalogGyroSim(int index) { m_index = index; } + /** + * Constructs from an AnalogGyro object. + * + * @param gyro AnalogGyro to simulate + */ + explicit AnalogGyroSim(const AnalogGyro& gyro) + : m_index{gyro.GetAnalogInput()->GetChannel()} {} + + /** + * Constructs from an analog input channel number. + * + * @param channel Channel number + */ + explicit AnalogGyroSim(int channel) : m_index{channel} {} std::unique_ptr RegisterAngleCallback(NotifyCallback callback, bool initialNotify) { diff --git a/wpilibc/src/main/native/include/frc/simulation/AnalogInSim.h b/wpilibc/src/main/native/include/frc/simulation/AnalogInputSim.h similarity index 92% rename from wpilibc/src/main/native/include/frc/simulation/AnalogInSim.h rename to wpilibc/src/main/native/include/frc/simulation/AnalogInputSim.h index d317807a5a..f975c218a1 100644 --- a/wpilibc/src/main/native/include/frc/simulation/AnalogInSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/AnalogInputSim.h @@ -13,12 +13,30 @@ #include #include "CallbackStore.h" +#include "frc/AnalogInput.h" namespace frc { namespace sim { -class AnalogInSim { + +/** + * Class to control a simulated analog input. + */ +class AnalogInputSim { public: - explicit AnalogInSim(int index) { m_index = index; } + /** + * Constructs from an AnalogInput object. + * + * @param analogInput AnalogInput to simulate + */ + explicit AnalogInputSim(const AnalogInput& analogInput) + : m_index{analogInput.GetChannel()} {} + + /** + * Constructs from an analog input channel number. + * + * @param channel Channel number + */ + explicit AnalogInputSim(int channel) : m_index{channel} {} std::unique_ptr RegisterInitializedCallback( NotifyCallback callback, bool initialNotify) { diff --git a/wpilibc/src/main/native/include/frc/simulation/AnalogOutSim.h b/wpilibc/src/main/native/include/frc/simulation/AnalogOutputSim.h similarity index 79% rename from wpilibc/src/main/native/include/frc/simulation/AnalogOutSim.h rename to wpilibc/src/main/native/include/frc/simulation/AnalogOutputSim.h index 7dc4afe13d..a72f59febc 100644 --- a/wpilibc/src/main/native/include/frc/simulation/AnalogOutSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/AnalogOutputSim.h @@ -13,12 +13,30 @@ #include #include "CallbackStore.h" +#include "frc/AnalogOutput.h" namespace frc { namespace sim { -class AnalogOutSim { + +/** + * Class to control a simulated analog output. + */ +class AnalogOutputSim { public: - explicit AnalogOutSim(int index) { m_index = index; } + /** + * Constructs from an AnalogOutput object. + * + * @param analogOutput AnalogOutput to simulate + */ + explicit AnalogOutputSim(const AnalogOutput& analogOutput) + : m_index{analogOutput.GetChannel()} {} + + /** + * Constructs from an analog output channel number. + * + * @param channel Channel number + */ + explicit AnalogOutputSim(int channel) : m_index{channel} {} std::unique_ptr RegisterVoltageCallback( NotifyCallback callback, bool initialNotify) { diff --git a/wpilibc/src/main/native/include/frc/simulation/AnalogTriggerSim.h b/wpilibc/src/main/native/include/frc/simulation/AnalogTriggerSim.h index e2462282b5..8dc41a55f2 100644 --- a/wpilibc/src/main/native/include/frc/simulation/AnalogTriggerSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/AnalogTriggerSim.h @@ -7,18 +7,56 @@ #pragma once +#include #include #include #include #include "CallbackStore.h" +#include "frc/AnalogTrigger.h" namespace frc { namespace sim { + +/** + * Class to control a simulated analog trigger. + */ class AnalogTriggerSim { public: - explicit AnalogTriggerSim(int index) { m_index = index; } + /** + * Constructs from an AnalogTrigger object. + * + * @param analogTrigger AnalogTrigger to simulate + */ + explicit AnalogTriggerSim(const AnalogTrigger& analogTrigger) + : m_index{analogTrigger.GetIndex()} {} + + /** + * Creates an AnalogTriggerSim for an analog input channel. + * + * @param channel analog input channel + * @return Simulated object + * @throws std::out_of_range if no AnalogTrigger is configured for that + * channel + */ + static AnalogTriggerSim CreateForChannel(int channel) { + int index = HALSIM_FindAnalogTriggerForChannel(channel); + if (index < 0) + throw std::out_of_range("no analog trigger found for channel"); + return AnalogTriggerSim{index}; + } + + /** + * Creates an AnalogTriggerSim for a simulated index. + * The index is incremented for each simulated AnalogTrigger. + * + * @param index simulator index + * @return Simulated object + */ + static AnalogTriggerSim CreateForIndex(int index) { + return AnalogTriggerSim{index}; + } std::unique_ptr RegisterInitializedCallback( NotifyCallback callback, bool initialNotify) { @@ -76,6 +114,8 @@ class AnalogTriggerSim { void ResetData() { HALSIM_ResetAnalogTriggerData(m_index); } private: + explicit AnalogTriggerSim(int index) : m_index{index} {} + int m_index; }; } // namespace sim diff --git a/wpilibc/src/main/native/include/frc/simulation/AccelerometerSim.h b/wpilibc/src/main/native/include/frc/simulation/BuiltInAccelerometerSim.h similarity index 88% rename from wpilibc/src/main/native/include/frc/simulation/AccelerometerSim.h rename to wpilibc/src/main/native/include/frc/simulation/BuiltInAccelerometerSim.h index 4c1c9fdf59..e3b816a197 100644 --- a/wpilibc/src/main/native/include/frc/simulation/AccelerometerSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/BuiltInAccelerometerSim.h @@ -13,12 +13,28 @@ #include #include "CallbackStore.h" +#include "frc/BuiltInAccelerometer.h" namespace frc { namespace sim { -class AccelerometerSim { + +/** + * Class to control a simulated built-in accelerometer. + */ +class BuiltInAccelerometerSim { public: - explicit AccelerometerSim(int index) { m_index = index; } + /** + * Constructs for the first built-in accelerometer. + */ + BuiltInAccelerometerSim() : m_index{0} {} + + /** + * Constructs from a BuiltInAccelerometer object. + * + * @param accel BuiltInAccelerometer to simulate + */ + explicit BuiltInAccelerometerSim(const BuiltInAccelerometer& accel) + : m_index{0} {} std::unique_ptr RegisterActiveCallback(NotifyCallback callback, bool initialNotify) { diff --git a/wpilibc/src/main/native/include/frc/simulation/CallbackStore.h b/wpilibc/src/main/native/include/frc/simulation/CallbackStore.h index 5d5d352fe8..f41742b911 100644 --- a/wpilibc/src/main/native/include/frc/simulation/CallbackStore.h +++ b/wpilibc/src/main/native/include/frc/simulation/CallbackStore.h @@ -16,12 +16,17 @@ namespace frc { namespace sim { using NotifyCallback = std::function; +using ConstBufferCallback = std::function; typedef void (*CancelCallbackFunc)(int32_t index, int32_t uid); typedef void (*CancelCallbackNoIndexFunc)(int32_t uid); typedef void (*CancelCallbackChannelFunc)(int32_t index, int32_t channel, int32_t uid); void CallbackStoreThunk(const char* name, void* param, const HAL_Value* value); +void ConstBufferCallbackStoreThunk(const char* name, void* param, + const unsigned char* buffer, + unsigned int count); class CallbackStore { public: @@ -51,6 +56,33 @@ class CallbackStore { cancelType = Channel; } + CallbackStore(int32_t i, ConstBufferCallback cb, + CancelCallbackNoIndexFunc ccf) { + index = i; + constBufferCallback = cb; + this->ccnif = ccf; + cancelType = NoIndex; + } + + CallbackStore(int32_t i, int32_t u, ConstBufferCallback cb, + CancelCallbackFunc ccf) { + index = i; + uid = u; + constBufferCallback = cb; + this->ccf = ccf; + cancelType = Normal; + } + + CallbackStore(int32_t i, int32_t c, int32_t u, ConstBufferCallback cb, + CancelCallbackChannelFunc ccf) { + index = i; + channel = c; + uid = u; + constBufferCallback = cb; + this->cccf = ccf; + cancelType = Channel; + } + ~CallbackStore() { switch (cancelType) { case Normal: @@ -70,12 +102,17 @@ class CallbackStore { friend void CallbackStoreThunk(const char* name, void* param, const HAL_Value* value); + friend void ConstBufferCallbackStoreThunk(const char* name, void* param, + const unsigned char* buffer, + unsigned int count); + private: int32_t index; int32_t channel; int32_t uid; NotifyCallback callback; + ConstBufferCallback constBufferCallback; union { CancelCallbackFunc ccf; CancelCallbackChannelFunc cccf; diff --git a/wpilibc/src/main/native/include/frc/simulation/DIOSim.h b/wpilibc/src/main/native/include/frc/simulation/DIOSim.h index 1bf002646f..6985ecb9ce 100644 --- a/wpilibc/src/main/native/include/frc/simulation/DIOSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/DIOSim.h @@ -13,12 +13,37 @@ #include #include "CallbackStore.h" +#include "frc/DigitalInput.h" +#include "frc/DigitalOutput.h" namespace frc { namespace sim { + +/** + * Class to control a simulated digital input or output. + */ class DIOSim { public: - explicit DIOSim(int index) { m_index = index; } + /** + * Constructs from a DigitalInput object. + * + * @param input DigitalInput to simulate + */ + explicit DIOSim(const DigitalInput& input) : m_index{input.GetChannel()} {} + + /** + * Constructs from a DigitalOutput object. + * + * @param output DigitalOutput to simulate + */ + explicit DIOSim(const DigitalOutput& output) : m_index{output.GetChannel()} {} + + /** + * Constructs from an digital I/O channel number. + * + * @param channel Channel number + */ + explicit DIOSim(int channel) : m_index{channel} {} std::unique_ptr RegisterInitializedCallback( NotifyCallback callback, bool initialNotify) { diff --git a/wpilibc/src/main/native/include/frc/simulation/DigitalPWMSim.h b/wpilibc/src/main/native/include/frc/simulation/DigitalPWMSim.h index 2a75031853..b9e8c6a5b8 100644 --- a/wpilibc/src/main/native/include/frc/simulation/DigitalPWMSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/DigitalPWMSim.h @@ -7,18 +7,57 @@ #pragma once +#include #include #include #include #include "CallbackStore.h" +#include "frc/DigitalOutput.h" namespace frc { namespace sim { + +/** + * Class to control a simulated digital PWM output. + * + * This is for duty cycle PWM outputs on a DigitalOutput, not for the servo + * style PWM outputs on a PWM channel. + */ class DigitalPWMSim { public: - explicit DigitalPWMSim(int index) { m_index = index; } + /** + * Constructs from a DigitalOutput object. + * + * @param digitalOutput DigitalOutput to simulate + */ + explicit DigitalPWMSim(const DigitalOutput& digitalOutput) + : m_index{digitalOutput.GetChannel()} {} + + /** + * Creates an DigitalPWMSim for a digital I/O channel. + * + * @param channel DIO channel + * @return Simulated object + * @throws std::out_of_range if no Digital PWM is configured for that channel + */ + static DigitalPWMSim CreateForChannel(int channel) { + int index = HALSIM_FindDigitalPWMForChannel(channel); + if (index < 0) throw std::out_of_range("no digital PWM found for channel"); + return DigitalPWMSim{index}; + } + + /** + * Creates an DigitalPWMSim for a simulated index. + * The index is incremented for each simulated DigitalPWM. + * + * @param index simulator index + * @return Simulated object + */ + static DigitalPWMSim CreateForIndex(int index) { + return DigitalPWMSim{index}; + } std::unique_ptr RegisterInitializedCallback( NotifyCallback callback, bool initialNotify) { @@ -68,6 +107,8 @@ class DigitalPWMSim { void ResetData() { HALSIM_ResetDigitalPWMData(m_index); } private: + explicit DigitalPWMSim(int index) : m_index{index} {} + int m_index; }; } // namespace sim diff --git a/wpilibc/src/main/native/include/frc/simulation/DriverStationSim.h b/wpilibc/src/main/native/include/frc/simulation/DriverStationSim.h index 90a6169ac8..c57281a7ca 100644 --- a/wpilibc/src/main/native/include/frc/simulation/DriverStationSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/DriverStationSim.h @@ -16,9 +16,13 @@ namespace frc { namespace sim { + +/** + * Class to control a simulated driver station. + */ class DriverStationSim { public: - std::unique_ptr RegisterEnabledCallback( + static std::unique_ptr RegisterEnabledCallback( NotifyCallback callback, bool initialNotify) { auto store = std::make_unique( -1, callback, &HALSIM_CancelDriverStationEnabledCallback); @@ -27,11 +31,13 @@ class DriverStationSim { return store; } - bool GetEnabled() const { return HALSIM_GetDriverStationEnabled(); } + static bool GetEnabled() { return HALSIM_GetDriverStationEnabled(); } - void SetEnabled(bool enabled) { HALSIM_SetDriverStationEnabled(enabled); } + static void SetEnabled(bool enabled) { + HALSIM_SetDriverStationEnabled(enabled); + } - std::unique_ptr RegisterAutonomousCallback( + static std::unique_ptr RegisterAutonomousCallback( NotifyCallback callback, bool initialNotify) { auto store = std::make_unique( -1, callback, &HALSIM_CancelDriverStationAutonomousCallback); @@ -40,14 +46,14 @@ class DriverStationSim { return store; } - bool GetAutonomous() const { return HALSIM_GetDriverStationAutonomous(); } + static bool GetAutonomous() { return HALSIM_GetDriverStationAutonomous(); } - void SetAutonomous(bool autonomous) { + static void SetAutonomous(bool autonomous) { HALSIM_SetDriverStationAutonomous(autonomous); } - std::unique_ptr RegisterTestCallback(NotifyCallback callback, - bool initialNotify) { + static std::unique_ptr RegisterTestCallback( + NotifyCallback callback, bool initialNotify) { auto store = std::make_unique( -1, callback, &HALSIM_CancelDriverStationTestCallback); store->SetUid(HALSIM_RegisterDriverStationTestCallback( @@ -55,12 +61,12 @@ class DriverStationSim { return store; } - bool GetTest() const { return HALSIM_GetDriverStationTest(); } + static bool GetTest() { return HALSIM_GetDriverStationTest(); } - void SetTest(bool test) { HALSIM_SetDriverStationTest(test); } + static void SetTest(bool test) { HALSIM_SetDriverStationTest(test); } - std::unique_ptr RegisterEStopCallback(NotifyCallback callback, - bool initialNotify) { + static std::unique_ptr RegisterEStopCallback( + NotifyCallback callback, bool initialNotify) { auto store = std::make_unique( -1, callback, &HALSIM_CancelDriverStationEStopCallback); store->SetUid(HALSIM_RegisterDriverStationEStopCallback( @@ -68,11 +74,11 @@ class DriverStationSim { return store; } - bool GetEStop() const { return HALSIM_GetDriverStationEStop(); } + static bool GetEStop() { return HALSIM_GetDriverStationEStop(); } - void SetEStop(bool eStop) { HALSIM_SetDriverStationEStop(eStop); } + static void SetEStop(bool eStop) { HALSIM_SetDriverStationEStop(eStop); } - std::unique_ptr RegisterFmsAttachedCallback( + static std::unique_ptr RegisterFmsAttachedCallback( NotifyCallback callback, bool initialNotify) { auto store = std::make_unique( -1, callback, &HALSIM_CancelDriverStationFmsAttachedCallback); @@ -81,13 +87,13 @@ class DriverStationSim { return store; } - bool GetFmsAttached() const { return HALSIM_GetDriverStationFmsAttached(); } + static bool GetFmsAttached() { return HALSIM_GetDriverStationFmsAttached(); } - void SetFmsAttached(bool fmsAttached) { + static void SetFmsAttached(bool fmsAttached) { HALSIM_SetDriverStationFmsAttached(fmsAttached); } - std::unique_ptr RegisterDsAttachedCallback( + static std::unique_ptr RegisterDsAttachedCallback( NotifyCallback callback, bool initialNotify) { auto store = std::make_unique( -1, callback, &HALSIM_CancelDriverStationDsAttachedCallback); @@ -96,15 +102,15 @@ class DriverStationSim { return store; } - bool GetDsAttached() const { return HALSIM_GetDriverStationDsAttached(); } + static bool GetDsAttached() { return HALSIM_GetDriverStationDsAttached(); } - void SetDsAttached(bool dsAttached) { + static void SetDsAttached(bool dsAttached) { HALSIM_SetDriverStationDsAttached(dsAttached); } - void NotifyNewData() { HALSIM_NotifyDriverStationNewData(); } + static void NotifyNewData() { HALSIM_NotifyDriverStationNewData(); } - void ResetData() { HALSIM_ResetDriverStationData(); } + static void ResetData() { HALSIM_ResetDriverStationData(); } }; } // namespace sim } // namespace frc diff --git a/wpilibc/src/main/native/include/frc/simulation/DutyCycleSim.h b/wpilibc/src/main/native/include/frc/simulation/DutyCycleSim.h index 2998c632c3..03b0f9ac24 100644 --- a/wpilibc/src/main/native/include/frc/simulation/DutyCycleSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/DutyCycleSim.h @@ -7,18 +7,52 @@ #pragma once +#include #include #include #include #include "CallbackStore.h" +#include "frc/DutyCycle.h" namespace frc { namespace sim { + +/** + * Class to control a simulated duty cycle digital input. + */ class DutyCycleSim { public: - explicit DutyCycleSim(int index) { m_index = index; } + /** + * Constructs from a DutyCycle object. + * + * @param dutyCycle DutyCycle to simulate + */ + explicit DutyCycleSim(const DutyCycle& dutyCycle) + : m_index{dutyCycle.GetFPGAIndex()} {} + + /** + * Creates a DutyCycleSim for a digital input channel. + * + * @param channel digital input channel + * @return Simulated object + * @throws std::out_of_range if no DutyCycle is configured for that channel + */ + static DutyCycleSim CreateForChannel(int channel) { + int index = HALSIM_FindDutyCycleForChannel(channel); + if (index < 0) throw std::out_of_range("no duty cycle found for channel"); + return DutyCycleSim{index}; + } + + /** + * Creates a DutyCycleSim for a simulated index. + * The index is incremented for each simulated DutyCycle. + * + * @param index simulator index + * @return Simulated object + */ + static DutyCycleSim CreateForIndex(int index) { return DutyCycleSim{index}; } std::unique_ptr RegisterInitializedCallback( NotifyCallback callback, bool initialNotify) { @@ -66,6 +100,8 @@ class DutyCycleSim { void ResetData() { HALSIM_ResetDutyCycleData(m_index); } private: + explicit DutyCycleSim(int index) : m_index{index} {} + int m_index; }; } // namespace sim diff --git a/wpilibc/src/main/native/include/frc/simulation/EncoderSim.h b/wpilibc/src/main/native/include/frc/simulation/EncoderSim.h index 5bf89b0dfe..12eaadb6ff 100644 --- a/wpilibc/src/main/native/include/frc/simulation/EncoderSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/EncoderSim.h @@ -7,18 +7,53 @@ #pragma once +#include #include #include #include #include "CallbackStore.h" +#include "frc/Encoder.h" namespace frc { namespace sim { + +/** + * Class to control a simulated encoder. + */ class EncoderSim { public: - explicit EncoderSim(int index) { m_index = index; } + /** + * Constructs from an Encoder object. + * + * @param encoder Encoder to simulate + */ + explicit EncoderSim(const Encoder& encoder) + : m_index{encoder.GetFPGAIndex()} {} + + /** + * Creates an EncoderSim for a digital input channel. Encoders take two + * channels, so either one may be specified. + * + * @param channel digital input channel + * @return Simulated object + * @throws NoSuchElementException if no Encoder is configured for that channel + */ + static EncoderSim CreateForChannel(int channel) { + int index = HALSIM_FindEncoderForChannel(channel); + if (index < 0) throw std::out_of_range("no encoder found for channel"); + return EncoderSim{index}; + } + + /** + * Creates an EncoderSim for a simulated index. + * The index is incremented for each simulated Encoder. + * + * @param index simulator index + * @return Simulated object + */ + static EncoderSim CreateForIndex(int index) { return EncoderSim{index}; } std::unique_ptr RegisterInitializedCallback( NotifyCallback callback, bool initialNotify) { @@ -168,6 +203,8 @@ class EncoderSim { double GetRate() { return HALSIM_GetEncoderRate(m_index); } private: + explicit EncoderSim(int index) : m_index{index} {} + int m_index; }; } // namespace sim diff --git a/wpilibc/src/main/native/include/frc/simulation/PCMSim.h b/wpilibc/src/main/native/include/frc/simulation/PCMSim.h index 091f7ff1ad..84f52672fd 100644 --- a/wpilibc/src/main/native/include/frc/simulation/PCMSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/PCMSim.h @@ -13,12 +13,32 @@ #include #include "CallbackStore.h" +#include "frc/Compressor.h" +#include "frc/SensorUtil.h" namespace frc { namespace sim { + +/** + * Class to control a simulated Pneumatic Control Module (PCM). + */ class PCMSim { public: - explicit PCMSim(int index) { m_index = index; } + /** + * Constructs from a PCM module number (CAN ID). + * + * @param module module number + */ + explicit PCMSim(int module = SensorUtil::GetDefaultSolenoidModule()) + : m_index{module} {} + + /** + * Constructs from a Compressor object. + * + * @param compressor Compressor connected to PCM to simulate + */ + explicit PCMSim(const Compressor& compressor) + : m_index{compressor.GetModule()} {} std::unique_ptr RegisterSolenoidInitializedCallback( int channel, NotifyCallback callback, bool initialNotify) { diff --git a/wpilibc/src/main/native/include/frc/simulation/PDPSim.h b/wpilibc/src/main/native/include/frc/simulation/PDPSim.h index 73e3cda54e..76cd408be5 100644 --- a/wpilibc/src/main/native/include/frc/simulation/PDPSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/PDPSim.h @@ -13,12 +13,30 @@ #include #include "CallbackStore.h" +#include "frc/PowerDistributionPanel.h" namespace frc { namespace sim { + +/** + * Class to control a simulated Power Distribution Panel (PDP). + */ class PDPSim { public: - explicit PDPSim(int index) { m_index = index; } + /** + * Constructs from a PDP module number (CAN ID). + * + * @param module module number + */ + explicit PDPSim(int module = 0) : m_index{module} {} + + /** + * Constructs from a PowerDistributionPanel object. + * + * @param pdp PowerDistributionPanel to simulate + */ + explicit PDPSim(const PowerDistributionPanel& pdp) + : m_index{pdp.GetModule()} {} std::unique_ptr RegisterInitializedCallback( NotifyCallback callback, bool initialNotify) { diff --git a/wpilibc/src/main/native/include/frc/simulation/PWMSim.h b/wpilibc/src/main/native/include/frc/simulation/PWMSim.h index 726555c8fb..8b950e796a 100644 --- a/wpilibc/src/main/native/include/frc/simulation/PWMSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/PWMSim.h @@ -13,12 +13,29 @@ #include #include "CallbackStore.h" +#include "frc/PWM.h" namespace frc { namespace sim { + +/** + * Class to control a simulated PWM output. + */ class PWMSim { public: - explicit PWMSim(int index) { m_index = index; } + /** + * Constructs from a PWM object. + * + * @param pwm PWM to simulate + */ + explicit PWMSim(const PWM& pwm) : m_index{pwm.GetChannel()} {} + + /** + * Constructs from a PWM channel number. + * + * @param channel Channel number + */ + explicit PWMSim(int channel) : m_index{channel} {} std::unique_ptr RegisterInitializedCallback( NotifyCallback callback, bool initialNotify) { diff --git a/wpilibc/src/main/native/include/frc/simulation/RelaySim.h b/wpilibc/src/main/native/include/frc/simulation/RelaySim.h index c8b1680c38..99ef8b70aa 100644 --- a/wpilibc/src/main/native/include/frc/simulation/RelaySim.h +++ b/wpilibc/src/main/native/include/frc/simulation/RelaySim.h @@ -13,12 +13,29 @@ #include #include "CallbackStore.h" +#include "frc/Relay.h" namespace frc { namespace sim { + +/** + * Class to control a simulated relay. + */ class RelaySim { public: - explicit RelaySim(int index) { m_index = index; } + /** + * Constructs from a Relay object. + * + * @param relay Relay to simulate + */ + explicit RelaySim(const Relay& relay) : m_index{relay.GetChannel()} {} + + /** + * Constructs from a relay channel number. + * + * @param channel Channel number + */ + explicit RelaySim(int channel) : m_index{channel} {} std::unique_ptr RegisterInitializedForwardCallback( NotifyCallback callback, bool initialNotify) { diff --git a/wpilibc/src/main/native/include/frc/simulation/SimDeviceSim.h b/wpilibc/src/main/native/include/frc/simulation/SimDeviceSim.h index 5ea076ea64..6765721078 100644 --- a/wpilibc/src/main/native/include/frc/simulation/SimDeviceSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/SimDeviceSim.h @@ -20,8 +20,17 @@ namespace frc { namespace sim { + +/** + * Class to control the simulation side of a SimDevice. + */ class SimDeviceSim { public: + /** + * Constructs a SimDeviceSim. + * + * @param name name of the SimDevice + */ explicit SimDeviceSim(const char* name) : m_handle{HALSIM_GetSimDeviceHandle(name)} {} diff --git a/wpilibc/src/main/native/include/frc/simulation/SimHooks.h b/wpilibc/src/main/native/include/frc/simulation/SimHooks.h index b91c9f8c47..9bbe104dd4 100644 --- a/wpilibc/src/main/native/include/frc/simulation/SimHooks.h +++ b/wpilibc/src/main/native/include/frc/simulation/SimHooks.h @@ -12,23 +12,25 @@ namespace frc { namespace sim { -void SetRuntimeType(HAL_RuntimeType type) { HALSIM_SetRuntimeType(type); } +inline void SetRuntimeType(HAL_RuntimeType type) { + HALSIM_SetRuntimeType(type); +} -void WaitForProgramStart() { HALSIM_WaitForProgramStart(); } +inline void WaitForProgramStart() { HALSIM_WaitForProgramStart(); } -void SetProgramStarted() { HALSIM_SetProgramStarted(); } +inline void SetProgramStarted() { HALSIM_SetProgramStarted(); } -bool GetProgramStarted() { return HALSIM_GetProgramStarted(); } +inline bool GetProgramStarted() { return HALSIM_GetProgramStarted(); } -void RestartTiming() { HALSIM_RestartTiming(); } +inline void RestartTiming() { HALSIM_RestartTiming(); } -void PauseTiming() { HALSIM_PauseTiming(); } +inline void PauseTiming() { HALSIM_PauseTiming(); } -void ResumeTiming() { HALSIM_ResumeTiming(); } +inline void ResumeTiming() { HALSIM_ResumeTiming(); } -bool IsTimingPaused() { return HALSIM_IsTimingPaused(); } +inline bool IsTimingPaused() { return HALSIM_IsTimingPaused(); } -void StepTiming(uint64_t delta) { HALSIM_StepTiming(delta); } +inline void StepTiming(uint64_t delta) { HALSIM_StepTiming(delta); } } // namespace sim } // namespace frc diff --git a/wpilibc/src/test/native/cpp/simulation/AccelerometerSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/AccelerometerSimTest.cpp index 7807e0c908..d2c7ea8910 100644 --- a/wpilibc/src/test/native/cpp/simulation/AccelerometerSimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/AccelerometerSimTest.cpp @@ -5,7 +5,7 @@ /* the project. */ /*----------------------------------------------------------------------------*/ -#include "frc/simulation/AccelerometerSim.h" // NOLINT(build/include_order) +#include "frc/simulation/BuiltInAccelerometerSim.h" // NOLINT(build/include_order) #include #include @@ -17,7 +17,7 @@ using namespace frc::sim; TEST(AcclerometerSimTests, TestActiveCallback) { HAL_Initialize(500, 0); - AccelerometerSim sim{0}; + BuiltInAccelerometerSim sim; sim.ResetData(); diff --git a/wpilibc/src/test/native/cpp/simulation/SimInitializationTest.cpp b/wpilibc/src/test/native/cpp/simulation/SimInitializationTest.cpp index c836d76afa..1b86e055a9 100644 --- a/wpilibc/src/test/native/cpp/simulation/SimInitializationTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/SimInitializationTest.cpp @@ -5,16 +5,20 @@ /* the project. */ /*----------------------------------------------------------------------------*/ +#include + #include -#include "frc/simulation/AccelerometerSim.h" +#include "frc/simulation/AddressableLEDSim.h" #include "frc/simulation/AnalogGyroSim.h" -#include "frc/simulation/AnalogInSim.h" -#include "frc/simulation/AnalogOutSim.h" +#include "frc/simulation/AnalogInputSim.h" +#include "frc/simulation/AnalogOutputSim.h" #include "frc/simulation/AnalogTriggerSim.h" +#include "frc/simulation/BuiltInAccelerometerSim.h" #include "frc/simulation/DIOSim.h" #include "frc/simulation/DigitalPWMSim.h" #include "frc/simulation/DriverStationSim.h" +#include "frc/simulation/DutyCycleSim.h" #include "frc/simulation/EncoderSim.h" #include "frc/simulation/PCMSim.h" #include "frc/simulation/PDPSim.h" @@ -28,16 +32,17 @@ using namespace frc::sim; TEST(SimInitializationTests, TestAllInitialize) { HAL_Initialize(500, 0); - AccelerometerSim acsim{0}; + BuiltInAccelerometerSim biacsim; AnalogGyroSim agsim{0}; - AnalogInSim aisim{0}; - AnalogOutSim aosim{0}; - AnalogTriggerSim atsim{0}; - DigitalPWMSim dpsim{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}; DriverStationSim dssim; (void)dssim; - EncoderSim esim{0}; + EncoderSim esim = EncoderSim::CreateForIndex(0); + (void)esim; PCMSim pcmsim{0}; PDPSim pdpsim{0}; PWMSim pwmsim{0}; @@ -45,4 +50,7 @@ TEST(SimInitializationTests, TestAllInitialize) { RoboRioSim rrsim; (void)rrsim; SPIAccelerometerSim sasim{0}; + DutyCycleSim dcsim = DutyCycleSim::CreateForIndex(0); + (void)dcsim; + AddressableLEDSim adLED; } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java index c688b55959..0ed22d98aa 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2020 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -184,7 +184,16 @@ public class AnalogGyro extends GyroBase implements Gyro, PIDSource, Sendable, A * * @param volts The size of the deadband in volts */ - void setDeadband(double volts) { + public void setDeadband(double volts) { AnalogGyroJNI.setAnalogGyroDeadband(m_gyroHandle, volts); } + + /** + * Gets the analog input for the gyro. + * + * @return AnalogInput + */ + public AnalogInput getAnalogInput() { + return m_analog; + } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java index 9d8a8dd4b1..8fbefd8d55 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2020 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -196,6 +196,15 @@ public class Compressor implements Sendable, AutoCloseable { CompressorJNI.clearAllPCMStickyFaults(m_module); } + /** + * Gets the module number (CAN ID). + * + * @return Module number + */ + public int getModule() { + return m_module; + } + @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Compressor"); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistributionPanel.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistributionPanel.java index e30be1be4b..ef46028a87 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistributionPanel.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistributionPanel.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */ +/* Copyright (c) 2014-2020 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -19,6 +19,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; */ public class PowerDistributionPanel implements Sendable, AutoCloseable { private final int m_handle; + private final int m_module; /** * Constructor. @@ -28,6 +29,7 @@ public class PowerDistributionPanel implements Sendable, AutoCloseable { public PowerDistributionPanel(int module) { SensorUtil.checkPDPModule(module); m_handle = PDPJNI.initializePDP(module); + m_module = module; HAL.report(tResourceType.kResourceType_PDP, module + 1); SendableRegistry.addLW(this, "PowerDistributionPanel", module); @@ -117,6 +119,13 @@ public class PowerDistributionPanel implements Sendable, AutoCloseable { PDPJNI.clearPDPStickyFaults(m_handle); } + /** + * Gets module number (CAN ID). + */ + public int getModule() { + return m_module; + } + @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("PowerDistributionPanel"); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AddressableLEDSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AddressableLEDSim.java index 8369a0593a..81c9a7be73 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AddressableLEDSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AddressableLEDSim.java @@ -10,14 +10,63 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.hal.simulation.AddressableLEDDataJNI; import edu.wpi.first.hal.simulation.ConstBufferCallback; import edu.wpi.first.hal.simulation.NotifyCallback; +import edu.wpi.first.wpilibj.AddressableLED; +import java.util.NoSuchElementException; +/** + * Class to control a simulated addressable LED. + */ public class AddressableLEDSim { private final int m_index; - public AddressableLEDSim(int index) { + /** + * Constructs for the first addressable LED. + */ + public AddressableLEDSim() { + m_index = 0; + } + + /** + * Constructs from an AddressableLED object. + * + * @param addressableLED AddressableLED to simulate + */ + @SuppressWarnings("PMD.UnusedFormalParameter") + public AddressableLEDSim(AddressableLED addressableLED) { + // there is only support for a single AddressableLED, so no lookup + m_index = 0; + } + + private AddressableLEDSim(int index) { m_index = index; } + /** + * Creates an AddressableLEDSim for a PWM channel. + * + * @param pwmChannel PWM channel + * @return Simulated object + * @throws NoSuchElementException if no AddressableLED is configured for that channel + */ + public static AddressableLEDSim createForChannel(int pwmChannel) { + int index = AddressableLEDDataJNI.findForChannel(pwmChannel); + if (index < 0) { + throw new NoSuchElementException("no addressable LED found for PWM channel " + pwmChannel); + } + return new AddressableLEDSim(index); + } + + /** + * Creates an AddressableLEDSim for a simulated index. + * The index is incremented for each simulated AddressableLED. + * + * @param index simulator index + * @return Simulated object + */ + public static AddressableLEDSim createForIndex(int index) { + return new AddressableLEDSim(index); + } + public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) { int uid = AddressableLEDDataJNI.registerInitializedCallback(m_index, callback, initialNotify); return new CallbackStore(m_index, uid, AddressableLEDDataJNI::cancelInitializedCallback); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogGyroSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogGyroSim.java index 539bac15c8..b204fae168 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogGyroSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogGyroSim.java @@ -9,12 +9,30 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.hal.simulation.AnalogGyroDataJNI; import edu.wpi.first.hal.simulation.NotifyCallback; +import edu.wpi.first.wpilibj.AnalogGyro; +/** + * Class to control a simulated analog gyro. + */ public class AnalogGyroSim { private final int m_index; - public AnalogGyroSim(int index) { - m_index = index; + /** + * Constructs from an AnalogGyro object. + * + * @param gyro AnalogGyro to simulate + */ + public AnalogGyroSim(AnalogGyro gyro) { + m_index = gyro.getAnalogInput().getChannel(); + } + + /** + * Constructs from an analog input channel number. + * + * @param channel Channel number + */ + public AnalogGyroSim(int channel) { + m_index = channel; } public CallbackStore registerAngleCallback(NotifyCallback callback, boolean initialNotify) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogInSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogInputSim.java similarity index 91% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogInSim.java rename to wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogInputSim.java index 0fee6d2855..d9494f7e74 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogInSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogInputSim.java @@ -9,12 +9,31 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.hal.simulation.AnalogInDataJNI; import edu.wpi.first.hal.simulation.NotifyCallback; +import edu.wpi.first.wpilibj.AnalogInput; -public class AnalogInSim { +/** + * Class to control a simulated analog input. + */ +@SuppressWarnings("PMD.TooManyMethods") +public class AnalogInputSim { private final int m_index; - public AnalogInSim(int index) { - m_index = index; + /** + * Constructs from an AnalogInput object. + * + * @param analogInput AnalogInput to simulate + */ + public AnalogInputSim(AnalogInput analogInput) { + m_index = analogInput.getChannel(); + } + + /** + * Constructs from an analog input channel number. + * + * @param channel Channel number + */ + public AnalogInputSim(int channel) { + m_index = channel; } public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogOutSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogOutputSim.java similarity index 76% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogOutSim.java rename to wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogOutputSim.java index fc67b3187f..077a2eb458 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogOutSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogOutputSim.java @@ -9,12 +9,30 @@ 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; -public class AnalogOutSim { +/** + * Class to control a simulated analog output. + */ +public class AnalogOutputSim { private final int m_index; - public AnalogOutSim(int index) { - m_index = 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; } public CallbackStore registerVoltageCallback(NotifyCallback callback, boolean initialNotify) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogTriggerSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogTriggerSim.java index d90ff3a117..6916fdc92c 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogTriggerSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AnalogTriggerSim.java @@ -9,14 +9,54 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.hal.simulation.AnalogTriggerDataJNI; import edu.wpi.first.hal.simulation.NotifyCallback; +import edu.wpi.first.wpilibj.AnalogTrigger; +import java.util.NoSuchElementException; +/** + * Class to control a simulated analog trigger. + */ public class AnalogTriggerSim { private final int m_index; - public AnalogTriggerSim(int index) { + /** + * Constructs from an AnalogTrigger object. + * + * @param analogTrigger AnalogTrigger to simulate + */ + public AnalogTriggerSim(AnalogTrigger analogTrigger) { + m_index = analogTrigger.getIndex(); + } + + private AnalogTriggerSim(int index) { m_index = index; } + /** + * Creates an AnalogTriggerSim for an analog input channel. + * + * @param channel analog input channel + * @return Simulated object + * @throws NoSuchElementException if no AnalogTrigger is configured for that channel + */ + public static AnalogTriggerSim createForChannel(int channel) { + int index = AnalogTriggerDataJNI.findForChannel(channel); + if (index < 0) { + throw new NoSuchElementException("no analog trigger found for channel " + channel); + } + return new AnalogTriggerSim(index); + } + + /** + * Creates an AnalogTriggerSim for a simulated index. + * The index is incremented for each simulated AnalogTrigger. + * + * @param index simulator index + * @return Simulated object + */ + public static AnalogTriggerSim createForIndex(int index) { + return new AnalogTriggerSim(index); + } + public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) { int uid = AnalogTriggerDataJNI.registerInitializedCallback(m_index, callback, initialNotify); return new CallbackStore(m_index, uid, AnalogTriggerDataJNI::cancelInitializedCallback); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AccelerometerSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/BuiltInAccelerometerSim.java similarity index 85% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AccelerometerSim.java rename to wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/BuiltInAccelerometerSim.java index 3acf1e9ae0..8905542611 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/AccelerometerSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/BuiltInAccelerometerSim.java @@ -9,11 +9,28 @@ 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; -public class AccelerometerSim { +/** + * Class to control a simulated built-in accelerometer. + */ +public class BuiltInAccelerometerSim { private final int m_index; - public AccelerometerSim() { + /** + * 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; } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DIOSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DIOSim.java index ef186a8e36..758d7e4cca 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DIOSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DIOSim.java @@ -9,12 +9,40 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.hal.simulation.DIODataJNI; import edu.wpi.first.hal.simulation.NotifyCallback; +import edu.wpi.first.wpilibj.DigitalInput; +import edu.wpi.first.wpilibj.DigitalOutput; +/** + * Class to control a simulated digital input or output. + */ public class DIOSim { private final int m_index; - public DIOSim(int index) { - m_index = index; + /** + * Constructs from a DigitalInput object. + * + * @param input DigitalInput to simulate + */ + public DIOSim(DigitalInput input) { + m_index = input.getChannel(); + } + + /** + * Constructs from a DigitalOutput object. + * + * @param output DigitalOutput to simulate + */ + public DIOSim(DigitalOutput output) { + m_index = output.getChannel(); + } + + /** + * Constructs from an digital I/O channel number. + * + * @param channel Channel number + */ + public DIOSim(int channel) { + m_index = channel; } public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DigitalPWMSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DigitalPWMSim.java index c934f87c76..db942eb18e 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DigitalPWMSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DigitalPWMSim.java @@ -9,14 +9,57 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.hal.simulation.DigitalPWMDataJNI; import edu.wpi.first.hal.simulation.NotifyCallback; +import edu.wpi.first.wpilibj.DigitalOutput; +import java.util.NoSuchElementException; +/** + * Class to control a simulated digital PWM output. + * + *

This is for duty cycle PWM outputs on a DigitalOutput, not for the servo + * style PWM outputs on a PWM channel. + */ public class DigitalPWMSim { private final int m_index; - public DigitalPWMSim(int index) { + /** + * Constructs from a DigitalOutput object. + * + * @param digitalOutput DigitalOutput to simulate + */ + public DigitalPWMSim(DigitalOutput digitalOutput) { + m_index = digitalOutput.getChannel(); + } + + private DigitalPWMSim(int index) { m_index = index; } + /** + * Creates an DigitalPWMSim for a digital I/O channel. + * + * @param channel DIO channel + * @return Simulated object + * @throws NoSuchElementException if no Digital PWM is configured for that channel + */ + public static DigitalPWMSim createForChannel(int channel) { + int index = DigitalPWMDataJNI.findForChannel(channel); + if (index < 0) { + throw new NoSuchElementException("no digital PWM found for channel " + channel); + } + return new DigitalPWMSim(index); + } + + /** + * Creates an DigitalPWMSim for a simulated index. + * The index is incremented for each simulated DigitalPWM. + * + * @param index simulator index + * @return Simulated object + */ + public static DigitalPWMSim createForIndex(int index) { + return new DigitalPWMSim(index); + } + public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) { int uid = DigitalPWMDataJNI.registerInitializedCallback(m_index, callback, initialNotify); return new CallbackStore(m_index, uid, DigitalPWMDataJNI::cancelInitializedCallback); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java index bc04608f19..8d6e6573b8 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java @@ -10,73 +10,77 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.hal.simulation.DriverStationDataJNI; import edu.wpi.first.hal.simulation.NotifyCallback; +/** + * Class to control a simulated driver station. + */ +@SuppressWarnings("PMD.UseUtilityClass") public class DriverStationSim { - public CallbackStore registerEnabledCallback(NotifyCallback callback, boolean initialNotify) { + public static CallbackStore registerEnabledCallback(NotifyCallback callback, boolean initialNotify) { int uid = DriverStationDataJNI.registerEnabledCallback(callback, initialNotify); return new CallbackStore(uid, DriverStationDataJNI::cancelEnabledCallback); } - public boolean getEnabled() { + public static boolean getEnabled() { return DriverStationDataJNI.getEnabled(); } - public void setEnabled(boolean enabled) { + public static void setEnabled(boolean enabled) { DriverStationDataJNI.setEnabled(enabled); } - public CallbackStore registerAutonomousCallback(NotifyCallback callback, boolean initialNotify) { + public static CallbackStore registerAutonomousCallback(NotifyCallback callback, boolean initialNotify) { int uid = DriverStationDataJNI.registerAutonomousCallback(callback, initialNotify); return new CallbackStore(uid, DriverStationDataJNI::cancelAutonomousCallback); } - public boolean getAutonomous() { + public static boolean getAutonomous() { return DriverStationDataJNI.getAutonomous(); } - public void setAutonomous(boolean autonomous) { + public static void setAutonomous(boolean autonomous) { DriverStationDataJNI.setAutonomous(autonomous); } - public CallbackStore registerTestCallback(NotifyCallback callback, boolean initialNotify) { + public static CallbackStore registerTestCallback(NotifyCallback callback, boolean initialNotify) { int uid = DriverStationDataJNI.registerTestCallback(callback, initialNotify); return new CallbackStore(uid, DriverStationDataJNI::cancelTestCallback); } - public boolean getTest() { + public static boolean getTest() { return DriverStationDataJNI.getTest(); } - public void setTest(boolean test) { + public static void setTest(boolean test) { DriverStationDataJNI.setTest(test); } - public CallbackStore registerEStopCallback(NotifyCallback callback, boolean initialNotify) { + public static CallbackStore registerEStopCallback(NotifyCallback callback, boolean initialNotify) { int uid = DriverStationDataJNI.registerEStopCallback(callback, initialNotify); return new CallbackStore(uid, DriverStationDataJNI::cancelEStopCallback); } - public boolean getEStop() { + public static boolean getEStop() { return DriverStationDataJNI.getEStop(); } - public void setEStop(boolean eStop) { + public static void setEStop(boolean eStop) { DriverStationDataJNI.setEStop(eStop); } - public CallbackStore registerFmsAttachedCallback(NotifyCallback callback, boolean initialNotify) { + public static CallbackStore registerFmsAttachedCallback(NotifyCallback callback, boolean initialNotify) { int uid = DriverStationDataJNI.registerFmsAttachedCallback(callback, initialNotify); return new CallbackStore(uid, DriverStationDataJNI::cancelFmsAttachedCallback); } - public boolean getFmsAttached() { + public static boolean getFmsAttached() { return DriverStationDataJNI.getFmsAttached(); } - public void setFmsAttached(boolean fmsAttached) { + public static void setFmsAttached(boolean fmsAttached) { DriverStationDataJNI.setFmsAttached(fmsAttached); } - public CallbackStore registerDsAttachedCallback(NotifyCallback callback, boolean initialNotify) { + public static CallbackStore registerDsAttachedCallback(NotifyCallback callback, boolean initialNotify) { int uid = DriverStationDataJNI.registerDsAttachedCallback(callback, initialNotify); return new CallbackStore(uid, DriverStationDataJNI::cancelDsAttachedCallback); } - public boolean getDsAttached() { + public static boolean getDsAttached() { return DriverStationDataJNI.getDsAttached(); } - public void setDsAttached(boolean dsAttached) { + public static void setDsAttached(boolean dsAttached) { DriverStationDataJNI.setDsAttached(dsAttached); } - public void notifyNewData() { + public static void notifyNewData() { DriverStationDataJNI.notifyNewData(); } @@ -85,11 +89,11 @@ public class DriverStationSim { * * @param shouldSend If false then messages will will be suppressed. */ - public void setSendError(boolean shouldSend) { + public static void setSendError(boolean shouldSend) { DriverStationDataJNI.setSendError(shouldSend); } - public void resetData() { + public static void resetData() { DriverStationDataJNI.resetData(); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DutyCycleSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DutyCycleSim.java index 47e2e637e2..726e08c141 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DutyCycleSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DutyCycleSim.java @@ -9,14 +9,54 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.hal.simulation.DutyCycleDataJNI; import edu.wpi.first.hal.simulation.NotifyCallback; +import edu.wpi.first.wpilibj.DutyCycle; +import java.util.NoSuchElementException; +/** + * Class to control a simulated duty cycle digital input. + */ public class DutyCycleSim { private final int m_index; - public DutyCycleSim(int index) { + /** + * Constructs from a DutyCycle object. + * + * @param dutyCycle DutyCycle to simulate + */ + public DutyCycleSim(DutyCycle dutyCycle) { + m_index = dutyCycle.getFPGAIndex(); + } + + private DutyCycleSim(int index) { m_index = index; } + /** + * Creates a DutyCycleSim for a digital input channel. + * + * @param channel digital input channel + * @return Simulated object + * @throws NoSuchElementException if no DutyCycle is configured for that channel + */ + public static DutyCycleSim createForChannel(int channel) { + int index = DutyCycleDataJNI.findForChannel(channel); + if (index < 0) { + throw new NoSuchElementException("no duty cycle found for channel " + channel); + } + return new DutyCycleSim(index); + } + + /** + * Creates a DutyCycleSim for a simulated index. + * The index is incremented for each simulated DutyCycle. + * + * @param index simulator index + * @return Simulated object + */ + public static DutyCycleSim createForIndex(int index) { + return new DutyCycleSim(index); + } + public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) { int uid = DutyCycleDataJNI.registerInitializedCallback(m_index, callback, initialNotify); return new CallbackStore(m_index, uid, DutyCycleDataJNI::cancelInitializedCallback); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/EncoderSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/EncoderSim.java index 2ea74ff5de..34d4219276 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/EncoderSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/EncoderSim.java @@ -9,14 +9,56 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.hal.simulation.EncoderDataJNI; import edu.wpi.first.hal.simulation.NotifyCallback; +import edu.wpi.first.wpilibj.Encoder; +import java.util.NoSuchElementException; +/** + * Class to control a simulated encoder. + */ +@SuppressWarnings("PMD.TooManyMethods") public class EncoderSim { private final int m_index; - public EncoderSim(int index) { + /** + * Constructs from an Encoder object. + * + * @param encoder Encoder to simulate + */ + public EncoderSim(Encoder encoder) { + m_index = encoder.getFPGAIndex(); + } + + private EncoderSim(int index) { m_index = index; } + /** + * Creates an EncoderSim for a digital input channel. Encoders take two + * channels, so either one may be specified. + * + * @param channel digital input channel + * @return Simulated object + * @throws NoSuchElementException if no Encoder is configured for that channel + */ + public static EncoderSim createForChannel(int channel) { + int index = EncoderDataJNI.findForChannel(channel); + if (index < 0) { + throw new NoSuchElementException("no encoder found for channel " + channel); + } + return new EncoderSim(index); + } + + /** + * Creates an EncoderSim for a simulated index. + * The index is incremented for each simulated Encoder. + * + * @param index simulator index + * @return Simulated object + */ + public static EncoderSim createForIndex(int index) { + return new EncoderSim(index); + } + public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) { int uid = EncoderDataJNI.registerInitializedCallback(m_index, callback, initialNotify); return new CallbackStore(m_index, uid, EncoderDataJNI::cancelInitializedCallback); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/NotifierSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/NotifierSim.java index 54958d81b9..3778e360d6 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/NotifierSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/NotifierSim.java @@ -9,14 +9,27 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.hal.simulation.NotifierDataJNI; +/** + * Class to control simulated notifiers. + */ public final class NotifierSim { private NotifierSim() { } + /** + * Gets the timeout of the next notifier. + * + * @return Timestamp + */ public static long getNextTimeout() { return NotifierDataJNI.getNextTimeout(); } + /** + * Gets the total number of notifiers. + * + * @return Count + */ public static int getNumNotifiers() { return NotifierDataJNI.getNumNotifiers(); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PCMSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PCMSim.java index 4d458a4ea2..7881f0cc04 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PCMSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PCMSim.java @@ -9,12 +9,38 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.hal.simulation.NotifyCallback; import edu.wpi.first.hal.simulation.PCMDataJNI; +import edu.wpi.first.wpilibj.Compressor; +import edu.wpi.first.wpilibj.SensorUtil; +/** + * Class to control a simulated Pneumatic Control Module (PCM). + */ public class PCMSim { private final int m_index; - public PCMSim(int index) { - m_index = index; + /** + * Constructs for the default PCM. + */ + public PCMSim() { + m_index = SensorUtil.getDefaultSolenoidModule(); + } + + /** + * Constructs from a PCM module number (CAN ID). + * + * @param module module number + */ + public PCMSim(int module) { + m_index = module; + } + + /** + * Constructs from a Compressor object. + * + * @param compressor Compressor connected to PCM to simulate + */ + public PCMSim(Compressor compressor) { + m_index = compressor.getModule(); } public CallbackStore registerSolenoidInitializedCallback(int channel, NotifyCallback callback, boolean initialNotify) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PDPSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PDPSim.java index 2696ef4050..ad57973955 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PDPSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PDPSim.java @@ -9,12 +9,37 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.hal.simulation.NotifyCallback; import edu.wpi.first.hal.simulation.PDPDataJNI; +import edu.wpi.first.wpilibj.PowerDistributionPanel; +/** + * Class to control a simulated Power Distribution Panel (PDP). + */ public class PDPSim { private final int m_index; - public PDPSim(int index) { - m_index = index; + /** + * Constructs for the default PDP. + */ + public PDPSim() { + m_index = 0; + } + + /** + * Constructs from a PDP module number (CAN ID). + * + * @param module module number + */ + public PDPSim(int module) { + m_index = module; + } + + /** + * Constructs from a PowerDistributionPanel object. + * + * @param pdp PowerDistributionPanel to simulate + */ + public PDPSim(PowerDistributionPanel pdp) { + m_index = pdp.getModule(); } public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PWMSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PWMSim.java index 2326e9a5c1..d0cca92fdc 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PWMSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PWMSim.java @@ -9,12 +9,30 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.hal.simulation.NotifyCallback; import edu.wpi.first.hal.simulation.PWMDataJNI; +import edu.wpi.first.wpilibj.PWM; +/** + * Class to control a simulated PWM output. + */ public class PWMSim { private final int m_index; - public PWMSim(int index) { - m_index = index; + /** + * Constructs from a PWM object. + * + * @param pwm PWM to simulate + */ + public PWMSim(PWM pwm) { + m_index = pwm.getChannel(); + } + + /** + * Constructs from a PWM channel number. + * + * @param channel Channel number + */ + public PWMSim(int channel) { + m_index = channel; } public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/RelaySim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/RelaySim.java index 140c6d76bb..dc7441e926 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/RelaySim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/RelaySim.java @@ -9,12 +9,30 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.hal.simulation.NotifyCallback; import edu.wpi.first.hal.simulation.RelayDataJNI; +import edu.wpi.first.wpilibj.Relay; +/** + * Class to control a simulated relay. + */ public class RelaySim { private final int m_index; - public RelaySim(int index) { - m_index = index; + /** + * Constructs from a Relay object. + * + * @param relay Relay to simulate + */ + public RelaySim(Relay relay) { + m_index = relay.getChannel(); + } + + /** + * Constructs from a relay channel number. + * + * @param channel Channel number + */ + public RelaySim(int channel) { + m_index = channel; } public CallbackStore registerInitializedForwardCallback(NotifyCallback callback, boolean initialNotify) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SPISim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SPISim.java index 6a7f548532..71c197a998 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SPISim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SPISim.java @@ -16,8 +16,8 @@ import edu.wpi.first.hal.simulation.SpiReadAutoReceiveBufferCallback; public class SPISim { private final int m_index; - public SPISim(int index) { - m_index = index; + public SPISim() { + m_index = 0; } public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SimDeviceSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SimDeviceSim.java index 49f57c43ac..e0829be4c1 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SimDeviceSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SimDeviceSim.java @@ -15,9 +15,17 @@ import edu.wpi.first.hal.simulation.SimDeviceCallback; import edu.wpi.first.hal.simulation.SimDeviceDataJNI; import edu.wpi.first.hal.simulation.SimValueCallback; +/** + * Class to control the simulation side of a SimDevice. + */ public class SimDeviceSim { private final int m_handle; + /** + * Constructs a SimDeviceSim. + * + * @param name name of the SimDevice + */ public SimDeviceSim(String name) { m_handle = SimDeviceDataJNI.getSimDeviceHandle(name); } 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 index 991e267b59..05ea2905e5 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AccelerometerSimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AccelerometerSimTest.java @@ -24,7 +24,7 @@ class AccelerometerSimTest { @Test void testCallbacks() { HAL.initialize(500, 0); - AccelerometerSim sim = new AccelerometerSim(); + BuiltInAccelerometerSim sim = new BuiltInAccelerometerSim(); sim.resetData(); TriggeredStore store = new TriggeredStore(); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AnalogInputSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AnalogInputSimTest.java index 642b2f2fa5..e78abf9d8e 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AnalogInputSimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AnalogInputSimTest.java @@ -26,7 +26,7 @@ class AnalogInputSimTest { HAL.initialize(500, 0); AnalogInput input = new AnalogInput(5); - AnalogInSim inputSim = new AnalogInSim(5); + AnalogInputSim inputSim = new AnalogInputSim(input); for (double i = 0; i < 5.0; i += 0.1) { inputSim.setVoltage(0); 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 index c8e095c3c5..fdb7384902 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AnalogOutputSimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AnalogOutputSimTest.java @@ -37,7 +37,7 @@ class AnalogOutputSimTest { AnalogOutput output = new AnalogOutput(0); output.setVoltage(0.5); - AnalogOutSim outputSim = new AnalogOutSim(0); + AnalogOutputSim outputSim = new AnalogOutputSim(output); DoubleStore store = new DoubleStore();