diff --git a/hal/src/generate/ResourceType.txt b/hal/src/generate/ResourceType.txt index f2f4dd9696..4c0348617e 100644 --- a/hal/src/generate/ResourceType.txt +++ b/hal/src/generate/ResourceType.txt @@ -89,3 +89,4 @@ kResourceType_Kinematics = 87 kResourceType_Odometry = 88 kResourceType_Units = 89 kResourceType_TrapezoidProfile = 90 +kResourceType_DutyCycle = 91 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 38e67a7750..449c06514c 100644 --- a/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java +++ b/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java @@ -7,8 +7,6 @@ package edu.wpi.first.hal; -import java.nio.IntBuffer; - public class AnalogJNI extends JNIWrapper { /** * native declaration : AthenaJava\target\native\include\HAL\Analog.h:58
enum values @@ -94,13 +92,18 @@ public class AnalogJNI extends JNIWrapper { public static native void getAccumulatorOutput(int analogPortHandle, AccumulatorResult result); - public static native int initializeAnalogTrigger(int analogInputHandle, IntBuffer index); + public static native int initializeAnalogTrigger(int analogInputHandle); + + public static native int initializeAnalogTriggerDutyCycle(int dutyCycleHandle); public static native void cleanAnalogTrigger(int analogTriggerHandle); public static native void setAnalogTriggerLimitsRaw(int analogTriggerHandle, int lower, int upper); + public static native void setAnalogTriggerLimitsDutyCycle(int analogTriggerHandle, double lower, + double higher); + public static native void setAnalogTriggerLimitsVoltage(int analogTriggerHandle, double lower, double upper); @@ -115,4 +118,7 @@ public class AnalogJNI extends JNIWrapper { public static native boolean getAnalogTriggerTriggerState(int analogTriggerHandle); public static native boolean getAnalogTriggerOutput(int analogTriggerHandle, int type); + + @SuppressWarnings("AbbreviationAsWordInName") + public static native int getAnalogTriggerFPGAIndex(int analogTriggerHandle); } diff --git a/hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java b/hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java new file mode 100644 index 0000000000..f0f93e117c --- /dev/null +++ b/hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java @@ -0,0 +1,21 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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. */ +/*----------------------------------------------------------------------------*/ + +package edu.wpi.first.hal; + +public class DutyCycleJNI extends JNIWrapper { + public static native int initialize(int digitalSourceHandle, int analogTriggerType); + public static native void free(int handle); + + public static native int getFrequency(int handle); + public static native double getOutput(int handle); + public static native int getOutputRaw(int handle); + public static native int getOutputScaleFactor(int handle); + + @SuppressWarnings("AbbreviationAsWordInName") + public static native int getFPGAIndex(int handle); +} diff --git a/hal/src/main/java/edu/wpi/first/hal/sim/DutyCycleSim.java b/hal/src/main/java/edu/wpi/first/hal/sim/DutyCycleSim.java new file mode 100644 index 0000000000..9b2806bfb1 --- /dev/null +++ b/hal/src/main/java/edu/wpi/first/hal/sim/DutyCycleSim.java @@ -0,0 +1,51 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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. */ +/*----------------------------------------------------------------------------*/ + +package edu.wpi.first.hal.sim; + +import edu.wpi.first.hal.sim.mockdata.DutyCycleDataJNI; + +public class DutyCycleSim { + private final int m_index; + + public DutyCycleSim(int index) { + m_index = index; + } + + public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) { + int uid = DutyCycleDataJNI.registerInitializedCallback(m_index, callback, initialNotify); + return new CallbackStore(m_index, uid, DutyCycleDataJNI::cancelInitializedCallback); + } + public boolean getInitialized() { + return DutyCycleDataJNI.getInitialized(m_index); + } + public void setInitialized(boolean initialized) { + DutyCycleDataJNI.setInitialized(m_index, initialized); + } + + public CallbackStore registerFrequencyCallback(NotifyCallback callback, boolean initialNotify) { + int uid = DutyCycleDataJNI.registerFrequencyCallback(m_index, callback, initialNotify); + return new CallbackStore(m_index, uid, DutyCycleDataJNI::cancelFrequencyCallback); + } + public int getFrequency() { + return DutyCycleDataJNI.getFrequency(m_index); + } + public void setFrequency(int frequency) { + DutyCycleDataJNI.setFrequency(m_index, frequency); + } + + public CallbackStore registerOutputCallback(NotifyCallback callback, boolean initialNotify) { + int uid = DutyCycleDataJNI.registerOutputCallback(m_index, callback, initialNotify); + return new CallbackStore(m_index, uid, DutyCycleDataJNI::cancelOutputCallback); + } + public double getOutput() { + return DutyCycleDataJNI.getOutput(m_index); + } + public void setOutput(double output) { + DutyCycleDataJNI.setOutput(m_index, output); + } +} diff --git a/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DutyCycleDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DutyCycleDataJNI.java new file mode 100644 index 0000000000..5cbae6efc7 --- /dev/null +++ b/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DutyCycleDataJNI.java @@ -0,0 +1,30 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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. */ +/*----------------------------------------------------------------------------*/ + +package edu.wpi.first.hal.sim.mockdata; + +import edu.wpi.first.hal.sim.NotifyCallback; +import edu.wpi.first.hal.JNIWrapper; + +public class DutyCycleDataJNI extends JNIWrapper { + 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 int registerFrequencyCallback(int index, NotifyCallback callback, boolean initialNotify); + public static native void cancelFrequencyCallback(int index, int uid); + public static native int getFrequency(int index); + public static native void setFrequency(int index, int frequency); + + public static native int registerOutputCallback(int index, NotifyCallback callback, boolean initialNotify); + public static native void cancelOutputCallback(int index, int uid); + public static native double getOutput(int index); + public static native void setOutput(int index, double output); + + public static native void resetData(int index); +} diff --git a/hal/src/main/native/athena/AnalogTrigger.cpp b/hal/src/main/native/athena/AnalogTrigger.cpp index 1841c51161..99a0d68a86 100644 --- a/hal/src/main/native/athena/AnalogTrigger.cpp +++ b/hal/src/main/native/athena/AnalogTrigger.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 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. */ @@ -8,9 +8,11 @@ #include "hal/AnalogTrigger.h" #include "AnalogInternal.h" +#include "DutyCycleInternal.h" #include "HALInitializer.h" #include "PortsInternal.h" #include "hal/AnalogInput.h" +#include "hal/DutyCycle.h" #include "hal/Errors.h" #include "hal/handles/HandlesInternal.h" #include "hal/handles/LimitedHandleResource.h" @@ -21,7 +23,7 @@ namespace { struct AnalogTrigger { std::unique_ptr trigger; - HAL_AnalogInputHandle analogHandle; + HAL_Handle handle; uint8_t index; }; @@ -46,7 +48,7 @@ void InitializeAnalogTrigger() { extern "C" { HAL_AnalogTriggerHandle HAL_InitializeAnalogTrigger( - HAL_AnalogInputHandle portHandle, int32_t* index, int32_t* status) { + HAL_AnalogInputHandle portHandle, int32_t* status) { hal::init::CheckInit(); // ensure we are given a valid and active AnalogInput handle auto analog_port = analogInputHandles->Get(portHandle); @@ -64,19 +66,46 @@ HAL_AnalogTriggerHandle HAL_InitializeAnalogTrigger( *status = HAL_HANDLE_ERROR; return HAL_kInvalidHandle; } - trigger->analogHandle = portHandle; + trigger->handle = portHandle; trigger->index = static_cast(getHandleIndex(handle)); - *index = trigger->index; trigger->trigger.reset(tAnalogTrigger::create(trigger->index, status)); trigger->trigger->writeSourceSelect_Channel(analog_port->channel, status); return handle; } +HAL_AnalogTriggerHandle HAL_InitializeAnalogTriggerDutyCycle( + HAL_DutyCycleHandle dutyCycleHandle, int32_t* status) { + hal::init::CheckInit(); + // ensure we are given a valid and active DutyCycle handle + auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle); + if (dutyCycle == nullptr) { + *status = HAL_HANDLE_ERROR; + return HAL_kInvalidHandle; + } + HAL_AnalogTriggerHandle handle = analogTriggerHandles->Allocate(); + if (handle == HAL_kInvalidHandle) { + *status = NO_AVAILABLE_RESOURCES; + return HAL_kInvalidHandle; + } + auto trigger = analogTriggerHandles->Get(handle); + if (trigger == nullptr) { // would only occur on thread issue + *status = HAL_HANDLE_ERROR; + return HAL_kInvalidHandle; + } + trigger->handle = dutyCycleHandle; + trigger->index = static_cast(getHandleIndex(handle)); + + trigger->trigger.reset(tAnalogTrigger::create(trigger->index, status)); + trigger->trigger->writeSourceSelect_Channel(dutyCycle->index, status); + trigger->trigger->writeSourceSelect_DutyCycle(true, status); + return handle; +} + void HAL_CleanAnalogTrigger(HAL_AnalogTriggerHandle analogTriggerHandle, int32_t* status) { analogTriggerHandles->Free(analogTriggerHandle); - // caller owns the analog input handle. + // caller owns the input handle. } void HAL_SetAnalogTriggerLimitsRaw(HAL_AnalogTriggerHandle analogTriggerHandle, @@ -89,11 +118,46 @@ void HAL_SetAnalogTriggerLimitsRaw(HAL_AnalogTriggerHandle analogTriggerHandle, } if (lower > upper) { *status = ANALOG_TRIGGER_LIMIT_ORDER_ERROR; + return; } trigger->trigger->writeLowerLimit(lower, status); trigger->trigger->writeUpperLimit(upper, status); } +void HAL_SetAnalogTriggerLimitsDutyCycle( + HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper, + int32_t* status) { + auto trigger = analogTriggerHandles->Get(analogTriggerHandle); + if (trigger == nullptr) { + *status = HAL_HANDLE_ERROR; + return; + } + if (getHandleType(trigger->handle) != HAL_HandleEnum::DutyCycle) { + *status = HAL_HANDLE_ERROR; + return; + } + if (lower > upper) { + *status = ANALOG_TRIGGER_LIMIT_ORDER_ERROR; + return; + } + + if (lower < 0.0 || upper > 1.0) { + *status = PARAMETER_OUT_OF_RANGE; + return; + } + + int32_t scaleFactor = + HAL_GetDutyCycleOutputScaleFactor(trigger->handle, status); + if (*status != 0) { + return; + } + + trigger->trigger->writeLowerLimit(static_cast(scaleFactor * lower), + status); + trigger->trigger->writeLowerLimit(static_cast(scaleFactor * upper), + status); +} + void HAL_SetAnalogTriggerLimitsVoltage( HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper, int32_t* status) { @@ -102,16 +166,22 @@ void HAL_SetAnalogTriggerLimitsVoltage( *status = HAL_HANDLE_ERROR; return; } + + if (getHandleType(trigger->handle) != HAL_HandleEnum::AnalogInput) { + *status = HAL_HANDLE_ERROR; + return; + } if (lower > upper) { *status = ANALOG_TRIGGER_LIMIT_ORDER_ERROR; + return; } // TODO: This depends on the averaged setting. Only raw values will work as // is. trigger->trigger->writeLowerLimit( - HAL_GetAnalogVoltsToValue(trigger->analogHandle, lower, status), status); + HAL_GetAnalogVoltsToValue(trigger->handle, lower, status), status); trigger->trigger->writeUpperLimit( - HAL_GetAnalogVoltsToValue(trigger->analogHandle, upper, status), status); + HAL_GetAnalogVoltsToValue(trigger->handle, upper, status), status); } void HAL_SetAnalogTriggerAveraged(HAL_AnalogTriggerHandle analogTriggerHandle, @@ -121,7 +191,8 @@ void HAL_SetAnalogTriggerAveraged(HAL_AnalogTriggerHandle analogTriggerHandle, *status = HAL_HANDLE_ERROR; return; } - if (trigger->trigger->readSourceSelect_Filter(status) != 0) { + if (trigger->trigger->readSourceSelect_Filter(status) != 0 || + trigger->trigger->readSourceSelect_DutyCycle(status) != 0) { *status = INCOMPATIBLE_STATE; // TODO: wpi_setWPIErrorWithContext(IncompatibleMode, "Hardware does not // support average and filtering at the same time."); @@ -136,7 +207,8 @@ void HAL_SetAnalogTriggerFiltered(HAL_AnalogTriggerHandle analogTriggerHandle, *status = HAL_HANDLE_ERROR; return; } - if (trigger->trigger->readSourceSelect_Averaged(status) != 0) { + if (trigger->trigger->readSourceSelect_Averaged(status) != 0 || + trigger->trigger->readSourceSelect_DutyCycle(status) != 0) { *status = INCOMPATIBLE_STATE; // TODO: wpi_setWPIErrorWithContext(IncompatibleMode, "Hardware does not " // "support average and filtering at the same time."); @@ -177,16 +249,28 @@ HAL_Bool HAL_GetAnalogTriggerOutput(HAL_AnalogTriggerHandle analogTriggerHandle, case HAL_Trigger_kInWindow: result = trigger->trigger->readOutput_InHysteresis(trigger->index, status); - break; // XXX: Backport + break; case HAL_Trigger_kState: result = trigger->trigger->readOutput_OverLimit(trigger->index, status); - break; // XXX: Backport + break; case HAL_Trigger_kRisingPulse: + result = trigger->trigger->readOutput_Rising(trigger->index, status); + break; case HAL_Trigger_kFallingPulse: - *status = ANALOG_TRIGGER_PULSE_OUTPUT_ERROR; - return false; + result = trigger->trigger->readOutput_Falling(trigger->index, status); + break; } return result; } +int32_t HAL_GetAnalogTriggerFPGAIndex( + HAL_AnalogTriggerHandle analogTriggerHandle, int32_t* status) { + auto trigger = analogTriggerHandles->Get(analogTriggerHandle); + if (trigger == nullptr) { + *status = HAL_HANDLE_ERROR; + return -1; + } + return trigger->index; +} + } // extern "C" diff --git a/hal/src/main/native/athena/DutyCycle.cpp b/hal/src/main/native/athena/DutyCycle.cpp new file mode 100644 index 0000000000..5553f0d2b8 --- /dev/null +++ b/hal/src/main/native/athena/DutyCycle.cpp @@ -0,0 +1,119 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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. */ +/*----------------------------------------------------------------------------*/ + +#include "hal/DutyCycle.h" + +#include + +#include "DigitalInternal.h" +#include "DutyCycleInternal.h" +#include "HALInitializer.h" +#include "PortsInternal.h" +#include "hal/ChipObject.h" +#include "hal/Errors.h" +#include "hal/handles/HandlesInternal.h" +#include "hal/handles/LimitedHandleResource.h" + +using namespace hal; + +namespace hal { +LimitedHandleResource* dutyCycleHandles; +namespace init { +void InitializeDutyCycle() { + static LimitedHandleResource + dcH; + dutyCycleHandles = &dcH; +} +} // namespace init +} // namespace hal + +static constexpr int32_t kScaleFactor = 4e7 - 1; + +extern "C" { +HAL_DutyCycleHandle HAL_InitializeDutyCycle(HAL_Handle digitalSourceHandle, + HAL_AnalogTriggerType triggerType, + int32_t* status) { + hal::init::CheckInit(); + + bool routingAnalogTrigger = false; + uint8_t routingChannel = 0; + uint8_t routingModule = 0; + bool success = + remapDigitalSource(digitalSourceHandle, triggerType, routingChannel, + routingModule, routingAnalogTrigger); + + if (!success) { + *status = HAL_HANDLE_ERROR; + return HAL_kInvalidHandle; + } + + HAL_DutyCycleHandle handle = dutyCycleHandles->Allocate(); + if (handle == HAL_kInvalidHandle) { + *status = NO_AVAILABLE_RESOURCES; + return HAL_kInvalidHandle; + } + + auto dutyCycle = dutyCycleHandles->Get(handle); + uint32_t index = static_cast(getHandleIndex(handle)); + dutyCycle->dutyCycle.reset(tDutyCycle::create(index, status)); + + dutyCycle->dutyCycle->writeSource_AnalogTrigger(routingAnalogTrigger, status); + dutyCycle->dutyCycle->writeSource_Channel(routingChannel, status); + dutyCycle->dutyCycle->writeSource_Module(routingModule, status); + dutyCycle->index = index; + + return handle; +} +void HAL_FreeDutyCycle(HAL_DutyCycleHandle dutyCycleHandle) { + // Just free it, the unique ptr will take care of everything else + dutyCycleHandles->Free(dutyCycleHandle); +} + +int32_t HAL_GetDutyCycleFrequency(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status) { + auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle); + if (!dutyCycle) { + *status = HAL_HANDLE_ERROR; + return 0; + } + + return dutyCycle->dutyCycle->readFrequency(status); +} + +double HAL_GetDutyCycleOutput(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status) { + return HAL_GetDutyCycleOutputRaw(dutyCycleHandle, status) / kScaleFactor; +} + +int32_t HAL_GetDutyCycleOutputRaw(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status) { + auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle); + if (!dutyCycle) { + *status = HAL_HANDLE_ERROR; + return 0; + } + + return dutyCycle->dutyCycle->readOutput(status); +} + +int32_t HAL_GetDutyCycleOutputScaleFactor(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status) { + return kScaleFactor; +} + +int32_t HAL_GetDutyCycleFPGAIndex(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status) { + auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle); + if (!dutyCycle) { + *status = HAL_HANDLE_ERROR; + return -1; + } + return dutyCycle->index; +} +} // extern "C" diff --git a/hal/src/main/native/athena/DutyCycleInternal.h b/hal/src/main/native/athena/DutyCycleInternal.h new file mode 100644 index 0000000000..33a8ff2972 --- /dev/null +++ b/hal/src/main/native/athena/DutyCycleInternal.h @@ -0,0 +1,24 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 "hal/ChipObject.h" +#include "hal/handles/HandlesInternal.h" +#include "hal/handles/LimitedHandleResource.h" + +namespace hal { +struct DutyCycle { + std::unique_ptr dutyCycle; + int index; +}; + +extern LimitedHandleResource* dutyCycleHandles; +} // namespace hal diff --git a/hal/src/main/native/athena/HAL.cpp b/hal/src/main/native/athena/HAL.cpp index a9abde690b..149e708f45 100644 --- a/hal/src/main/native/athena/HAL.cpp +++ b/hal/src/main/native/athena/HAL.cpp @@ -56,6 +56,7 @@ void InitializeHAL() { InitializeCounter(); InitializeDigitalInternal(); InitializeDIO(); + InitializeDutyCycle(); InitializeEncoder(); InitializeFPGAEncoder(); InitializeFRCDriverStation(); diff --git a/hal/src/main/native/athena/HALInitializer.h b/hal/src/main/native/athena/HALInitializer.h index fc38038669..22c1dcb705 100644 --- a/hal/src/main/native/athena/HALInitializer.h +++ b/hal/src/main/native/athena/HALInitializer.h @@ -32,6 +32,7 @@ extern void InitializeConstants(); extern void InitializeCounter(); extern void InitializeDigitalInternal(); extern void InitializeDIO(); +extern void InitializeDutyCycle(); extern void InitializeEncoder(); extern void InitializeFPGAEncoder(); extern void InitializeFRCDriverStation(); diff --git a/hal/src/main/native/athena/Ports.cpp b/hal/src/main/native/athena/Ports.cpp index 9a527368da..525acac91d 100644 --- a/hal/src/main/native/athena/Ports.cpp +++ b/hal/src/main/native/athena/Ports.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 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. */ @@ -37,5 +37,6 @@ int32_t HAL_GetNumPCMModules(void) { return kNumPCMModules; } int32_t HAL_GetNumSolenoidChannels(void) { return kNumSolenoidChannels; } int32_t HAL_GetNumPDPModules(void) { return kNumPDPModules; } int32_t HAL_GetNumPDPChannels(void) { return kNumPDPChannels; } +int32_t HAL_GetNumDutyCycles(void) { return kNumDutyCycles; } } // extern "C" diff --git a/hal/src/main/native/athena/PortsInternal.h b/hal/src/main/native/athena/PortsInternal.h index b3eb6b0ed6..846bda0d59 100644 --- a/hal/src/main/native/athena/PortsInternal.h +++ b/hal/src/main/native/athena/PortsInternal.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 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. */ @@ -35,5 +35,6 @@ constexpr int32_t kNumPCMModules = 63; constexpr int32_t kNumSolenoidChannels = 8; constexpr int32_t kNumPDPModules = 63; constexpr int32_t kNumPDPChannels = 16; +constexpr int32_t kNumDutyCycles = 8; } // namespace hal diff --git a/hal/src/main/native/cpp/jni/AnalogJNI.cpp b/hal/src/main/native/cpp/jni/AnalogJNI.cpp index abd614f0ca..5571d55453 100644 --- a/hal/src/main/native/cpp/jni/AnalogJNI.cpp +++ b/hal/src/main/native/cpp/jni/AnalogJNI.cpp @@ -486,18 +486,31 @@ Java_edu_wpi_first_hal_AnalogJNI_getAccumulatorOutput /* * Class: edu_wpi_first_hal_AnalogJNI * Method: initializeAnalogTrigger - * Signature: (ILjava/lang/Object;)I + * Signature: (I)I */ JNIEXPORT jint JNICALL Java_edu_wpi_first_hal_AnalogJNI_initializeAnalogTrigger - (JNIEnv* env, jclass, jint id, jobject index) + (JNIEnv* env, jclass, jint id) { - jint* indexHandle = - reinterpret_cast(env->GetDirectBufferAddress(index)); int32_t status = 0; - HAL_AnalogTriggerHandle analogTrigger = HAL_InitializeAnalogTrigger( - (HAL_AnalogInputHandle)id, reinterpret_cast(indexHandle), - &status); + HAL_AnalogTriggerHandle analogTrigger = + HAL_InitializeAnalogTrigger((HAL_AnalogInputHandle)id, &status); + CheckStatus(env, status); + return (jint)analogTrigger; +} + +/* + * Class: edu_wpi_first_hal_AnalogJNI + * Method: initializeAnalogTriggerDutyCycle + * Signature: (I)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_AnalogJNI_initializeAnalogTriggerDutyCycle + (JNIEnv* env, jclass, jint id) +{ + int32_t status = 0; + HAL_AnalogTriggerHandle analogTrigger = + HAL_InitializeAnalogTriggerDutyCycle((HAL_DutyCycleHandle)id, &status); CheckStatus(env, status); return (jint)analogTrigger; } @@ -531,6 +544,21 @@ Java_edu_wpi_first_hal_AnalogJNI_setAnalogTriggerLimitsRaw CheckStatus(env, status); } +/* + * Class: edu_wpi_first_hal_AnalogJNI + * Method: setAnalogTriggerLimitsDutyCycle + * Signature: (IDD)V + */ +JNIEXPORT void JNICALL +Java_edu_wpi_first_hal_AnalogJNI_setAnalogTriggerLimitsDutyCycle + (JNIEnv* env, jclass, jint id, jdouble lower, jdouble upper) +{ + int32_t status = 0; + HAL_SetAnalogTriggerLimitsDutyCycle((HAL_AnalogTriggerHandle)id, lower, upper, + &status); + CheckStatus(env, status); +} + /* * Class: edu_wpi_first_hal_AnalogJNI * Method: setAnalogTriggerLimitsVoltage @@ -622,4 +650,20 @@ Java_edu_wpi_first_hal_AnalogJNI_getAnalogTriggerOutput return val; } +/* + * Class: edu_wpi_first_hal_AnalogJNI + * Method: getAnalogTriggerFPGAIndex + * Signature: (I)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_AnalogJNI_getAnalogTriggerFPGAIndex + (JNIEnv* env, jclass, jint id) +{ + int32_t status = 0; + auto val = + HAL_GetAnalogTriggerFPGAIndex((HAL_AnalogTriggerHandle)id, &status); + CheckStatus(env, status); + return val; +} + } // extern "C" diff --git a/hal/src/main/native/cpp/jni/DutyCycleJNI.cpp b/hal/src/main/native/cpp/jni/DutyCycleJNI.cpp new file mode 100644 index 0000000000..510ca009c0 --- /dev/null +++ b/hal/src/main/native/cpp/jni/DutyCycleJNI.cpp @@ -0,0 +1,126 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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. */ +/*----------------------------------------------------------------------------*/ + +#include + +#include "HALUtil.h" +#include "edu_wpi_first_hal_DutyCycleJNI.h" +#include "hal/DutyCycle.h" + +using namespace frc; + +extern "C" { +/* + * Class: edu_wpi_first_hal_DutyCycleJNI + * Method: initialize + * Signature: (II)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_DutyCycleJNI_initialize + (JNIEnv* env, jclass, jint digitalSourceHandle, jint analogTriggerType) +{ + int32_t status = 0; + auto handle = HAL_InitializeDutyCycle( + static_cast(digitalSourceHandle), + static_cast(analogTriggerType), &status); + CheckStatus(env, status); + return handle; +} + +/* + * Class: edu_wpi_first_hal_DutyCycleJNI + * Method: free + * Signature: (I)V + */ +JNIEXPORT void JNICALL +Java_edu_wpi_first_hal_DutyCycleJNI_free + (JNIEnv*, jclass, jint handle) +{ + HAL_FreeDutyCycle(static_cast(handle)); +} + +/* + * Class: edu_wpi_first_hal_DutyCycleJNI + * Method: getFrequency + * Signature: (I)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_DutyCycleJNI_getFrequency + (JNIEnv* env, jclass, jint handle) +{ + int32_t status = 0; + auto retVal = HAL_GetDutyCycleFrequency( + static_cast(handle), &status); + CheckStatus(env, status); + return retVal; +} + +/* + * Class: edu_wpi_first_hal_DutyCycleJNI + * Method: getOutput + * Signature: (I)D + */ +JNIEXPORT jdouble JNICALL +Java_edu_wpi_first_hal_DutyCycleJNI_getOutput + (JNIEnv* env, jclass, jint handle) +{ + int32_t status = 0; + auto retVal = + HAL_GetDutyCycleOutput(static_cast(handle), &status); + CheckStatus(env, status); + return retVal; +} + +/* + * Class: edu_wpi_first_hal_DutyCycleJNI + * Method: getOutputRaw + * Signature: (I)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_DutyCycleJNI_getOutputRaw + (JNIEnv* env, jclass, jint handle) +{ + int32_t status = 0; + auto retVal = HAL_GetDutyCycleOutputRaw( + static_cast(handle), &status); + CheckStatus(env, status); + return retVal; +} + +/* + * Class: edu_wpi_first_hal_DutyCycleJNI + * Method: getOutputScaleFactor + * Signature: (I)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_DutyCycleJNI_getOutputScaleFactor + (JNIEnv* env, jclass, jint handle) +{ + int32_t status = 0; + auto retVal = HAL_GetDutyCycleOutputScaleFactor( + static_cast(handle), &status); + CheckStatus(env, status); + return retVal; +} + +/* + * Class: edu_wpi_first_hal_DutyCycleJNI + * Method: getFPGAIndex + * Signature: (I)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_DutyCycleJNI_getFPGAIndex + (JNIEnv* env, jclass, jint handle) +{ + int32_t status = 0; + auto retVal = HAL_GetDutyCycleFPGAIndex( + static_cast(handle), &status); + CheckStatus(env, status); + return retVal; +} + +} // extern "C" diff --git a/hal/src/main/native/include/hal/AnalogTrigger.h b/hal/src/main/native/include/hal/AnalogTrigger.h index f461f1dbd6..85d7680aec 100644 --- a/hal/src/main/native/include/hal/AnalogTrigger.h +++ b/hal/src/main/native/include/hal/AnalogTrigger.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 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. */ @@ -37,11 +37,17 @@ extern "C" { * Initializes an analog trigger. * * @param portHandle the analog input to use for triggering - * @param index the trigger index value (output) * @return the created analog trigger handle */ HAL_AnalogTriggerHandle HAL_InitializeAnalogTrigger( - HAL_AnalogInputHandle portHandle, int32_t* index, int32_t* status); + HAL_AnalogInputHandle portHandle, int32_t* status); + +/** + * Initializes an analog trigger with a Duty Cycle input + * + */ +HAL_AnalogTriggerHandle HAL_InitializeAnalogTriggerDutyCycle( + HAL_DutyCycleHandle dutyCycleHandle, int32_t* status); /** * Frees an analog trigger. @@ -54,7 +60,8 @@ void HAL_CleanAnalogTrigger(HAL_AnalogTriggerHandle analogTriggerHandle, /** * Sets the raw ADC upper and lower limits of the analog trigger. * - * HAL_SetAnalogTriggerLimitsVoltage is likely better in most cases. + * HAL_SetAnalogTriggerLimitsVoltage or HAL_SetAnalogTriggerLimitsDutyCycle + * is likely better in most cases. * * @param analogTriggerHandle the trigger handle * @param lower the lower ADC value @@ -77,12 +84,19 @@ void HAL_SetAnalogTriggerLimitsVoltage( HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper, int32_t* status); +void HAL_SetAnalogTriggerLimitsDutyCycle( + HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper, + int32_t* status); + /** * Configures the analog trigger to use the averaged vs. raw values. * * If the value is true, then the averaged value is selected for the analog * trigger, otherwise the immediate value is used. * + * This is not allowed to be used if filtered mode is set. + * This is not allowed to be used with Duty Cycle based inputs. + * * @param analogTriggerHandle the trigger handle * @param useAveragedValue true to use averaged values, false for raw */ @@ -96,6 +110,8 @@ void HAL_SetAnalogTriggerAveraged(HAL_AnalogTriggerHandle analogTriggerHandle, * is designed to help with 360 degree pot applications for the period where the * pot crosses through zero. * + * This is not allowed to be used if averaged mode is set. + * * @param analogTriggerHandle the trigger handle * @param useFilteredValue true to use filtered values, false for average or * raw @@ -137,6 +153,15 @@ HAL_Bool HAL_GetAnalogTriggerTriggerState( HAL_Bool HAL_GetAnalogTriggerOutput(HAL_AnalogTriggerHandle analogTriggerHandle, HAL_AnalogTriggerType type, int32_t* status); + +/** + * Get the FPGA index for the AnlogTrigger. + * + * @param analogTriggerHandle the trigger handle + * @return the FPGA index + */ +int32_t HAL_GetAnalogTriggerFPGAIndex( + HAL_AnalogTriggerHandle analogTriggerHandle, int32_t* status); #ifdef __cplusplus } // extern "C" #endif diff --git a/hal/src/main/native/include/hal/ChipObject.h b/hal/src/main/native/include/hal/ChipObject.h index 878595b96c..5e4bed10a8 100644 --- a/hal/src/main/native/include/hal/ChipObject.h +++ b/hal/src/main/native/include/hal/ChipObject.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 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. */ @@ -24,6 +24,7 @@ #include #include #include +#include #include #include #include diff --git a/hal/src/main/native/include/hal/DutyCycle.h b/hal/src/main/native/include/hal/DutyCycle.h new file mode 100644 index 0000000000..dfe9ed6731 --- /dev/null +++ b/hal/src/main/native/include/hal/DutyCycle.h @@ -0,0 +1,102 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 "hal/AnalogTrigger.h" +#include "hal/Types.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Initialize a DutyCycle input. + * + * @param digitalSourceHandle the digital source to use (either a + * HAL_DigitalHandle or a HAL_AnalogTriggerHandle) + * @param triggerType the analog trigger type of the source if it is + * an analog trigger + * @return thre created duty cycle handle + */ +HAL_DutyCycleHandle HAL_InitializeDutyCycle(HAL_Handle digitalSourceHandle, + HAL_AnalogTriggerType triggerType, + int32_t* status); + +/** + * Free a DutyCycle. + * + * @param dutyCycleHandle the duty cycle handle + */ +void HAL_FreeDutyCycle(HAL_DutyCycleHandle dutyCycleHandle); + +/** + * Indicates the duty cycle is used by a simulated device. + * + * @param handle the duty cycle handle + * @param device simulated device handle + */ +void HAL_SetDutyCycleSimDevice(HAL_DutyCycleHandle handle, + HAL_SimDeviceHandle device); + +/** + * Get the frequency of the duty cycle signal. + * + * @param dutyCycleHandle the duty cycle handle + * @return frequency in Hertz + */ +int32_t HAL_GetDutyCycleFrequency(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status); + +/** + * Get the output ratio of the duty cycle signal. + * + *

0 means always low, 1 means always high. + * + * @param dutyCycleHandle the duty cycle handle + * @return output ratio between 0 and 1 + */ +double HAL_GetDutyCycleOutput(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status); + +/** + * Get the raw output ratio of the duty cycle signal. + * + *

0 means always low, an output equal to + * GetOutputScaleFactor() means always high. + * + * @param dutyCycleHandle the duty cycle handle + * @return output ratio in raw units + */ +int32_t HAL_GetDutyCycleOutputRaw(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status); + +/** + * Get the scale factor of the output. + * + *

An output equal to this value is always high, and then linearly scales + * down to 0. Divide the result of getOutputRaw by this in order to get the + * percentage between 0 and 1. + * + * @param dutyCycleHandle the duty cycle handle + * @return the output scale factor + */ +int32_t HAL_GetDutyCycleOutputScaleFactor(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status); + +/** + * Get the FPGA index for the DutyCycle. + * + * @param dutyCycleHandle the duty cycle handle + * @return the FPGA index + */ +int32_t HAL_GetDutyCycleFPGAIndex(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status); + +#ifdef __cplusplus +} // extern "C" +#endif diff --git a/hal/src/main/native/include/hal/Errors.h b/hal/src/main/native/include/hal/Errors.h index 4476ab0318..761c2cfb1d 100644 --- a/hal/src/main/native/include/hal/Errors.h +++ b/hal/src/main/native/include/hal/Errors.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 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. */ @@ -117,6 +117,9 @@ #define HAL_CAN_TIMEOUT -1154 #define HAL_CAN_TIMEOUT_MESSAGE "HAL: CAN Receive has Timed Out" +#define HAL_SIM_NOT_SUPPORTED -1155 +#define HAL_SIM_NOT_SUPPORTED_MESSAGE "HAL: Method not supported in sim" + #define VI_ERROR_SYSTEM_ERROR_MESSAGE "HAL - VISA: System Error"; #define VI_ERROR_INV_OBJECT_MESSAGE "HAL - VISA: Invalid Object" #define VI_ERROR_RSRC_LOCKED_MESSAGE "HAL - VISA: Resource Locked" diff --git a/hal/src/main/native/include/hal/Ports.h b/hal/src/main/native/include/hal/Ports.h index 9b29817fe0..1992cdb31c 100644 --- a/hal/src/main/native/include/hal/Ports.h +++ b/hal/src/main/native/include/hal/Ports.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 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. */ @@ -144,6 +144,13 @@ int32_t HAL_GetNumPDPModules(void); * @return the number of PDP channels */ int32_t HAL_GetNumPDPChannels(void); + +/** + * Gets the number of duty cycle inputs in the current system. + * + * @return the number of Duty Cycle inputs + */ +int32_t HAL_GetNumDutyCycles(void); #ifdef __cplusplus } // extern "C" #endif diff --git a/hal/src/main/native/include/hal/Types.h b/hal/src/main/native/include/hal/Types.h index 5ce600933a..b96f994abf 100644 --- a/hal/src/main/native/include/hal/Types.h +++ b/hal/src/main/native/include/hal/Types.h @@ -57,6 +57,8 @@ typedef HAL_Handle HAL_SimDeviceHandle; typedef HAL_Handle HAL_SimValueHandle; +typedef HAL_Handle HAL_DutyCycleHandle; + typedef HAL_CANHandle HAL_PDPHandle; typedef int32_t HAL_Bool; diff --git a/hal/src/main/native/include/hal/handles/HandlesInternal.h b/hal/src/main/native/include/hal/handles/HandlesInternal.h index 5340d82fcf..f722ef43fc 100644 --- a/hal/src/main/native/include/hal/handles/HandlesInternal.h +++ b/hal/src/main/native/include/hal/handles/HandlesInternal.h @@ -66,6 +66,7 @@ enum class HAL_HandleEnum { SimulationJni = 18, CAN = 19, SerialPort = 20, + DutyCycle = 21 }; /** diff --git a/hal/src/main/native/include/mockdata/AnalogTriggerData.h b/hal/src/main/native/include/mockdata/AnalogTriggerData.h index 7f06c2e626..566f2f531a 100644 --- a/hal/src/main/native/include/mockdata/AnalogTriggerData.h +++ b/hal/src/main/native/include/mockdata/AnalogTriggerData.h @@ -13,6 +13,7 @@ enum HALSIM_AnalogTriggerMode : int32_t { HALSIM_AnalogTriggerUnassigned, HALSIM_AnalogTriggerFiltered, + HALSIM_AnalogTriggerDutyCycle, HALSIM_AnalogTriggerAveraged }; diff --git a/hal/src/main/native/include/mockdata/DutyCycleData.h b/hal/src/main/native/include/mockdata/DutyCycleData.h new file mode 100644 index 0000000000..b97b355131 --- /dev/null +++ b/hal/src/main/native/include/mockdata/DutyCycleData.h @@ -0,0 +1,52 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 "NotifyListener.h" +#include "hal/Types.h" + +#ifdef __cplusplus +extern "C" { +#endif + +void HALSIM_ResetDutyCycleData(int32_t index); +int32_t HALSIM_GetDutyCycleDigitalChannel(int32_t index); + +int32_t HALSIM_RegisterDutyCycleInitializedCallback(int32_t index, + HAL_NotifyCallback callback, + void* param, + HAL_Bool initialNotify); +void HALSIM_CancelDutyCycleInitializedCallback(int32_t index, int32_t uid); +HAL_Bool HALSIM_GetDutyCycleInitialized(int32_t index); +void HALSIM_SetDutyCycleInitialized(int32_t index, HAL_Bool initialized); + +HAL_SimDeviceHandle HALSIM_GetDutyCycleSimDevice(int32_t index); + +int32_t HALSIM_RegisterDutyCycleOutputCallback(int32_t index, + HAL_NotifyCallback callback, + void* param, + HAL_Bool initialNotify); +void HALSIM_CancelDutyCycleOutputCallback(int32_t index, int32_t uid); +double HALSIM_GetDutyCycleOutput(int32_t index); +void HALSIM_SetDutyCycleOutput(int32_t index, double output); + +int32_t HALSIM_RegisterDutyCycleFrequencyCallback(int32_t index, + HAL_NotifyCallback callback, + void* param, + HAL_Bool initialNotify); +void HALSIM_CancelDutyCycleFrequencyCallback(int32_t index, int32_t uid); +int32_t HALSIM_GetDutyCycleFrequency(int32_t index); +void HALSIM_SetDutyCycleFrequency(int32_t index, int32_t frequency); + +void HALSIM_RegisterDutyCycleAllCallbacks(int32_t index, + HAL_NotifyCallback callback, + void* param, HAL_Bool initialNotify); + +#ifdef __cplusplus +} // extern "C" +#endif diff --git a/hal/src/main/native/include/simulation/DutyCycleSim.h b/hal/src/main/native/include/simulation/DutyCycleSim.h new file mode 100644 index 0000000000..f55dfc96f1 --- /dev/null +++ b/hal/src/main/native/include/simulation/DutyCycleSim.h @@ -0,0 +1,71 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 "CallbackStore.h" +#include "mockdata/DutyCycleData.h" + +namespace frc { +namespace sim { +class DutyCycleSim { + public: + explicit DutyCycleSim(int index) { m_index = index; } + + std::unique_ptr RegisterInitializedCallback( + NotifyCallback callback, bool initialNotify) { + auto store = std::make_unique( + m_index, -1, callback, &HALSIM_CancelDutyCycleInitializedCallback); + store->SetUid(HALSIM_RegisterDutyCycleInitializedCallback( + m_index, &CallbackStoreThunk, store.get(), initialNotify)); + return store; + } + + bool GetInitialized() const { + return HALSIM_GetDutyCycleInitialized(m_index); + } + + void SetInitialized(bool initialized) { + HALSIM_SetDutyCycleInitialized(m_index, initialized); + } + + std::unique_ptr RegisterFrequencyCallback( + NotifyCallback callback, bool initialNotify) { + auto store = std::make_unique( + m_index, -1, callback, &HALSIM_CancelDutyCycleFrequencyCallback); + store->SetUid(HALSIM_RegisterDutyCycleFrequencyCallback( + m_index, &CallbackStoreThunk, store.get(), initialNotify)); + return store; + } + + int GetFrequency() const { return HALSIM_GetDutyCycleFrequency(m_index); } + + void SetFrequency(int count) { HALSIM_SetDutyCycleFrequency(m_index, count); } + + std::unique_ptr RegisterOutputCallback(NotifyCallback callback, + bool initialNotify) { + auto store = std::make_unique( + m_index, -1, callback, &HALSIM_CancelDutyCycleOutputCallback); + store->SetUid(HALSIM_RegisterDutyCycleOutputCallback( + m_index, &CallbackStoreThunk, store.get(), initialNotify)); + return store; + } + + double GetOutput() const { return HALSIM_GetDutyCycleOutput(m_index); } + + void SetOutput(double period) { HALSIM_SetDutyCycleOutput(m_index, period); } + + void ResetData() { HALSIM_ResetDutyCycleData(m_index); } + + private: + int m_index; +}; +} // namespace sim +} // namespace frc diff --git a/hal/src/main/native/sim/AnalogTrigger.cpp b/hal/src/main/native/sim/AnalogTrigger.cpp index 53b165c60d..4415803700 100644 --- a/hal/src/main/native/sim/AnalogTrigger.cpp +++ b/hal/src/main/native/sim/AnalogTrigger.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2017-2019 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. */ @@ -63,7 +63,7 @@ int32_t hal::GetAnalogTriggerInputIndex(HAL_AnalogTriggerHandle handle, extern "C" { HAL_AnalogTriggerHandle HAL_InitializeAnalogTrigger( - HAL_AnalogInputHandle portHandle, int32_t* index, int32_t* status) { + HAL_AnalogInputHandle portHandle, int32_t* status) { hal::init::CheckInit(); // ensure we are given a valid and active AnalogInput handle auto analog_port = analogInputHandles->Get(portHandle); @@ -83,7 +83,6 @@ HAL_AnalogTriggerHandle HAL_InitializeAnalogTrigger( } trigger->analogHandle = portHandle; trigger->index = static_cast(getHandleIndex(handle)); - *index = trigger->index; SimAnalogTriggerData[trigger->index].initialized = true; @@ -92,6 +91,12 @@ HAL_AnalogTriggerHandle HAL_InitializeAnalogTrigger( return handle; } +HAL_AnalogTriggerHandle HAL_InitializeAnalogTriggerDutyCycle( + HAL_DutyCycleHandle dutyCycleHandle, int32_t* status) { + *status = HAL_SIM_NOT_SUPPORTED; + return HAL_kInvalidHandle; +} + void HAL_CleanAnalogTrigger(HAL_AnalogTriggerHandle analogTriggerHandle, int32_t* status) { auto trigger = analogTriggerHandles->Get(analogTriggerHandle); @@ -133,6 +138,13 @@ void HAL_SetAnalogTriggerLimitsRaw(HAL_AnalogTriggerHandle analogTriggerHandle, SimAnalogTriggerData[trigger->index].triggerUpperBound = trigUpper; SimAnalogTriggerData[trigger->index].triggerLowerBound = trigLower; } + +void HAL_SetAnalogTriggerLimitsDutyCycle( + HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper, + int32_t* status) { + *status = HAL_SIM_NOT_SUPPORTED; +} + void HAL_SetAnalogTriggerLimitsVoltage( HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper, int32_t* status) { @@ -158,7 +170,7 @@ void HAL_SetAnalogTriggerAveraged(HAL_AnalogTriggerHandle analogTriggerHandle, AnalogTriggerData* triggerData = &SimAnalogTriggerData[trigger->index]; - if (triggerData->triggerMode.Get() == HALSIM_AnalogTriggerFiltered) { + if (triggerData->triggerMode.Get() != HALSIM_AnalogTriggerUnassigned) { *status = INCOMPATIBLE_STATE; return; } @@ -167,6 +179,25 @@ void HAL_SetAnalogTriggerAveraged(HAL_AnalogTriggerHandle analogTriggerHandle, : HALSIM_AnalogTriggerUnassigned; triggerData->triggerMode = setVal; } +void HAL_SetAnalogTriggerDutyCycle(HAL_AnalogTriggerHandle analogTriggerHandle, + HAL_Bool useDutyCycle, int32_t* status) { + auto trigger = analogTriggerHandles->Get(analogTriggerHandle); + if (trigger == nullptr) { + *status = HAL_HANDLE_ERROR; + return; + } + + AnalogTriggerData* triggerData = &SimAnalogTriggerData[trigger->index]; + + if (triggerData->triggerMode.Get() != HALSIM_AnalogTriggerUnassigned) { + *status = INCOMPATIBLE_STATE; + return; + } + + auto setVal = useDutyCycle ? HALSIM_AnalogTriggerDutyCycle + : HALSIM_AnalogTriggerUnassigned; + triggerData->triggerMode = setVal; +} void HAL_SetAnalogTriggerFiltered(HAL_AnalogTriggerHandle analogTriggerHandle, HAL_Bool useFilteredValue, int32_t* status) { auto trigger = analogTriggerHandles->Get(analogTriggerHandle); @@ -177,12 +208,12 @@ void HAL_SetAnalogTriggerFiltered(HAL_AnalogTriggerHandle analogTriggerHandle, AnalogTriggerData* triggerData = &SimAnalogTriggerData[trigger->index]; - if (triggerData->triggerMode.Get() == HALSIM_AnalogTriggerAveraged) { + if (triggerData->triggerMode.Get() != HALSIM_AnalogTriggerUnassigned) { *status = INCOMPATIBLE_STATE; return; } - auto setVal = useFilteredValue ? HALSIM_AnalogTriggerAveraged + auto setVal = useFilteredValue ? HALSIM_AnalogTriggerFiltered : HALSIM_AnalogTriggerUnassigned; triggerData->triggerMode = setVal; } @@ -258,4 +289,15 @@ HAL_Bool HAL_GetAnalogTriggerOutput(HAL_AnalogTriggerHandle analogTriggerHandle, return false; } } + +int32_t HAL_GetAnalogTriggerFPGAIndex( + HAL_AnalogTriggerHandle analogTriggerHandle, int32_t* status) { + auto trigger = analogTriggerHandles->Get(analogTriggerHandle); + if (trigger == nullptr) { + *status = HAL_HANDLE_ERROR; + return -1; + } + return trigger->index; +} + } // extern "C" diff --git a/hal/src/main/native/sim/DutyCycle.cpp b/hal/src/main/native/sim/DutyCycle.cpp new file mode 100644 index 0000000000..0e14eeb3dd --- /dev/null +++ b/hal/src/main/native/sim/DutyCycle.cpp @@ -0,0 +1,120 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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. */ +/*----------------------------------------------------------------------------*/ + +#include "hal/DutyCycle.h" + +#include "HALInitializer.h" +#include "PortsInternal.h" +#include "hal/Errors.h" +#include "hal/handles/HandlesInternal.h" +#include "hal/handles/LimitedHandleResource.h" +#include "mockdata/DutyCycleDataInternal.h" + +using namespace hal; + +namespace { +struct DutyCycle { + uint8_t index; +}; +struct Empty {}; +} // namespace + +static LimitedHandleResource* dutyCycleHandles; + +namespace hal { +namespace init { +void InitializeDutyCycle() { + static LimitedHandleResource + dcH; + dutyCycleHandles = &dcH; +} +} // namespace init +} // namespace hal + +extern "C" { +HAL_DutyCycleHandle HAL_InitializeDutyCycle(HAL_Handle digitalSourceHandle, + HAL_AnalogTriggerType triggerType, + int32_t* status) { + hal::init::CheckInit(); + + HAL_DutyCycleHandle handle = dutyCycleHandles->Allocate(); + if (handle == HAL_kInvalidHandle) { + *status = NO_AVAILABLE_RESOURCES; + return HAL_kInvalidHandle; + } + + auto dutyCycle = dutyCycleHandles->Get(handle); + if (dutyCycle == nullptr) { // would only occur on thread issue + *status = HAL_HANDLE_ERROR; + return HAL_kInvalidHandle; + } + + int16_t index = getHandleIndex(handle); + SimDutyCycleData[index].digitalChannel = getHandleIndex(digitalSourceHandle); + SimDutyCycleData[index].initialized = true; + SimDutyCycleData[index].simDevice = 0; + dutyCycle->index = index; + return handle; +} +void HAL_FreeDutyCycle(HAL_DutyCycleHandle dutyCycleHandle) { + auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle); + dutyCycleHandles->Free(dutyCycleHandle); + if (dutyCycle == nullptr) return; + SimDutyCycleData[dutyCycle->index].initialized = false; +} + +void HAL_SetDutyCycleSimDevice(HAL_EncoderHandle handle, + HAL_SimDeviceHandle device) { + auto dutyCycle = dutyCycleHandles->Get(handle); + if (dutyCycle == nullptr) return; + SimDutyCycleData[dutyCycle->index].simDevice = device; +} + +int32_t HAL_GetDutyCycleFrequency(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status) { + auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle); + if (dutyCycle == nullptr) { + *status = HAL_HANDLE_ERROR; + return 0; + } + return SimDutyCycleData[dutyCycle->index].frequency; +} +double HAL_GetDutyCycleOutput(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status) { + auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle); + if (dutyCycle == nullptr) { + *status = HAL_HANDLE_ERROR; + return 0; + } + return SimDutyCycleData[dutyCycle->index].output; +} +int32_t HAL_GetDutyCycleOutputRaw(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status) { + auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle); + if (dutyCycle == nullptr) { + *status = HAL_HANDLE_ERROR; + return 0; + } + return SimDutyCycleData[dutyCycle->index].output * + HAL_GetDutyCycleOutputScaleFactor(dutyCycleHandle, status); +} +int32_t HAL_GetDutyCycleOutputScaleFactor(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status) { + return 4e7 - 1; +} +int32_t HAL_GetDutyCycleFPGAIndex(HAL_DutyCycleHandle dutyCycleHandle, + int32_t* status) { + auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle); + if (dutyCycle == nullptr) { + *status = HAL_HANDLE_ERROR; + return -1; + } + return dutyCycle->index; +} +} // extern "C" diff --git a/hal/src/main/native/sim/HAL.cpp b/hal/src/main/native/sim/HAL.cpp index cf019cfcc4..bc86c93907 100644 --- a/hal/src/main/native/sim/HAL.cpp +++ b/hal/src/main/native/sim/HAL.cpp @@ -32,6 +32,7 @@ void InitializeHAL() { InitializeCanData(); InitializeCANAPI(); InitializeDigitalPWMData(); + InitializeDutyCycleData(); InitializeDIOData(); InitializeDriverStationData(); InitializeEncoderData(); @@ -56,6 +57,7 @@ void InitializeHAL() { InitializeCounter(); InitializeDigitalInternal(); InitializeDIO(); + InitializeDutyCycle(); InitializeDriverStation(); InitializeEncoder(); InitializeExtensions(); @@ -199,6 +201,8 @@ const char* HAL_GetErrorMessage(int32_t code) { return HAL_PWM_SCALE_ERROR_MESSAGE; case HAL_CAN_TIMEOUT: return HAL_CAN_TIMEOUT_MESSAGE; + case HAL_SIM_NOT_SUPPORTED: + return HAL_SIM_NOT_SUPPORTED_MESSAGE; default: return "Unknown error status"; } diff --git a/hal/src/main/native/sim/HALInitializer.h b/hal/src/main/native/sim/HALInitializer.h index 4c91b404fe..8e68ac3911 100644 --- a/hal/src/main/native/sim/HALInitializer.h +++ b/hal/src/main/native/sim/HALInitializer.h @@ -26,7 +26,9 @@ extern void InitializeAnalogTriggerData(); extern void InitializeCanData(); extern void InitializeCANAPI(); extern void InitializeDigitalPWMData(); +extern void InitializeDutyCycleData(); extern void InitializeDIOData(); +extern void InitializeDutyCycle(); extern void InitializeDriverStationData(); extern void InitializeEncoderData(); extern void InitializeI2CData(); diff --git a/hal/src/main/native/sim/Ports.cpp b/hal/src/main/native/sim/Ports.cpp index f50304fab4..a21eeb3626 100644 --- a/hal/src/main/native/sim/Ports.cpp +++ b/hal/src/main/native/sim/Ports.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 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. */ @@ -36,5 +36,5 @@ int32_t HAL_GetNumPCMModules(void) { return kNumPCMModules; } int32_t HAL_GetNumSolenoidChannels(void) { return kNumSolenoidChannels; } int32_t HAL_GetNumPDPModules(void) { return kNumPDPModules; } int32_t HAL_GetNumPDPChannels(void) { return kNumPDPChannels; } -int32_t HAL_GetNumCanTalons(void) { return kNumCanTalons; } +int32_t HAL_GetNumDutyCycles(void) { return kNumDutyCycles; } } // extern "C" diff --git a/hal/src/main/native/sim/PortsInternal.h b/hal/src/main/native/sim/PortsInternal.h index 0b899f7a55..c830af01f6 100644 --- a/hal/src/main/native/sim/PortsInternal.h +++ b/hal/src/main/native/sim/PortsInternal.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 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,5 +28,5 @@ constexpr int32_t kNumPCMModules = 63; constexpr int32_t kNumSolenoidChannels = 8; constexpr int32_t kNumPDPModules = 63; constexpr int32_t kNumPDPChannels = 16; -constexpr int32_t kNumCanTalons = 63; +constexpr int32_t kNumDutyCycles = 8; } // namespace hal diff --git a/hal/src/main/native/sim/jni/DutyCycleDataJNI.cpp b/hal/src/main/native/sim/jni/DutyCycleDataJNI.cpp new file mode 100644 index 0000000000..d746ce1a20 --- /dev/null +++ b/hal/src/main/native/sim/jni/DutyCycleDataJNI.cpp @@ -0,0 +1,178 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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. */ +/*----------------------------------------------------------------------------*/ + +#include + +#include "CallbackStore.h" +#include "edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI.h" +#include "mockdata/DutyCycleData.h" + +extern "C" { + +/* + * Class: edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI + * Method: registerInitializedCallback + * Signature: (ILjava/lang/Object;Z)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_registerInitializedCallback + (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify) +{ + return sim::AllocateCallback(env, index, callback, initialNotify, + &HALSIM_RegisterDutyCycleInitializedCallback); +} + +/* + * Class: edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI + * Method: cancelInitializedCallback + * Signature: (II)V + */ +JNIEXPORT void JNICALL +Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_cancelInitializedCallback + (JNIEnv* env, jclass, jint index, jint handle) +{ + return sim::FreeCallback(env, handle, index, + &HALSIM_CancelDutyCycleInitializedCallback); +} + +/* + * Class: edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI + * Method: getInitialized + * Signature: (I)Z + */ +JNIEXPORT jboolean JNICALL +Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_getInitialized + (JNIEnv*, jclass, jint index) +{ + return HALSIM_GetDutyCycleInitialized(index); +} + +/* + * Class: edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI + * Method: setInitialized + * Signature: (IZ)V + */ +JNIEXPORT void JNICALL +Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_setInitialized + (JNIEnv*, jclass, jint index, jboolean value) +{ + HALSIM_SetDutyCycleInitialized(index, value); +} + +/* + * Class: edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI + * Method: registerFrequencyCallback + * Signature: (ILjava/lang/Object;Z)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_registerFrequencyCallback + (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify) +{ + return sim::AllocateCallback(env, index, callback, initialNotify, + &HALSIM_RegisterDutyCycleFrequencyCallback); +} + +/* + * Class: edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI + * Method: cancelFrequencyCallback + * Signature: (II)V + */ +JNIEXPORT void JNICALL +Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_cancelFrequencyCallback + (JNIEnv* env, jclass, jint index, jint handle) +{ + return sim::FreeCallback(env, handle, index, + &HALSIM_CancelDutyCycleFrequencyCallback); +} + +/* + * Class: edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI + * Method: getFrequency + * Signature: (I)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_getFrequency + (JNIEnv*, jclass, jint index) +{ + return HALSIM_GetDutyCycleFrequency(index); +} + +/* + * Class: edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI + * Method: setFrequency + * Signature: (II)V + */ +JNIEXPORT void JNICALL +Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_setFrequency + (JNIEnv*, jclass, jint index, jint value) +{ + HALSIM_SetDutyCycleFrequency(index, value); +} + +/* + * Class: edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI + * Method: registerOutputCallback + * Signature: (ILjava/lang/Object;Z)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_registerOutputCallback + (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify) +{ + return sim::AllocateCallback(env, index, callback, initialNotify, + &HALSIM_RegisterDutyCycleOutputCallback); +} + +/* + * Class: edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI + * Method: cancelOutputCallback + * Signature: (II)V + */ +JNIEXPORT void JNICALL +Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_cancelOutputCallback + (JNIEnv* env, jclass, jint index, jint handle) +{ + return sim::FreeCallback(env, handle, index, + &HALSIM_CancelDutyCycleOutputCallback); +} + +/* + * Class: edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI + * Method: getOutput + * Signature: (I)D + */ +JNIEXPORT jdouble JNICALL +Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_getOutput + (JNIEnv*, jclass, jint index) +{ + return HALSIM_GetDutyCycleOutput(index); +} + +/* + * Class: edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI + * Method: setOutput + * Signature: (ID)V + */ +JNIEXPORT void JNICALL +Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_setOutput + (JNIEnv*, jclass, jint index, jdouble value) +{ + HALSIM_SetDutyCycleOutput(index, value); +} + +/* + * Class: edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI + * Method: resetData + * Signature: (I)V + */ +JNIEXPORT void JNICALL +Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_resetData + (JNIEnv*, jclass, jint index) +{ + HALSIM_ResetDutyCycleData(index); +} + +} // extern "C" diff --git a/hal/src/main/native/sim/mockdata/DutyCycleData.cpp b/hal/src/main/native/sim/mockdata/DutyCycleData.cpp new file mode 100644 index 0000000000..04806e016b --- /dev/null +++ b/hal/src/main/native/sim/mockdata/DutyCycleData.cpp @@ -0,0 +1,63 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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. */ +/*----------------------------------------------------------------------------*/ + +#include "../PortsInternal.h" +#include "DutyCycleDataInternal.h" + +using namespace hal; + +namespace hal { +namespace init { +void InitializeDutyCycleData() { + static DutyCycleData sed[kNumDutyCycles]; + ::hal::SimDutyCycleData = sed; +} +} // namespace init +} // namespace hal + +DutyCycleData* hal::SimDutyCycleData; + +void DutyCycleData::ResetData() { + digitalChannel = 0; + initialized.Reset(false); + simDevice = 0; + frequency.Reset(0); + output.Reset(0); +} + +extern "C" { +void HALSIM_ResetDutyCycleData(int32_t index) { + SimDutyCycleData[index].ResetData(); +} +int32_t HALSIM_GetDutyCycleDigitalChannel(int32_t index) { + return SimDutyCycleData[index].digitalChannel; +} + +HAL_SimDeviceHandle HALSIM_GetDutyCycleSimDevice(int32_t index) { + return SimDutyCycleData[index].simDevice; +} + +#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME) \ + HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, DutyCycle##CAPINAME, \ + SimDutyCycleData, LOWERNAME) + +DEFINE_CAPI(HAL_Bool, Initialized, initialized) +DEFINE_CAPI(int32_t, Frequency, frequency) +DEFINE_CAPI(double, Output, output) + +#define REGISTER(NAME) \ + SimDutyCycleData[index].NAME.RegisterCallback(callback, param, initialNotify) + +void HALSIM_RegisterDutyCycleAllCallbacks(int32_t index, + HAL_NotifyCallback callback, + void* param, HAL_Bool initialNotify) { + REGISTER(initialized); + REGISTER(frequency); + REGISTER(output); +} + +} // extern "C" diff --git a/hal/src/main/native/sim/mockdata/DutyCycleDataInternal.h b/hal/src/main/native/sim/mockdata/DutyCycleDataInternal.h new file mode 100644 index 0000000000..2f98b072be --- /dev/null +++ b/hal/src/main/native/sim/mockdata/DutyCycleDataInternal.h @@ -0,0 +1,33 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 "mockdata/DutyCycleData.h" +#include "mockdata/SimDataValue.h" + +namespace hal { +class DutyCycleData { + HAL_SIMDATAVALUE_DEFINE_NAME(Initialized) + HAL_SIMDATAVALUE_DEFINE_NAME(Output) + HAL_SIMDATAVALUE_DEFINE_NAME(Frequency) + + public: + std::atomic digitalChannel{0}; + SimDataValue initialized{ + false}; + std::atomic simDevice; + SimDataValue frequency{0}; + SimDataValue output{0}; + + virtual void ResetData(); +}; +extern DutyCycleData* SimDutyCycleData; +} // namespace hal diff --git a/myRobot/src/main/native/cpp/MyRobot.cpp b/myRobot/src/main/native/cpp/MyRobot.cpp index ff066d8844..2c9bd98f67 100644 --- a/myRobot/src/main/native/cpp/MyRobot.cpp +++ b/myRobot/src/main/native/cpp/MyRobot.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2016-2019 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. */ @@ -7,12 +7,42 @@ #include +#include +#include +#include +#include + +#include "frc/smartdashboard/SmartDashboard.h" + +HAL_DigitalHandle inputHandle; +HAL_DutyCycleHandle dutyCycleHandle; + class MyRobot : public frc::TimedRobot { /** * This function is run when the robot is first started up and should be * used for any initialization code. */ - void RobotInit() override {} + void RobotInit() override { + int32_t status = 0; + inputHandle = HAL_InitializeDIOPort(HAL_GetPort(9), true, &status); + std::cout << "DIO Status: " << status << std::endl; + dutyCycleHandle = HAL_InitializeDutyCycle( + inputHandle, HAL_AnalogTriggerType::HAL_Trigger_kInWindow, &status); + std::cout << "Duty Cycle Status: " << status << std::endl; + + // float pbs = 0; + // uint32_t boc = 0; + // uint32_t txfc = 0; + // uint32_t rec = 0; + // uint32_t tec = 0; + status = 0; + auto start = HAL_GetFPGATime(&status); + // HAL_CAN_GetCANStatus(&pbs, &boc, &txfc, &rec, &tec, &status); + uint8_t data = 0; + HAL_CAN_SendMessage(0, &data, 1, HAL_CAN_SEND_PERIOD_NO_REPEAT, &status); + auto end = HAL_GetFPGATime(&status); + std::cout << "Start " << start << " end " << end << std::endl; + } /** * This function is run once each time the robot enters autonomous mode @@ -42,7 +72,15 @@ class MyRobot : public frc::TimedRobot { /** * This function is called periodically during all modes */ - void RobotPeriodic() override {} + void RobotPeriodic() override { + int32_t status = 0; + auto freq = HAL_GetDutyCycleFrequency(dutyCycleHandle, &status); + auto raw = HAL_GetDutyCycleOutputRaw(dutyCycleHandle, &status); + auto percentage = HAL_GetDutyCycleOutput(dutyCycleHandle, &status); + frc::SmartDashboard::PutNumber("Freq", freq); + frc::SmartDashboard::PutNumber("Raw", raw); + frc::SmartDashboard::PutNumber("Percentage", percentage); + } }; int main() { return frc::StartRobot(); } diff --git a/wpilibc/src/main/native/cpp/AnalogTrigger.cpp b/wpilibc/src/main/native/cpp/AnalogTrigger.cpp index 42fe3706fb..d9ecd7a451 100644 --- a/wpilibc/src/main/native/cpp/AnalogTrigger.cpp +++ b/wpilibc/src/main/native/cpp/AnalogTrigger.cpp @@ -12,6 +12,7 @@ #include #include "frc/AnalogInput.h" +#include "frc/DutyCycle.h" #include "frc/WPIErrors.h" #include "frc/smartdashboard/SendableRegistry.h" @@ -26,19 +27,31 @@ AnalogTrigger::AnalogTrigger(int channel) AnalogTrigger::AnalogTrigger(AnalogInput* input) { m_analogInput = input; int32_t status = 0; - int index = 0; - m_trigger = HAL_InitializeAnalogTrigger(input->m_port, &index, &status); + m_trigger = HAL_InitializeAnalogTrigger(input->m_port, &status); if (status != 0) { wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); - m_index = std::numeric_limits::max(); m_trigger = HAL_kInvalidHandle; return; } - m_index = index; + int index = GetIndex(); - HAL_Report(HALUsageReporting::kResourceType_AnalogTrigger, m_index + 1); - SendableRegistry::GetInstance().AddLW(this, "AnalogTrigger", - input->GetChannel()); + HAL_Report(HALUsageReporting::kResourceType_AnalogTrigger, index + 1); + SendableRegistry::GetInstance().AddLW(this, "AnalogTrigger", index); +} + +AnalogTrigger::AnalogTrigger(DutyCycle* input) { + m_dutyCycle = input; + int32_t status = 0; + m_trigger = HAL_InitializeAnalogTriggerDutyCycle(input->m_handle, &status); + if (status != 0) { + wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); + m_trigger = HAL_kInvalidHandle; + return; + } + int index = GetIndex(); + + HAL_Report(HALUsageReporting::kResourceType_AnalogTrigger, index + 1); + SendableRegistry::GetInstance().AddLW(this, "AnalogTrigger", index); } AnalogTrigger::~AnalogTrigger() { @@ -53,9 +66,9 @@ AnalogTrigger::~AnalogTrigger() { AnalogTrigger::AnalogTrigger(AnalogTrigger&& rhs) : ErrorBase(std::move(rhs)), SendableHelper(std::move(rhs)), - m_index(std::move(rhs.m_index)), m_trigger(std::move(rhs.m_trigger)) { std::swap(m_analogInput, rhs.m_analogInput); + std::swap(m_dutyCycle, rhs.m_dutyCycle); std::swap(m_ownsAnalog, rhs.m_ownsAnalog); } @@ -63,9 +76,9 @@ AnalogTrigger& AnalogTrigger::operator=(AnalogTrigger&& rhs) { ErrorBase::operator=(std::move(rhs)); SendableHelper::operator=(std::move(rhs)); - m_index = std::move(rhs.m_index); m_trigger = std::move(rhs.m_trigger); std::swap(m_analogInput, rhs.m_analogInput); + std::swap(m_dutyCycle, rhs.m_dutyCycle); std::swap(m_ownsAnalog, rhs.m_ownsAnalog); return *this; @@ -78,6 +91,13 @@ void AnalogTrigger::SetLimitsVoltage(double lower, double upper) { wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); } +void AnalogTrigger::SetLimitsDutyCycle(double lower, double upper) { + if (StatusIsFatal()) return; + int32_t status = 0; + HAL_SetAnalogTriggerLimitsDutyCycle(m_trigger, lower, upper, &status); + wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); +} + void AnalogTrigger::SetLimitsRaw(int lower, int upper) { if (StatusIsFatal()) return; int32_t status = 0; @@ -101,7 +121,10 @@ void AnalogTrigger::SetFiltered(bool useFilteredValue) { int AnalogTrigger::GetIndex() const { if (StatusIsFatal()) return -1; - return m_index; + int32_t status = 0; + auto ret = HAL_GetAnalogTriggerFPGAIndex(m_trigger, &status); + wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); + return ret; } bool AnalogTrigger::GetInWindow() { diff --git a/wpilibc/src/main/native/cpp/AnalogTriggerOutput.cpp b/wpilibc/src/main/native/cpp/AnalogTriggerOutput.cpp index 5dc30339ee..cae01aabff 100644 --- a/wpilibc/src/main/native/cpp/AnalogTriggerOutput.cpp +++ b/wpilibc/src/main/native/cpp/AnalogTriggerOutput.cpp @@ -33,7 +33,7 @@ AnalogTriggerType AnalogTriggerOutput::GetAnalogTriggerTypeForRouting() const { bool AnalogTriggerOutput::IsAnalogTrigger() const { return true; } -int AnalogTriggerOutput::GetChannel() const { return m_trigger->m_index; } +int AnalogTriggerOutput::GetChannel() const { return m_trigger->GetIndex(); } void AnalogTriggerOutput::InitSendable(SendableBuilder&) {} diff --git a/wpilibc/src/main/native/cpp/DutyCycle.cpp b/wpilibc/src/main/native/cpp/DutyCycle.cpp new file mode 100644 index 0000000000..90ebaa5ae0 --- /dev/null +++ b/wpilibc/src/main/native/cpp/DutyCycle.cpp @@ -0,0 +1,99 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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. */ +/*----------------------------------------------------------------------------*/ + +#include "frc/DutyCycle.h" + +#include +#include +#include + +#include "frc/DigitalSource.h" +#include "frc/WPIErrors.h" +#include "frc/smartdashboard/SendableBuilder.h" + +using namespace frc; + +DutyCycle::DutyCycle(DigitalSource* source) + : m_source{source, NullDeleter()} { + if (m_source == nullptr) { + wpi_setWPIError(NullParameter); + } else { + InitDutyCycle(); + } +} + +DutyCycle::DutyCycle(DigitalSource& source) + : m_source{&source, NullDeleter()} { + InitDutyCycle(); +} + +DutyCycle::DutyCycle(std::shared_ptr source) + : m_source{std::move(source)} { + if (m_source == nullptr) { + wpi_setWPIError(NullParameter); + } else { + InitDutyCycle(); + } +} + +DutyCycle::~DutyCycle() { HAL_FreeDutyCycle(m_handle); } + +void DutyCycle::InitDutyCycle() { + int32_t status = 0; + m_handle = + HAL_InitializeDutyCycle(m_source->GetPortHandleForRouting(), + static_cast( + m_source->GetAnalogTriggerTypeForRouting()), + &status); + wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); + int index = GetFPGAIndex(); + HAL_Report(HALUsageReporting::kResourceType_DutyCycle, index + 1); + SendableRegistry::GetInstance().AddLW(this, "Duty Cycle", index); +} + +int DutyCycle::GetFPGAIndex() const { + int32_t status = 0; + auto retVal = HAL_GetDutyCycleFPGAIndex(m_handle, &status); + wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); + return retVal; +} + +int DutyCycle::GetFrequency() const { + int32_t status = 0; + auto retVal = HAL_GetDutyCycleFrequency(m_handle, &status); + wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); + return retVal; +} + +double DutyCycle::GetOutput() const { + int32_t status = 0; + auto retVal = HAL_GetDutyCycleOutput(m_handle, &status); + wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); + return retVal; +} + +unsigned int DutyCycle::GetOutputRaw() const { + int32_t status = 0; + auto retVal = HAL_GetDutyCycleOutput(m_handle, &status); + wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); + return retVal; +} + +unsigned int DutyCycle::GetOutputScaleFactor() const { + int32_t status = 0; + auto retVal = HAL_GetDutyCycleOutputScaleFactor(m_handle, &status); + wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); + return retVal; +} + +void DutyCycle::InitSendable(SendableBuilder& builder) { + builder.SetSmartDashboardType("Duty Cycle"); + builder.AddDoubleProperty("Frequency", + [this] { return this->GetFrequency(); }, nullptr); + builder.AddDoubleProperty("Output", [this] { return this->GetOutput(); }, + nullptr); +} diff --git a/wpilibc/src/main/native/include/frc/AnalogTrigger.h b/wpilibc/src/main/native/include/frc/AnalogTrigger.h index 6a57f8a833..7554bd9a9f 100644 --- a/wpilibc/src/main/native/include/frc/AnalogTrigger.h +++ b/wpilibc/src/main/native/include/frc/AnalogTrigger.h @@ -19,6 +19,7 @@ namespace frc { class AnalogInput; +class DutyCycle; class SendableBuilder; class AnalogTrigger : public ErrorBase, @@ -45,6 +46,13 @@ class AnalogTrigger : public ErrorBase, */ explicit AnalogTrigger(AnalogInput* channel); + /** + * Construct an analog trigger given a duty cycle input. + * + * @param channel The pointer to the existing DutyCycle object + */ + explicit AnalogTrigger(DutyCycle* dutyCycle); + ~AnalogTrigger() override; AnalogTrigger(AnalogTrigger&& rhs); @@ -60,6 +68,16 @@ class AnalogTrigger : public ErrorBase, */ void SetLimitsVoltage(double lower, double upper); + /** + * Set the upper and lower duty cycle limits of the analog trigger. + * + * The limits are given as floating point values between 0 and 1. + * + * @param lower The lower limit of the trigger in percentage. + * @param upper The upper limit of the trigger in percentage. + */ + void SetLimitsDutyCycle(double lower, double upper); + /** * Set the upper and lower limits of the analog trigger. * @@ -82,6 +100,17 @@ class AnalogTrigger : public ErrorBase, */ void SetAveraged(bool useAveragedValue); + /** + * Configure the analog trigger to use the duty cycle vs. raw values. + * + * If the value is true, then the duty cycle value is selected for the analog + * trigger, otherwise the immediate value is used. + * + * @param useDutyCycle If true, use the duty cycle value, otherwise use the + * instantaneous reading + */ + void SetDutyCycle(bool useDutyCycle); + /** * Configure the analog trigger to use a filtered value. * @@ -139,9 +168,9 @@ class AnalogTrigger : public ErrorBase, void InitSendable(SendableBuilder& builder) override; private: - int m_index; hal::Handle m_trigger; AnalogInput* m_analogInput = nullptr; + DutyCycle* m_dutyCycle = nullptr; bool m_ownsAnalog = false; }; diff --git a/wpilibc/src/main/native/include/frc/DutyCycle.h b/wpilibc/src/main/native/include/frc/DutyCycle.h new file mode 100644 index 0000000000..37db4fc6a2 --- /dev/null +++ b/wpilibc/src/main/native/include/frc/DutyCycle.h @@ -0,0 +1,124 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 "frc/ErrorBase.h" +#include "frc/smartdashboard/Sendable.h" +#include "frc/smartdashboard/SendableHelper.h" + +namespace frc { +class DigitalSource; +class AnalogTrigger; + +/** + * Class to read a duty cycle PWM input. + * + *

PWM input signals are specified with a frequency and a ratio of high to + * low in that frequency. There are 8 of these in the roboRIO, and they can be + * attached to any DigitalSource. + * + *

These can be combined as the input of an AnalogTrigger to a Counter in + * order to implement rollover checking. + * + */ +class DutyCycle : public ErrorBase, + public Sendable, + public SendableHelper { + friend class AnalogTrigger; + + public: + /** + * Constructs a DutyCycle input from a DigitalSource input. + * + *

This class does not own the inputted source. + * + * @param source The DigitalSource to use. + */ + explicit DutyCycle(DigitalSource& source); + /** + * Constructs a DutyCycle input from a DigitalSource input. + * + *

This class does not own the inputted source. + * + * @param source The DigitalSource to use. + */ + explicit DutyCycle(DigitalSource* source); + /** + * Constructs a DutyCycle input from a DigitalSource input. + * + *

This class does not own the inputted source. + * + * @param source The DigitalSource to use. + */ + explicit DutyCycle(std::shared_ptr source); + + /** + * Close the DutyCycle and free all resources. + */ + ~DutyCycle() override; + + DutyCycle(DutyCycle&&) = default; + DutyCycle& operator=(DutyCycle&&) = default; + + /** + * Get the frequency of the duty cycle signal. + * + * @return frequency in Hertz + */ + int GetFrequency() const; + + /** + * Get the output ratio of the duty cycle signal. + * + *

0 means always low, 1 means always high. + * + * @return output ratio between 0 and 1 + */ + double GetOutput() const; + + /** + * Get the raw output ratio of the duty cycle signal. + * + *

0 means always low, an output equal to + * GetOutputScaleFactor() means always high. + * + * @return output ratio in raw units + */ + unsigned int GetOutputRaw() const; + + /** + * Get the scale factor of the output. + * + *

An output equal to this value is always high, and then linearly scales + * down to 0. Divide the result of getOutputRaw by this in order to get the + * percentage between 0 and 1. + * + * @return the output scale factor + */ + unsigned int GetOutputScaleFactor() const; + + /** + * Get the FPGA index for the DutyCycle. + * + * @return the FPGA index + */ + int GetFPGAIndex() const; + + protected: + void InitSendable(SendableBuilder& builder) override; + + private: + void InitDutyCycle(); + std::shared_ptr m_source; + hal::Handle m_handle; +}; +} // namespace frc diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java index 52f4003918..f7f98bde71 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java @@ -7,9 +7,6 @@ package edu.wpi.first.wpilibj; -import java.nio.ByteBuffer; -import java.nio.ByteOrder; - import edu.wpi.first.hal.AnalogJNI; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; @@ -42,8 +39,8 @@ public class AnalogTrigger implements Sendable, AutoCloseable { * Where the analog trigger is attached. */ protected int m_port; - protected int m_index; protected AnalogInput m_analogInput; + protected DutyCycle m_dutyCycle; protected boolean m_ownsAnalog; /** @@ -65,15 +62,29 @@ public class AnalogTrigger implements Sendable, AutoCloseable { */ public AnalogTrigger(AnalogInput channel) { m_analogInput = channel; - ByteBuffer index = ByteBuffer.allocateDirect(4); - index.order(ByteOrder.LITTLE_ENDIAN); - m_port = - AnalogJNI.initializeAnalogTrigger(channel.m_port, index.asIntBuffer()); - m_index = index.asIntBuffer().get(0); + m_port = AnalogJNI.initializeAnalogTrigger(channel.m_port); - HAL.report(tResourceType.kResourceType_AnalogTrigger, m_index + 1); - SendableRegistry.addLW(this, "AnalogTrigger", channel.getChannel()); + int index = getIndex(); + + HAL.report(tResourceType.kResourceType_AnalogTrigger, index + 1); + SendableRegistry.addLW(this, "AnalogTrigger", index); + } + + /** + * Construct an analog trigger given a duty cycle input. + * + * @param input the DutyCycle to use for the analog trigger + */ + public AnalogTrigger(DutyCycle input) { + m_dutyCycle = input; + + m_port = AnalogJNI.initializeAnalogTriggerDutyCycle(input.m_handle); + + int index = getIndex(); + + HAL.report(tResourceType.kResourceType_AnalogTrigger, index + 1); + SendableRegistry.addLW(this, "AnalogTrigger", index); } @Override @@ -100,6 +111,20 @@ public class AnalogTrigger implements Sendable, AutoCloseable { AnalogJNI.setAnalogTriggerLimitsRaw(m_port, lower, upper); } + /** + * Set the upper and lower limits of the analog trigger. The limits are given as floating point + * values between 0 and 1. + * + * @param lower the lower duty cycle limit + * @param upper the upper duty cycle limit + */ + public void setLimitsDutyCycle(double lower, double upper) { + if (lower > upper) { + throw new BoundaryException("Lower bound is greater than upper bound"); + } + AnalogJNI.setAnalogTriggerLimitsDutyCycle(m_port, lower, upper); + } + /** * Set the upper and lower limits of the analog trigger. The limits are given as floating point * voltage values. @@ -141,8 +166,8 @@ public class AnalogTrigger implements Sendable, AutoCloseable { * * @return The index of the analog trigger. */ - public int getIndex() { - return m_index; + public final int getIndex() { + return AnalogJNI.getAnalogTriggerFPGAIndex(m_port); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java index 8217f54a39..7635196662 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java @@ -98,7 +98,7 @@ public class AnalogTriggerOutput extends DigitalSource implements Sendable { @Override public int getChannel() { - return m_trigger.m_index; + return m_trigger.getIndex(); } @Override diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java new file mode 100644 index 0000000000..6bc8e7ebea --- /dev/null +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java @@ -0,0 +1,117 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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. */ +/*----------------------------------------------------------------------------*/ + +package edu.wpi.first.wpilibj; + +import edu.wpi.first.hal.DutyCycleJNI; +import edu.wpi.first.hal.FRCNetComm.tResourceType; +import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry; + +/** + * Class to read a duty cycle PWM input. + * + *

PWM input signals are specified with a frequency and a ratio of high to low + * in that frequency. There are 8 of these in the roboRIO, and they can be + * attached to any {@link DigitalSource}. + * + *

These can be combined as the input of an AnalogTrigger to a Counter in order + * to implement rollover checking. + * + */ +public class DutyCycle implements Sendable, AutoCloseable { + // Explicitly package private + final int m_handle; + + /** + * Constructs a DutyCycle input from a DigitalSource input. + * + *

This class does not own the inputted source. + * + * @param digitalSource The DigitalSource to use. + */ + public DutyCycle(DigitalSource digitalSource) { + m_handle = DutyCycleJNI.initialize(digitalSource.getPortHandleForRouting(), + digitalSource.getAnalogTriggerTypeForRouting()); + + int index = getFPGAIndex(); + HAL.report(tResourceType.kResourceType_DutyCycle, index + 1); + SendableRegistry.addLW(this, "Duty Cycle", index); + } + + /** + * Close the DutyCycle and free all resources. + */ + @Override + public void close() { + DutyCycleJNI.free(m_handle); + } + + /** + * Get the frequency of the duty cycle signal. + * + * @return frequency in Hertz + */ + public int getFrequency() { + return DutyCycleJNI.getFrequency(m_handle); + } + + /** + * Get the output ratio of the duty cycle signal. + * + *

0 means always low, 1 means always high. + * + * @return output ratio between 0 and 1 + */ + public double getOutput() { + return DutyCycleJNI.getOutput(m_handle); + } + + /** + * Get the raw output ratio of the duty cycle signal. + * + *

0 means always low, an output equal to getOutputScaleFactor() means always + * high. + * + * @return output ratio in raw units + */ + public int getOutputRaw() { + return DutyCycleJNI.getOutputRaw(m_handle); + } + + /** + * Get the scale factor of the output. + * + *

An output equal to this value is always high, and then linearly scales down + * to 0. Divide the result of getOutputRaw by this in order to get the + * percentage between 0 and 1. + * + * @return the output scale factor + */ + public int getOutputScaleFactor() { + return DutyCycleJNI.getOutputScaleFactor(m_handle); + } + + /** + * Get the FPGA index for the DutyCycle. + * + * @return the FPGA index + */ + @SuppressWarnings("AbbreviationAsWordInName") + public final int getFPGAIndex() { + return DutyCycleJNI.getFPGAIndex(m_handle); + } + + @Override + public void initSendable(SendableBuilder builder) { + builder.setSmartDashboardType("Duty Cycle"); + builder.addDoubleProperty("Frequency", this::getFrequency, null); + builder.addDoubleProperty("Output", this::getOutput, null); + + } +}