mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[hal, wpilib] Add initial systemcore counter implementation (#7723)
This commit is contained in:
@@ -4,35 +4,21 @@
|
||||
|
||||
package edu.wpi.first.hal;
|
||||
|
||||
import java.nio.IntBuffer;
|
||||
|
||||
/**
|
||||
* Counter HAL JNI functions.
|
||||
*
|
||||
* @see "hal/Counter.h"
|
||||
*/
|
||||
public class CounterJNI extends JNIWrapper {
|
||||
/** Two pulse mode. */
|
||||
public static final int TWO_PULSE = 0;
|
||||
|
||||
/** Semi-period mode. */
|
||||
public static final int SEMI_PERIOD = 1;
|
||||
|
||||
/** Pulse length mode. */
|
||||
public static final int PULSE_LENGTH = 2;
|
||||
|
||||
/** External direction mode. */
|
||||
public static final int EXTERNAL_DIRECTION = 3;
|
||||
|
||||
/**
|
||||
* Initializes a counter.
|
||||
*
|
||||
* @param mode the counter mode
|
||||
* @param index the compressor index (output)
|
||||
* @param channel the DIO channel
|
||||
* @param risingEdge true to trigger on rising
|
||||
* @return the created handle
|
||||
* @see "HAL_InitializeCounter"
|
||||
*/
|
||||
public static native int initializeCounter(int mode, IntBuffer index);
|
||||
public static native int initializeCounter(int channel, boolean risingEdge);
|
||||
|
||||
/**
|
||||
* Frees a counter.
|
||||
@@ -42,27 +28,6 @@ public class CounterJNI extends JNIWrapper {
|
||||
*/
|
||||
public static native void freeCounter(int counterHandle);
|
||||
|
||||
/**
|
||||
* Sets the average sample size of a counter.
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @param size the size of samples to average
|
||||
* @see "HAL_SetCounterAverageSize"
|
||||
*/
|
||||
public static native void setCounterAverageSize(int counterHandle, int size);
|
||||
|
||||
/**
|
||||
* Sets the source object that causes the counter to count up.
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @param digitalSourceHandle the digital source handle (either a HAL_AnalogTriggerHandle or a
|
||||
* HAL_DigitalHandle)
|
||||
* @param analogTriggerType the analog trigger type if the source is an analog trigger
|
||||
* @see "HAL_SetCounterUpSource"
|
||||
*/
|
||||
public static native void setCounterUpSource(
|
||||
int counterHandle, int digitalSourceHandle, int analogTriggerType);
|
||||
|
||||
/**
|
||||
* Sets the up source to either detect rising edges or falling edges.
|
||||
*
|
||||
@@ -70,117 +35,9 @@ public class CounterJNI extends JNIWrapper {
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @param risingEdge true to trigger on rising
|
||||
* @param fallingEdge true to trigger on falling
|
||||
* @see "HAL_SetCounterUpSourceEdge"
|
||||
*/
|
||||
public static native void setCounterUpSourceEdge(
|
||||
int counterHandle, boolean risingEdge, boolean fallingEdge);
|
||||
|
||||
/**
|
||||
* Disables the up counting source to the counter.
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @see "HAL_ClearCounterUpSource"
|
||||
*/
|
||||
public static native void clearCounterUpSource(int counterHandle);
|
||||
|
||||
/**
|
||||
* Sets the source object that causes the counter to count down.
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @param digitalSourceHandle the digital source handle (either a HAL_AnalogTriggerHandle or a
|
||||
* HAL_DigitalHandle)
|
||||
* @param analogTriggerType the analog trigger type if the source is an analog trigger
|
||||
* @see "HAL_SetCounterDownSource"
|
||||
*/
|
||||
public static native void setCounterDownSource(
|
||||
int counterHandle, int digitalSourceHandle, int analogTriggerType);
|
||||
|
||||
/**
|
||||
* Sets the down source to either detect rising edges or falling edges. Note that both are allowed
|
||||
* to be set true at the same time without issues.
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @param risingEdge true to trigger on rising
|
||||
* @param fallingEdge true to trigger on falling
|
||||
* @see "HAL_SetCounterDownSourceEdge"
|
||||
*/
|
||||
public static native void setCounterDownSourceEdge(
|
||||
int counterHandle, boolean risingEdge, boolean fallingEdge);
|
||||
|
||||
/**
|
||||
* Disables the down counting source to the counter.
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @see "HAL_ClearCounterDownSource"
|
||||
*/
|
||||
public static native void clearCounterDownSource(int counterHandle);
|
||||
|
||||
/**
|
||||
* Sets standard up / down counting mode on this counter.
|
||||
*
|
||||
* <p>Up and down counts are sourced independently from two inputs.
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @see "HAL_SetCounterUpDownMode"
|
||||
*/
|
||||
public static native void setCounterUpDownMode(int counterHandle);
|
||||
|
||||
/**
|
||||
* Sets directional counting mode on this counter.
|
||||
*
|
||||
* <p>The direction is determined by the B input, with counting happening with the A input.
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @see "HAL_SetCounterExternalDirectionMode"
|
||||
*/
|
||||
public static native void setCounterExternalDirectionMode(int counterHandle);
|
||||
|
||||
/**
|
||||
* Sets Semi-period mode on this counter.
|
||||
*
|
||||
* <p>The counter counts up based on the time the input is triggered. High or Low depends on the
|
||||
* highSemiPeriod parameter.
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @param highSemiPeriod true for counting when the input is high, false for low
|
||||
* @see "HAL_SetCounterSemiPeriodMode"
|
||||
*/
|
||||
public static native void setCounterSemiPeriodMode(int counterHandle, boolean highSemiPeriod);
|
||||
|
||||
/**
|
||||
* Configures the counter to count in up or down based on the length of the input pulse.
|
||||
*
|
||||
* <p>This mode is most useful for direction sensitive gear tooth sensors.
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @param threshold The pulse length beyond which the counter counts the opposite direction
|
||||
* (seconds)
|
||||
* @see "HAL_SetCounterPulseLengthMode"
|
||||
*/
|
||||
public static native void setCounterPulseLengthMode(int counterHandle, double threshold);
|
||||
|
||||
/**
|
||||
* Gets the Samples to Average which specifies the number of samples of the timer to average when
|
||||
* calculating the period. Perform averaging to account for mechanical imperfections or as
|
||||
* oversampling to increase resolution.
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @return SamplesToAverage The number of samples being averaged (from 1 to 127)
|
||||
* @see "HAL_GetCounterSamplesToAverage"
|
||||
*/
|
||||
public static native int getCounterSamplesToAverage(int counterHandle);
|
||||
|
||||
/**
|
||||
* Sets the Samples to Average which specifies the number of samples of the timer to average when
|
||||
* calculating the period. Perform averaging to account for mechanical imperfections or as
|
||||
* oversampling to increase resolution.
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @param samplesToAverage The number of samples to average from 1 to 127
|
||||
* @see "HAL_SetCounterSamplesToAverage"
|
||||
*/
|
||||
public static native void setCounterSamplesToAverage(int counterHandle, int samplesToAverage);
|
||||
public static native void setCounterEdgeConfiguration(int counterHandle, boolean risingEdge);
|
||||
|
||||
/**
|
||||
* Resets the Counter to zero.
|
||||
@@ -229,30 +86,6 @@ public class CounterJNI extends JNIWrapper {
|
||||
*/
|
||||
public static native void setCounterMaxPeriod(int counterHandle, double maxPeriod);
|
||||
|
||||
/**
|
||||
* Selects whether you want to continue updating the event timer output when there are no samples
|
||||
* captured.
|
||||
*
|
||||
* <p>The output of the event timer has a buffer of periods that are averaged and posted to a
|
||||
* register on the FPGA. When the timer detects that the event source has stopped (based on the
|
||||
* MaxPeriod) the buffer of samples to be averaged is emptied.
|
||||
*
|
||||
* <p>If you enable the update when empty, you will be notified of the stopped source and the
|
||||
* event time will report 0 samples.
|
||||
*
|
||||
* <p>If you disable update when empty, the most recent average will remain on the output until a
|
||||
* new sample is acquired.
|
||||
*
|
||||
* <p>You will never see 0 samples output (except when there have been no events since an FPGA
|
||||
* reset) and you will likely not see the stopped bit become true (since it is updated at the end
|
||||
* of an average and there are no samples to average).
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @param enabled true to enable counter updating with no samples
|
||||
* @see "HAL_SetCounterUpdateWhenEmpty"
|
||||
*/
|
||||
public static native void setCounterUpdateWhenEmpty(int counterHandle, boolean enabled);
|
||||
|
||||
/**
|
||||
* Determines if the clock is stopped.
|
||||
*
|
||||
@@ -266,27 +99,6 @@ public class CounterJNI extends JNIWrapper {
|
||||
*/
|
||||
public static native boolean getCounterStopped(int counterHandle);
|
||||
|
||||
/**
|
||||
* Gets the last direction the counter value changed.
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @return the last direction the counter value changed
|
||||
* @see "HAL_GetCounterDirection"
|
||||
*/
|
||||
public static native boolean getCounterDirection(int counterHandle);
|
||||
|
||||
/**
|
||||
* Sets the Counter to return reversed sensing on the direction.
|
||||
*
|
||||
* <p>This allows counters to change the direction they are counting in the case of 1X and 2X
|
||||
* quadrature encoding only. Any other counter mode isn't supported.
|
||||
*
|
||||
* @param counterHandle the counter handle
|
||||
* @param reverseDirection true if the value counted should be negated.
|
||||
* @see "HAL_SetCounterReverseDirection"
|
||||
*/
|
||||
public static native void setCounterReverseDirection(int counterHandle, boolean reverseDirection);
|
||||
|
||||
/** Utility class. */
|
||||
private CounterJNI() {}
|
||||
}
|
||||
|
||||
@@ -6,23 +6,13 @@
|
||||
|
||||
#include <cassert>
|
||||
|
||||
#include <wpi/jni_util.h>
|
||||
|
||||
#include "HALUtil.h"
|
||||
#include "edu_wpi_first_hal_CounterJNI.h"
|
||||
#include "hal/Counter.h"
|
||||
#include "hal/Errors.h"
|
||||
|
||||
static_assert(HAL_Counter_Mode::HAL_Counter_kTwoPulse ==
|
||||
edu_wpi_first_hal_CounterJNI_TWO_PULSE);
|
||||
|
||||
static_assert(HAL_Counter_Mode::HAL_Counter_kSemiperiod ==
|
||||
edu_wpi_first_hal_CounterJNI_SEMI_PERIOD);
|
||||
|
||||
static_assert(HAL_Counter_Mode::HAL_Counter_kPulseLength ==
|
||||
edu_wpi_first_hal_CounterJNI_PULSE_LENGTH);
|
||||
|
||||
static_assert(HAL_Counter_Mode::HAL_Counter_kExternalDirection ==
|
||||
edu_wpi_first_hal_CounterJNI_EXTERNAL_DIRECTION);
|
||||
|
||||
using namespace hal;
|
||||
|
||||
extern "C" {
|
||||
@@ -30,16 +20,16 @@ extern "C" {
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: initializeCounter
|
||||
* Signature: (ILjava/lang/Object;)I
|
||||
* Signature: (IZ)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_initializeCounter
|
||||
(JNIEnv* env, jclass, jint mode, jobject index)
|
||||
(JNIEnv* env, jclass, jint channel, jboolean risingEdge)
|
||||
{
|
||||
jint* indexPtr = reinterpret_cast<jint*>(env->GetDirectBufferAddress(index));
|
||||
int32_t status = 0;
|
||||
auto counter = HAL_InitializeCounter(
|
||||
(HAL_Counter_Mode)mode, reinterpret_cast<int32_t*>(indexPtr), &status);
|
||||
auto stack = wpi::java::GetJavaStackTrace(env, "edu.wpi.first");
|
||||
auto counter =
|
||||
HAL_InitializeCounter(channel, risingEdge, stack.c_str(), &status);
|
||||
CheckStatusForceThrow(env, status);
|
||||
return (jint)counter;
|
||||
}
|
||||
@@ -60,192 +50,15 @@ Java_edu_wpi_first_hal_CounterJNI_freeCounter
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: setCounterAverageSize
|
||||
* Signature: (II)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_setCounterAverageSize
|
||||
(JNIEnv* env, jclass, jint id, jint value)
|
||||
{
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterAverageSize((HAL_CounterHandle)id, value, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: setCounterUpSource
|
||||
* Signature: (III)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_setCounterUpSource
|
||||
(JNIEnv* env, jclass, jint id, jint digitalSourceHandle,
|
||||
jint analogTriggerType)
|
||||
{
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterUpSource((HAL_CounterHandle)id, (HAL_Handle)digitalSourceHandle,
|
||||
(HAL_AnalogTriggerType)analogTriggerType, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: setCounterUpSourceEdge
|
||||
* Signature: (IZZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_setCounterUpSourceEdge
|
||||
(JNIEnv* env, jclass, jint id, jboolean valueRise, jboolean valueFall)
|
||||
{
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterUpSourceEdge((HAL_CounterHandle)id, valueRise, valueFall,
|
||||
&status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: clearCounterUpSource
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_clearCounterUpSource
|
||||
(JNIEnv* env, jclass, jint id)
|
||||
{
|
||||
int32_t status = 0;
|
||||
HAL_ClearCounterUpSource((HAL_CounterHandle)id, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: setCounterDownSource
|
||||
* Signature: (III)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_setCounterDownSource
|
||||
(JNIEnv* env, jclass, jint id, jint digitalSourceHandle,
|
||||
jint analogTriggerType)
|
||||
{
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterDownSource((HAL_CounterHandle)id,
|
||||
(HAL_Handle)digitalSourceHandle,
|
||||
(HAL_AnalogTriggerType)analogTriggerType, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: setCounterDownSourceEdge
|
||||
* Signature: (IZZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_setCounterDownSourceEdge
|
||||
(JNIEnv* env, jclass, jint id, jboolean valueRise, jboolean valueFall)
|
||||
{
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterDownSourceEdge((HAL_CounterHandle)id, valueRise, valueFall,
|
||||
&status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: clearCounterDownSource
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_clearCounterDownSource
|
||||
(JNIEnv* env, jclass, jint id)
|
||||
{
|
||||
int32_t status = 0;
|
||||
HAL_ClearCounterDownSource((HAL_CounterHandle)id, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: setCounterUpDownMode
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_setCounterUpDownMode
|
||||
(JNIEnv* env, jclass, jint id)
|
||||
{
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterUpDownMode((HAL_CounterHandle)id, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: setCounterExternalDirectionMode
|
||||
* Signature: (I)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_setCounterExternalDirectionMode
|
||||
(JNIEnv* env, jclass, jint id)
|
||||
{
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterExternalDirectionMode((HAL_CounterHandle)id, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: setCounterSemiPeriodMode
|
||||
* Method: setCounterEdgeConfiguration
|
||||
* Signature: (IZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_setCounterSemiPeriodMode
|
||||
(JNIEnv* env, jclass, jint id, jboolean value)
|
||||
Java_edu_wpi_first_hal_CounterJNI_setCounterEdgeConfiguration
|
||||
(JNIEnv* env, jclass, jint id, jboolean valueRise)
|
||||
{
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterSemiPeriodMode((HAL_CounterHandle)id, value, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: setCounterPulseLengthMode
|
||||
* Signature: (ID)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_setCounterPulseLengthMode
|
||||
(JNIEnv* env, jclass, jint id, jdouble value)
|
||||
{
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterPulseLengthMode((HAL_CounterHandle)id, value, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: getCounterSamplesToAverage
|
||||
* Signature: (I)I
|
||||
*/
|
||||
JNIEXPORT jint JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_getCounterSamplesToAverage
|
||||
(JNIEnv* env, jclass, jint id)
|
||||
{
|
||||
int32_t status = 0;
|
||||
jint returnValue =
|
||||
HAL_GetCounterSamplesToAverage((HAL_CounterHandle)id, &status);
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: setCounterSamplesToAverage
|
||||
* Signature: (II)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_setCounterSamplesToAverage
|
||||
(JNIEnv* env, jclass, jint id, jint value)
|
||||
{
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterSamplesToAverage((HAL_CounterHandle)id, value, &status);
|
||||
HAL_SetCounterEdgeConfiguration((HAL_CounterHandle)id, valueRise, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
@@ -307,20 +120,6 @@ Java_edu_wpi_first_hal_CounterJNI_setCounterMaxPeriod
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: setCounterUpdateWhenEmpty
|
||||
* Signature: (IZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_setCounterUpdateWhenEmpty
|
||||
(JNIEnv* env, jclass, jint id, jboolean value)
|
||||
{
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterUpdateWhenEmpty((HAL_CounterHandle)id, value, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: getCounterStopped
|
||||
@@ -336,34 +135,4 @@ Java_edu_wpi_first_hal_CounterJNI_getCounterStopped
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: getCounterDirection
|
||||
* Signature: (I)Z
|
||||
*/
|
||||
JNIEXPORT jboolean JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_getCounterDirection
|
||||
(JNIEnv* env, jclass, jint id)
|
||||
{
|
||||
int32_t status = 0;
|
||||
jboolean returnValue =
|
||||
HAL_GetCounterDirection((HAL_CounterHandle)id, &status);
|
||||
CheckStatus(env, status);
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_hal_CounterJNI
|
||||
* Method: setCounterReverseDirection
|
||||
* Signature: (IZ)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_hal_CounterJNI_setCounterReverseDirection
|
||||
(JNIEnv* env, jclass, jint id, jboolean value)
|
||||
{
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterReverseDirection((HAL_CounterHandle)id, value, &status);
|
||||
CheckStatus(env, status);
|
||||
}
|
||||
|
||||
} // extern "C"
|
||||
|
||||
@@ -15,20 +15,6 @@
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* The counter mode.
|
||||
*/
|
||||
HAL_ENUM(HAL_Counter_Mode) {
|
||||
/** Two pulse mode. */
|
||||
HAL_Counter_kTwoPulse = 0,
|
||||
/** Semi-period mode. */
|
||||
HAL_Counter_kSemiperiod = 1,
|
||||
/** Pulse length mode. */
|
||||
HAL_Counter_kPulseLength = 2,
|
||||
/** External direction mode. */
|
||||
HAL_Counter_kExternalDirection = 3
|
||||
};
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
@@ -36,12 +22,16 @@ extern "C" {
|
||||
/**
|
||||
* Initializes a counter.
|
||||
*
|
||||
* @param[in] mode the counter mode
|
||||
* @param[in] index the compressor index (output)
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
* @param[in] channel the dio channel
|
||||
* @param[in] risingEdge true to count on rising edge, false for
|
||||
* falling
|
||||
* @param[in] allocationLocation the location where the allocation is
|
||||
* occurring (can be null)
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
* @return the created handle
|
||||
*/
|
||||
HAL_CounterHandle HAL_InitializeCounter(HAL_Counter_Mode mode, int32_t* index,
|
||||
HAL_CounterHandle HAL_InitializeCounter(int channel, HAL_Bool risingEdge,
|
||||
const char* allocationLocation,
|
||||
int32_t* status);
|
||||
|
||||
/**
|
||||
@@ -51,32 +41,6 @@ HAL_CounterHandle HAL_InitializeCounter(HAL_Counter_Mode mode, int32_t* index,
|
||||
*/
|
||||
void HAL_FreeCounter(HAL_CounterHandle counterHandle);
|
||||
|
||||
/**
|
||||
* Sets the average sample size of a counter.
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[in] size the size of samples to average
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
*/
|
||||
void HAL_SetCounterAverageSize(HAL_CounterHandle counterHandle, int32_t size,
|
||||
int32_t* status);
|
||||
|
||||
/**
|
||||
* Sets the source object that causes the counter to count up.
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[in] digitalSourceHandle the digital source handle (either a
|
||||
* HAL_AnalogTriggerHandle or a
|
||||
* HAL_DigitalHandle)
|
||||
* @param[in] analogTriggerType the analog trigger type if the source is an
|
||||
* analog trigger
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
*/
|
||||
void HAL_SetCounterUpSource(HAL_CounterHandle counterHandle,
|
||||
HAL_Handle digitalSourceHandle,
|
||||
HAL_AnalogTriggerType analogTriggerType,
|
||||
int32_t* status);
|
||||
|
||||
/**
|
||||
* Sets the up source to either detect rising edges or falling edges.
|
||||
*
|
||||
@@ -84,132 +48,10 @@ void HAL_SetCounterUpSource(HAL_CounterHandle counterHandle,
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[in] risingEdge true to trigger on rising
|
||||
* @param[in] fallingEdge true to trigger on falling
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
*/
|
||||
void HAL_SetCounterUpSourceEdge(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool risingEdge, HAL_Bool fallingEdge,
|
||||
int32_t* status);
|
||||
|
||||
/**
|
||||
* Disables the up counting source to the counter.
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
*/
|
||||
void HAL_ClearCounterUpSource(HAL_CounterHandle counterHandle, int32_t* status);
|
||||
|
||||
/**
|
||||
* Sets the source object that causes the counter to count down.
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[in] digitalSourceHandle the digital source handle (either a
|
||||
* HAL_AnalogTriggerHandle or a
|
||||
* HAL_DigitalHandle)
|
||||
* @param[in] analogTriggerType the analog trigger type if the source is an
|
||||
* analog trigger
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
*/
|
||||
void HAL_SetCounterDownSource(HAL_CounterHandle counterHandle,
|
||||
HAL_Handle digitalSourceHandle,
|
||||
HAL_AnalogTriggerType analogTriggerType,
|
||||
int32_t* status);
|
||||
|
||||
/**
|
||||
* Sets the down source to either detect rising edges or falling edges.
|
||||
* Note that both are allowed to be set true at the same time without issues.
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[in] risingEdge true to trigger on rising
|
||||
* @param[in] fallingEdge true to trigger on falling
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
*/
|
||||
void HAL_SetCounterDownSourceEdge(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool risingEdge, HAL_Bool fallingEdge,
|
||||
int32_t* status);
|
||||
|
||||
/**
|
||||
* Disables the down counting source to the counter.
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
*/
|
||||
void HAL_ClearCounterDownSource(HAL_CounterHandle counterHandle,
|
||||
int32_t* status);
|
||||
|
||||
/**
|
||||
* Sets standard up / down counting mode on this counter.
|
||||
*
|
||||
* Up and down counts are sourced independently from two inputs.
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
*/
|
||||
void HAL_SetCounterUpDownMode(HAL_CounterHandle counterHandle, int32_t* status);
|
||||
|
||||
/**
|
||||
* Sets directional counting mode on this counter.
|
||||
*
|
||||
* The direction is determined by the B input, with counting happening with the
|
||||
* A input.
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
*/
|
||||
void HAL_SetCounterExternalDirectionMode(HAL_CounterHandle counterHandle,
|
||||
int32_t* status);
|
||||
|
||||
/**
|
||||
* Sets Semi-period mode on this counter.
|
||||
*
|
||||
* The counter counts up based on the time the input is triggered. High or Low
|
||||
* depends on the highSemiPeriod parameter.
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[in] highSemiPeriod true for counting when the input is high, false for
|
||||
* low
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
*/
|
||||
void HAL_SetCounterSemiPeriodMode(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool highSemiPeriod, int32_t* status);
|
||||
|
||||
/**
|
||||
* Configures the counter to count in up or down based on the length of the
|
||||
* input pulse.
|
||||
*
|
||||
* This mode is most useful for direction sensitive gear tooth sensors.
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[in] threshold The pulse length beyond which the counter counts the
|
||||
* opposite direction (seconds)
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
*/
|
||||
void HAL_SetCounterPulseLengthMode(HAL_CounterHandle counterHandle,
|
||||
double threshold, int32_t* status);
|
||||
|
||||
/**
|
||||
* Gets the Samples to Average which specifies the number of samples of the
|
||||
* timer to average when calculating the period. Perform averaging to account
|
||||
* for mechanical imperfections or as oversampling to increase resolution.
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
* @return SamplesToAverage The number of samples being averaged (from 1 to 127)
|
||||
*/
|
||||
int32_t HAL_GetCounterSamplesToAverage(HAL_CounterHandle counterHandle,
|
||||
int32_t* status);
|
||||
|
||||
/**
|
||||
* Sets the Samples to Average which specifies the number of samples of the
|
||||
* timer to average when calculating the period. Perform averaging to account
|
||||
* for mechanical imperfections or as oversampling to increase resolution.
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[in] samplesToAverage The number of samples to average from 1 to 127
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
*/
|
||||
void HAL_SetCounterSamplesToAverage(HAL_CounterHandle counterHandle,
|
||||
int32_t samplesToAverage, int32_t* status);
|
||||
void HAL_SetCounterEdgeConfiguration(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool risingEdge, int32_t* status);
|
||||
|
||||
/**
|
||||
* Resets the Counter to zero.
|
||||
@@ -261,33 +103,6 @@ double HAL_GetCounterPeriod(HAL_CounterHandle counterHandle, int32_t* status);
|
||||
void HAL_SetCounterMaxPeriod(HAL_CounterHandle counterHandle, double maxPeriod,
|
||||
int32_t* status);
|
||||
|
||||
/**
|
||||
* Selects whether you want to continue updating the event timer output when
|
||||
* there are no samples captured.
|
||||
*
|
||||
* The output of the event timer has a buffer of periods that are averaged and
|
||||
* posted to a register on the FPGA. When the timer detects that the event
|
||||
* source has stopped (based on the MaxPeriod) the buffer of samples to be
|
||||
* averaged is emptied.
|
||||
*
|
||||
* If you enable the update when empty, you will be
|
||||
* notified of the stopped source and the event time will report 0 samples.
|
||||
*
|
||||
* If you disable update when empty, the most recent average will remain on the
|
||||
* output until a new sample is acquired.
|
||||
*
|
||||
* You will never see 0 samples output (except when there have been no events
|
||||
* since an FPGA reset) and you will likely not see the stopped bit become true
|
||||
* (since it is updated at the end of an average and there are no samples to
|
||||
* average).
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[in] enabled true to enable counter updating with no samples
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
*/
|
||||
void HAL_SetCounterUpdateWhenEmpty(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool enabled, int32_t* status);
|
||||
|
||||
/**
|
||||
* Determines if the clock is stopped.
|
||||
*
|
||||
@@ -302,29 +117,6 @@ void HAL_SetCounterUpdateWhenEmpty(HAL_CounterHandle counterHandle,
|
||||
*/
|
||||
HAL_Bool HAL_GetCounterStopped(HAL_CounterHandle counterHandle,
|
||||
int32_t* status);
|
||||
|
||||
/**
|
||||
* Gets the last direction the counter value changed.
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
* @return the last direction the counter value changed
|
||||
*/
|
||||
HAL_Bool HAL_GetCounterDirection(HAL_CounterHandle counterHandle,
|
||||
int32_t* status);
|
||||
|
||||
/**
|
||||
* Sets the Counter to return reversed sensing on the direction.
|
||||
*
|
||||
* This allows counters to change the direction they are counting in the case of
|
||||
* 1X and 2X quadrature encoding only. Any other counter mode isn't supported.
|
||||
*
|
||||
* @param[in] counterHandle the counter handle
|
||||
* @param[in] reverseDirection true if the value counted should be negated.
|
||||
* @param[out] status Error status variable. 0 on success.
|
||||
*/
|
||||
void HAL_SetCounterReverseDirection(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool reverseDirection, int32_t* status);
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
|
||||
@@ -26,47 +26,15 @@ void InitializeCounter() {
|
||||
} // namespace hal::init
|
||||
|
||||
extern "C" {
|
||||
HAL_CounterHandle HAL_InitializeCounter(HAL_Counter_Mode mode, int32_t* index,
|
||||
HAL_CounterHandle HAL_InitializeCounter(int channel, HAL_Bool risingEdge,
|
||||
const char* allocationLocation,
|
||||
int32_t* status) {
|
||||
hal::init::CheckInit();
|
||||
return 0;
|
||||
}
|
||||
void HAL_FreeCounter(HAL_CounterHandle counterHandle) {}
|
||||
void HAL_SetCounterAverageSize(HAL_CounterHandle counterHandle, int32_t size,
|
||||
int32_t* status) {}
|
||||
void HAL_SetCounterUpSource(HAL_CounterHandle counterHandle,
|
||||
HAL_Handle digitalSourceHandle,
|
||||
HAL_AnalogTriggerType analogTriggerType,
|
||||
int32_t* status) {}
|
||||
void HAL_SetCounterUpSourceEdge(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool risingEdge, HAL_Bool fallingEdge,
|
||||
int32_t* status) {}
|
||||
void HAL_ClearCounterUpSource(HAL_CounterHandle counterHandle,
|
||||
int32_t* status) {}
|
||||
void HAL_SetCounterDownSource(HAL_CounterHandle counterHandle,
|
||||
HAL_Handle digitalSourceHandle,
|
||||
HAL_AnalogTriggerType analogTriggerType,
|
||||
int32_t* status) {}
|
||||
void HAL_SetCounterDownSourceEdge(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool risingEdge, HAL_Bool fallingEdge,
|
||||
int32_t* status) {}
|
||||
void HAL_ClearCounterDownSource(HAL_CounterHandle counterHandle,
|
||||
int32_t* status) {}
|
||||
void HAL_SetCounterUpDownMode(HAL_CounterHandle counterHandle,
|
||||
int32_t* status) {}
|
||||
void HAL_SetCounterExternalDirectionMode(HAL_CounterHandle counterHandle,
|
||||
int32_t* status) {}
|
||||
void HAL_SetCounterSemiPeriodMode(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool highSemiPeriod, int32_t* status) {}
|
||||
void HAL_SetCounterPulseLengthMode(HAL_CounterHandle counterHandle,
|
||||
double threshold, int32_t* status) {}
|
||||
int32_t HAL_GetCounterSamplesToAverage(HAL_CounterHandle counterHandle,
|
||||
int32_t* status) {
|
||||
return 0;
|
||||
}
|
||||
void HAL_SetCounterSamplesToAverage(HAL_CounterHandle counterHandle,
|
||||
int32_t samplesToAverage, int32_t* status) {
|
||||
}
|
||||
void HAL_SetCounterEdgeConfiguration(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool risingEdge, int32_t* status) {}
|
||||
void HAL_ResetCounter(HAL_CounterHandle counterHandle, int32_t* status) {}
|
||||
int32_t HAL_GetCounter(HAL_CounterHandle counterHandle, int32_t* status) {
|
||||
return 0;
|
||||
@@ -76,17 +44,8 @@ double HAL_GetCounterPeriod(HAL_CounterHandle counterHandle, int32_t* status) {
|
||||
}
|
||||
void HAL_SetCounterMaxPeriod(HAL_CounterHandle counterHandle, double maxPeriod,
|
||||
int32_t* status) {}
|
||||
void HAL_SetCounterUpdateWhenEmpty(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool enabled, int32_t* status) {}
|
||||
HAL_Bool HAL_GetCounterStopped(HAL_CounterHandle counterHandle,
|
||||
int32_t* status) {
|
||||
return false;
|
||||
}
|
||||
HAL_Bool HAL_GetCounterDirection(HAL_CounterHandle counterHandle,
|
||||
int32_t* status) {
|
||||
return false;
|
||||
}
|
||||
void HAL_SetCounterReverseDirection(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool reverseDirection,
|
||||
int32_t* status) {}
|
||||
} // extern "C"
|
||||
|
||||
@@ -4,15 +4,19 @@
|
||||
|
||||
#include "hal/Counter.h"
|
||||
|
||||
#include <cstdio>
|
||||
#include <limits>
|
||||
#include <memory>
|
||||
#include <thread>
|
||||
|
||||
#include <fmt/format.h>
|
||||
|
||||
#include "HALInitializer.h"
|
||||
#include "HALInternal.h"
|
||||
#include "PortsInternal.h"
|
||||
#include "SmartIo.h"
|
||||
#include "hal/HAL.h"
|
||||
#include "hal/cpp/fpga_clock.h"
|
||||
#include "hal/handles/LimitedHandleResource.h"
|
||||
|
||||
using namespace hal;
|
||||
@@ -23,106 +27,90 @@ void InitializeCounter() {}
|
||||
|
||||
extern "C" {
|
||||
|
||||
HAL_CounterHandle HAL_InitializeCounter(HAL_Counter_Mode mode, int32_t* index,
|
||||
HAL_CounterHandle HAL_InitializeCounter(int channel, HAL_Bool risingEdge,
|
||||
const char* allocationLocation,
|
||||
int32_t* status) {
|
||||
hal::init::CheckInit();
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return HAL_kInvalidHandle;
|
||||
if (channel == InvalidHandleIndex || channel >= kNumSmartIo) {
|
||||
*status = RESOURCE_OUT_OF_RANGE;
|
||||
hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Counter", 0,
|
||||
kNumSmartIo, channel);
|
||||
return HAL_kInvalidHandle;
|
||||
}
|
||||
|
||||
HAL_CounterHandle handle;
|
||||
|
||||
auto port = smartIoHandles->Allocate(channel, HAL_HandleEnum::Counter,
|
||||
&handle, status);
|
||||
|
||||
if (*status != 0) {
|
||||
if (port) {
|
||||
hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel,
|
||||
port->previousAllocation);
|
||||
} else {
|
||||
hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Counter", 0,
|
||||
kNumSmartIo, channel);
|
||||
}
|
||||
return HAL_kInvalidHandle; // failed to allocate. Pass error back.
|
||||
}
|
||||
|
||||
port->channel = channel;
|
||||
|
||||
*status =
|
||||
port->InitializeMode(risingEdge ? SmartIoMode::SingleCounterRising
|
||||
: SmartIoMode::SingleCounterFalling);
|
||||
if (*status != 0) {
|
||||
smartIoHandles->Free(handle, HAL_HandleEnum::Counter);
|
||||
return HAL_kInvalidHandle;
|
||||
}
|
||||
|
||||
port->previousAllocation = allocationLocation ? allocationLocation : "";
|
||||
|
||||
return handle;
|
||||
}
|
||||
|
||||
void HAL_FreeCounter(HAL_CounterHandle counterHandle) {}
|
||||
void HAL_FreeCounter(HAL_CounterHandle counterHandle) {
|
||||
auto port = smartIoHandles->Get(counterHandle, HAL_HandleEnum::Counter);
|
||||
if (port == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
void HAL_SetCounterAverageSize(HAL_CounterHandle counterHandle, int32_t size,
|
||||
int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return;
|
||||
smartIoHandles->Free(counterHandle, HAL_HandleEnum::Counter);
|
||||
|
||||
// Wait for no other object to hold this handle.
|
||||
auto start = hal::fpga_clock::now();
|
||||
while (port.use_count() != 1) {
|
||||
auto current = hal::fpga_clock::now();
|
||||
if (start + std::chrono::seconds(1) < current) {
|
||||
std::puts("DIO handle free timeout");
|
||||
std::fflush(stdout);
|
||||
break;
|
||||
}
|
||||
std::this_thread::yield();
|
||||
}
|
||||
}
|
||||
|
||||
void HAL_SetCounterUpSource(HAL_CounterHandle counterHandle,
|
||||
HAL_Handle digitalSourceHandle,
|
||||
HAL_AnalogTriggerType analogTriggerType,
|
||||
int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return;
|
||||
}
|
||||
|
||||
void HAL_SetCounterUpSourceEdge(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool risingEdge, HAL_Bool fallingEdge,
|
||||
int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return;
|
||||
}
|
||||
|
||||
void HAL_ClearCounterUpSource(HAL_CounterHandle counterHandle,
|
||||
int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return;
|
||||
}
|
||||
|
||||
void HAL_SetCounterDownSource(HAL_CounterHandle counterHandle,
|
||||
HAL_Handle digitalSourceHandle,
|
||||
HAL_AnalogTriggerType analogTriggerType,
|
||||
int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return;
|
||||
}
|
||||
|
||||
void HAL_SetCounterDownSourceEdge(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool risingEdge, HAL_Bool fallingEdge,
|
||||
int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return;
|
||||
}
|
||||
|
||||
void HAL_ClearCounterDownSource(HAL_CounterHandle counterHandle,
|
||||
int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return;
|
||||
}
|
||||
|
||||
void HAL_SetCounterUpDownMode(HAL_CounterHandle counterHandle,
|
||||
int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return;
|
||||
}
|
||||
|
||||
void HAL_SetCounterExternalDirectionMode(HAL_CounterHandle counterHandle,
|
||||
int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return;
|
||||
}
|
||||
|
||||
void HAL_SetCounterSemiPeriodMode(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool highSemiPeriod, int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return;
|
||||
}
|
||||
|
||||
void HAL_SetCounterPulseLengthMode(HAL_CounterHandle counterHandle,
|
||||
double threshold, int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return;
|
||||
}
|
||||
|
||||
int32_t HAL_GetCounterSamplesToAverage(HAL_CounterHandle counterHandle,
|
||||
int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return 0;
|
||||
}
|
||||
|
||||
void HAL_SetCounterSamplesToAverage(HAL_CounterHandle counterHandle,
|
||||
int32_t samplesToAverage, int32_t* status) {
|
||||
void HAL_SetCounterEdgeConfiguration(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool risingEdge, int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return;
|
||||
}
|
||||
|
||||
void HAL_ResetCounter(HAL_CounterHandle counterHandle, int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
// TODO
|
||||
return;
|
||||
}
|
||||
|
||||
int32_t HAL_GetCounter(HAL_CounterHandle counterHandle, int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
auto port = smartIoHandles->Get(counterHandle, HAL_HandleEnum::Counter);
|
||||
if (port == nullptr) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return false;
|
||||
}
|
||||
|
||||
int32_t ret = 0;
|
||||
*status = port->GetCounter(&ret);
|
||||
return ret;
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -137,12 +125,6 @@ void HAL_SetCounterMaxPeriod(HAL_CounterHandle counterHandle, double maxPeriod,
|
||||
return;
|
||||
}
|
||||
|
||||
void HAL_SetCounterUpdateWhenEmpty(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool enabled, int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return;
|
||||
}
|
||||
|
||||
HAL_Bool HAL_GetCounterStopped(HAL_CounterHandle counterHandle,
|
||||
int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
@@ -155,9 +137,8 @@ HAL_Bool HAL_GetCounterDirection(HAL_CounterHandle counterHandle,
|
||||
return false;
|
||||
}
|
||||
|
||||
void HAL_SetCounterReverseDirection(HAL_CounterHandle counterHandle,
|
||||
HAL_Bool reverseDirection,
|
||||
int32_t* status) {
|
||||
void HAL_SetCounterDirection(HAL_CounterHandle counterHandle, HAL_Bool countUp,
|
||||
int32_t* status) {
|
||||
*status = HAL_HANDLE_ERROR;
|
||||
return;
|
||||
}
|
||||
|
||||
@@ -164,4 +164,17 @@ int32_t SmartIo::GetAnalogInput(uint16_t* value) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
int32_t SmartIo::GetCounter(int32_t* value) {
|
||||
if (currentMode != SmartIoMode::SingleCounterFalling &&
|
||||
currentMode != SmartIoMode::SingleCounterRising) {
|
||||
return INCOMPATIBLE_STATE;
|
||||
}
|
||||
|
||||
int32_t val = getSubscriber.Get();
|
||||
|
||||
*value = val;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
} // namespace hal
|
||||
|
||||
@@ -66,6 +66,8 @@ struct SmartIo {
|
||||
int32_t GetPwmMicroseconds(uint16_t* microseconds);
|
||||
|
||||
int32_t GetAnalogInput(uint16_t* value);
|
||||
|
||||
int32_t GetCounter(int32_t* count);
|
||||
};
|
||||
|
||||
extern DigitalHandleResource<HAL_DigitalHandle, SmartIo, kNumSmartIo>*
|
||||
|
||||
@@ -72,7 +72,7 @@ def tagList = [
|
||||
"LQR", "Pose Estimator",
|
||||
|
||||
/* --- Hardware --- */
|
||||
"Analog", "Ultrasonic", "Gyro", "Pneumatics", "I2C", "Duty Cycle", "PDP",
|
||||
"Analog", "Gyro", "Pneumatics", "I2C", "Duty Cycle", "PDP",
|
||||
"AddressableLEDs", "HAL", "Encoder", "Smart Motor Controller", "Digital Input",
|
||||
"Digital Output",
|
||||
|
||||
|
||||
@@ -90,10 +90,6 @@
|
||||
<Bug pattern="SF_SWITCH_FALLTHROUGH" />
|
||||
<Source name="CameraServer.java" />
|
||||
</Match>
|
||||
<Match>
|
||||
<Bug pattern="SSD_DO_NOT_USE_INSTANCE_LOCK_ON_SHARED_STATIC_DATA" />
|
||||
<Source name="Ultrasonic.java" />
|
||||
</Match>
|
||||
<Match>
|
||||
<Bug pattern="ST_WRITE_TO_STATIC_FROM_INSTANCE_METHOD" />
|
||||
</Match>
|
||||
|
||||
@@ -1,322 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "frc/Counter.h"
|
||||
|
||||
#include <memory>
|
||||
|
||||
#include <hal/Counter.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <wpi/NullDeleter.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
|
||||
#include "frc/AnalogTrigger.h"
|
||||
#include "frc/DigitalInput.h"
|
||||
#include "frc/Errors.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
Counter::Counter(Mode mode) {
|
||||
int32_t status = 0;
|
||||
m_counter = HAL_InitializeCounter(static_cast<HAL_Counter_Mode>(mode),
|
||||
&m_index, &status);
|
||||
FRC_CheckErrorStatus(status, "InitializeCounter");
|
||||
|
||||
SetMaxPeriod(0.5_s);
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_Counter, m_index + 1, mode + 1);
|
||||
wpi::SendableRegistry::Add(this, "Counter", m_index);
|
||||
}
|
||||
|
||||
Counter::Counter(int channel) : Counter(kTwoPulse) {
|
||||
SetUpSource(channel);
|
||||
ClearDownSource();
|
||||
}
|
||||
|
||||
Counter::Counter(DigitalSource* source) : Counter(kTwoPulse) {
|
||||
SetUpSource(source);
|
||||
ClearDownSource();
|
||||
}
|
||||
|
||||
Counter::Counter(std::shared_ptr<DigitalSource> source) : Counter(kTwoPulse) {
|
||||
SetUpSource(source);
|
||||
ClearDownSource();
|
||||
}
|
||||
|
||||
Counter::Counter(const AnalogTrigger& trigger) : Counter(kTwoPulse) {
|
||||
SetUpSource(trigger.CreateOutput(AnalogTriggerType::kState));
|
||||
ClearDownSource();
|
||||
}
|
||||
|
||||
Counter::Counter(EncodingType encodingType, DigitalSource* upSource,
|
||||
DigitalSource* downSource, bool inverted)
|
||||
: Counter(encodingType,
|
||||
std::shared_ptr<DigitalSource>(upSource,
|
||||
wpi::NullDeleter<DigitalSource>()),
|
||||
std::shared_ptr<DigitalSource>(downSource,
|
||||
wpi::NullDeleter<DigitalSource>()),
|
||||
inverted) {}
|
||||
|
||||
Counter::Counter(EncodingType encodingType,
|
||||
std::shared_ptr<DigitalSource> upSource,
|
||||
std::shared_ptr<DigitalSource> downSource, bool inverted)
|
||||
: Counter(kExternalDirection) {
|
||||
if (encodingType != k1X && encodingType != k2X) {
|
||||
throw FRC_MakeError(err::ParameterOutOfRange,
|
||||
"Counter only supports 1X and 2X quadrature decoding");
|
||||
}
|
||||
SetUpSource(upSource);
|
||||
SetDownSource(downSource);
|
||||
int32_t status = 0;
|
||||
|
||||
if (encodingType == k1X) {
|
||||
SetUpSourceEdge(true, false);
|
||||
HAL_SetCounterAverageSize(m_counter, 1, &status);
|
||||
} else {
|
||||
SetUpSourceEdge(true, true);
|
||||
HAL_SetCounterAverageSize(m_counter, 2, &status);
|
||||
}
|
||||
|
||||
FRC_CheckErrorStatus(status, "Counter constructor");
|
||||
SetDownSourceEdge(inverted, true);
|
||||
}
|
||||
|
||||
Counter::~Counter() {
|
||||
if (m_counter != HAL_kInvalidHandle) {
|
||||
try {
|
||||
SetUpdateWhenEmpty(true);
|
||||
} catch (const RuntimeError& e) {
|
||||
e.Report();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void Counter::SetUpSource(int channel) {
|
||||
SetUpSource(std::make_shared<DigitalInput>(channel));
|
||||
wpi::SendableRegistry::AddChild(this, m_upSource.get());
|
||||
}
|
||||
|
||||
void Counter::SetUpSource(AnalogTrigger* analogTrigger,
|
||||
AnalogTriggerType triggerType) {
|
||||
SetUpSource(std::shared_ptr<AnalogTrigger>(analogTrigger,
|
||||
wpi::NullDeleter<AnalogTrigger>()),
|
||||
triggerType);
|
||||
}
|
||||
|
||||
void Counter::SetUpSource(std::shared_ptr<AnalogTrigger> analogTrigger,
|
||||
AnalogTriggerType triggerType) {
|
||||
SetUpSource(analogTrigger->CreateOutput(triggerType));
|
||||
}
|
||||
|
||||
void Counter::SetUpSource(DigitalSource* source) {
|
||||
SetUpSource(std::shared_ptr<DigitalSource>(
|
||||
source, wpi::NullDeleter<DigitalSource>()));
|
||||
}
|
||||
|
||||
void Counter::SetUpSource(std::shared_ptr<DigitalSource> source) {
|
||||
m_upSource = source;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterUpSource(m_counter, source->GetPortHandleForRouting(),
|
||||
static_cast<HAL_AnalogTriggerType>(
|
||||
source->GetAnalogTriggerTypeForRouting()),
|
||||
&status);
|
||||
FRC_CheckErrorStatus(status, "SetUpSource");
|
||||
}
|
||||
|
||||
void Counter::SetUpSource(DigitalSource& source) {
|
||||
SetUpSource(std::shared_ptr<DigitalSource>(
|
||||
&source, wpi::NullDeleter<DigitalSource>()));
|
||||
}
|
||||
|
||||
void Counter::SetUpSourceEdge(bool risingEdge, bool fallingEdge) {
|
||||
if (m_upSource == nullptr) {
|
||||
throw FRC_MakeError(
|
||||
err::NullParameter,
|
||||
"Must set non-nullptr UpSource before setting UpSourceEdge");
|
||||
}
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterUpSourceEdge(m_counter, risingEdge, fallingEdge, &status);
|
||||
FRC_CheckErrorStatus(status, "SetUpSourceEdge");
|
||||
}
|
||||
|
||||
void Counter::ClearUpSource() {
|
||||
m_upSource.reset();
|
||||
int32_t status = 0;
|
||||
HAL_ClearCounterUpSource(m_counter, &status);
|
||||
FRC_CheckErrorStatus(status, "ClearUpSource");
|
||||
}
|
||||
|
||||
void Counter::SetDownSource(int channel) {
|
||||
SetDownSource(std::make_shared<DigitalInput>(channel));
|
||||
wpi::SendableRegistry::AddChild(this, m_downSource.get());
|
||||
}
|
||||
|
||||
void Counter::SetDownSource(AnalogTrigger* analogTrigger,
|
||||
AnalogTriggerType triggerType) {
|
||||
SetDownSource(std::shared_ptr<AnalogTrigger>(
|
||||
analogTrigger, wpi::NullDeleter<AnalogTrigger>()),
|
||||
triggerType);
|
||||
}
|
||||
|
||||
void Counter::SetDownSource(std::shared_ptr<AnalogTrigger> analogTrigger,
|
||||
AnalogTriggerType triggerType) {
|
||||
SetDownSource(analogTrigger->CreateOutput(triggerType));
|
||||
}
|
||||
|
||||
void Counter::SetDownSource(DigitalSource* source) {
|
||||
SetDownSource(std::shared_ptr<DigitalSource>(
|
||||
source, wpi::NullDeleter<DigitalSource>()));
|
||||
}
|
||||
|
||||
void Counter::SetDownSource(DigitalSource& source) {
|
||||
SetDownSource(std::shared_ptr<DigitalSource>(
|
||||
&source, wpi::NullDeleter<DigitalSource>()));
|
||||
}
|
||||
|
||||
void Counter::SetDownSource(std::shared_ptr<DigitalSource> source) {
|
||||
m_downSource = source;
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterDownSource(m_counter, source->GetPortHandleForRouting(),
|
||||
static_cast<HAL_AnalogTriggerType>(
|
||||
source->GetAnalogTriggerTypeForRouting()),
|
||||
&status);
|
||||
FRC_CheckErrorStatus(status, "SetDownSource");
|
||||
}
|
||||
|
||||
void Counter::SetDownSourceEdge(bool risingEdge, bool fallingEdge) {
|
||||
if (m_downSource == nullptr) {
|
||||
throw FRC_MakeError(
|
||||
err::NullParameter,
|
||||
"Must set non-nullptr DownSource before setting DownSourceEdge");
|
||||
}
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterDownSourceEdge(m_counter, risingEdge, fallingEdge, &status);
|
||||
FRC_CheckErrorStatus(status, "SetDownSourceEdge");
|
||||
}
|
||||
|
||||
void Counter::ClearDownSource() {
|
||||
m_downSource.reset();
|
||||
int32_t status = 0;
|
||||
HAL_ClearCounterDownSource(m_counter, &status);
|
||||
FRC_CheckErrorStatus(status, "ClearDownSource");
|
||||
}
|
||||
|
||||
void Counter::SetUpDownCounterMode() {
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterUpDownMode(m_counter, &status);
|
||||
FRC_CheckErrorStatus(status, "SetUpDownCounterMode");
|
||||
}
|
||||
|
||||
void Counter::SetExternalDirectionMode() {
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterExternalDirectionMode(m_counter, &status);
|
||||
FRC_CheckErrorStatus(status, "SetExternalDirectionMode");
|
||||
}
|
||||
|
||||
void Counter::SetSemiPeriodMode(bool highSemiPeriod) {
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterSemiPeriodMode(m_counter, highSemiPeriod, &status);
|
||||
FRC_CheckErrorStatus(status, "SetSemiPeriodMode to {}",
|
||||
highSemiPeriod ? "true" : "false");
|
||||
}
|
||||
|
||||
void Counter::SetPulseLengthMode(double threshold) {
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterPulseLengthMode(m_counter, threshold, &status);
|
||||
FRC_CheckErrorStatus(status, "SetPulseLengthMode");
|
||||
}
|
||||
|
||||
void Counter::SetReverseDirection(bool reverseDirection) {
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterReverseDirection(m_counter, reverseDirection, &status);
|
||||
FRC_CheckErrorStatus(status, "SetReverseDirection to {}",
|
||||
reverseDirection ? "true" : "false");
|
||||
}
|
||||
|
||||
void Counter::SetSamplesToAverage(int samplesToAverage) {
|
||||
if (samplesToAverage < 1 || samplesToAverage > 127) {
|
||||
throw FRC_MakeError(
|
||||
err::ParameterOutOfRange,
|
||||
"Average counter values must be between 1 and 127, {} out of range",
|
||||
samplesToAverage);
|
||||
}
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterSamplesToAverage(m_counter, samplesToAverage, &status);
|
||||
FRC_CheckErrorStatus(status, "SetSamplesToAverage to {}", samplesToAverage);
|
||||
}
|
||||
|
||||
int Counter::GetSamplesToAverage() const {
|
||||
int32_t status = 0;
|
||||
int samples = HAL_GetCounterSamplesToAverage(m_counter, &status);
|
||||
FRC_CheckErrorStatus(status, "GetSamplesToAverage");
|
||||
return samples;
|
||||
}
|
||||
|
||||
int Counter::GetFPGAIndex() const {
|
||||
return m_index;
|
||||
}
|
||||
|
||||
void Counter::SetDistancePerPulse(double distancePerPulse) {
|
||||
m_distancePerPulse = distancePerPulse;
|
||||
}
|
||||
|
||||
double Counter::GetDistance() const {
|
||||
return Get() * m_distancePerPulse;
|
||||
}
|
||||
|
||||
double Counter::GetRate() const {
|
||||
return m_distancePerPulse / GetPeriod().value();
|
||||
}
|
||||
|
||||
int Counter::Get() const {
|
||||
int32_t status = 0;
|
||||
int value = HAL_GetCounter(m_counter, &status);
|
||||
FRC_CheckErrorStatus(status, "Get");
|
||||
return value;
|
||||
}
|
||||
|
||||
void Counter::Reset() {
|
||||
int32_t status = 0;
|
||||
HAL_ResetCounter(m_counter, &status);
|
||||
FRC_CheckErrorStatus(status, "Reset");
|
||||
}
|
||||
|
||||
units::second_t Counter::GetPeriod() const {
|
||||
int32_t status = 0;
|
||||
double value = HAL_GetCounterPeriod(m_counter, &status);
|
||||
FRC_CheckErrorStatus(status, "GetPeriod");
|
||||
return units::second_t{value};
|
||||
}
|
||||
|
||||
void Counter::SetMaxPeriod(units::second_t maxPeriod) {
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterMaxPeriod(m_counter, maxPeriod.value(), &status);
|
||||
FRC_CheckErrorStatus(status, "SetMaxPeriod");
|
||||
}
|
||||
|
||||
void Counter::SetUpdateWhenEmpty(bool enabled) {
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterUpdateWhenEmpty(m_counter, enabled, &status);
|
||||
FRC_CheckErrorStatus(status, "SetUpdateWhenEmpty");
|
||||
}
|
||||
|
||||
bool Counter::GetStopped() const {
|
||||
int32_t status = 0;
|
||||
bool value = HAL_GetCounterStopped(m_counter, &status);
|
||||
FRC_CheckErrorStatus(status, "GetStopped");
|
||||
return value;
|
||||
}
|
||||
|
||||
bool Counter::GetDirection() const {
|
||||
int32_t status = 0;
|
||||
bool value = HAL_GetCounterDirection(m_counter, &status);
|
||||
FRC_CheckErrorStatus(status, "GetDirection");
|
||||
return value;
|
||||
}
|
||||
|
||||
void Counter::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("Counter");
|
||||
builder.AddDoubleProperty("Value", [=, this] { return Get(); }, nullptr);
|
||||
}
|
||||
@@ -1,203 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "frc/Ultrasonic.h"
|
||||
|
||||
#include <memory>
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <wpi/NullDeleter.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
|
||||
#include "frc/Counter.h"
|
||||
#include "frc/DigitalInput.h"
|
||||
#include "frc/DigitalOutput.h"
|
||||
#include "frc/Errors.h"
|
||||
#include "frc/Timer.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
// Automatic round robin mode
|
||||
std::atomic<bool> Ultrasonic::m_automaticEnabled{false};
|
||||
|
||||
std::vector<Ultrasonic*> Ultrasonic::m_sensors;
|
||||
std::thread Ultrasonic::m_thread;
|
||||
|
||||
Ultrasonic::Ultrasonic(int pingChannel, int echoChannel)
|
||||
: m_pingChannel(std::make_shared<DigitalOutput>(pingChannel)),
|
||||
m_echoChannel(std::make_shared<DigitalInput>(echoChannel)),
|
||||
m_counter(m_echoChannel) {
|
||||
Initialize();
|
||||
wpi::SendableRegistry::AddChild(this, m_pingChannel.get());
|
||||
wpi::SendableRegistry::AddChild(this, m_echoChannel.get());
|
||||
}
|
||||
|
||||
Ultrasonic::Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel)
|
||||
: m_pingChannel(pingChannel, wpi::NullDeleter<DigitalOutput>()),
|
||||
m_echoChannel(echoChannel, wpi::NullDeleter<DigitalInput>()),
|
||||
m_counter(m_echoChannel) {
|
||||
if (!pingChannel) {
|
||||
throw FRC_MakeError(err::NullParameter, "pingChannel");
|
||||
}
|
||||
if (!echoChannel) {
|
||||
throw FRC_MakeError(err::NullParameter, "echoChannel");
|
||||
}
|
||||
Initialize();
|
||||
}
|
||||
|
||||
Ultrasonic::Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel)
|
||||
: m_pingChannel(&pingChannel, wpi::NullDeleter<DigitalOutput>()),
|
||||
m_echoChannel(&echoChannel, wpi::NullDeleter<DigitalInput>()),
|
||||
m_counter(m_echoChannel) {
|
||||
Initialize();
|
||||
}
|
||||
|
||||
Ultrasonic::Ultrasonic(std::shared_ptr<DigitalOutput> pingChannel,
|
||||
std::shared_ptr<DigitalInput> echoChannel)
|
||||
: m_pingChannel(std::move(pingChannel)),
|
||||
m_echoChannel(std::move(echoChannel)),
|
||||
m_counter(m_echoChannel) {
|
||||
Initialize();
|
||||
}
|
||||
|
||||
Ultrasonic::~Ultrasonic() {
|
||||
// Delete the instance of the ultrasonic sensor by freeing the allocated
|
||||
// digital channels. If the system was in automatic mode (round robin), then
|
||||
// it is stopped, then started again after this sensor is removed (provided
|
||||
// this wasn't the last sensor).
|
||||
|
||||
bool wasAutomaticMode = m_automaticEnabled;
|
||||
SetAutomaticMode(false);
|
||||
|
||||
// No synchronization needed because the background task is stopped.
|
||||
m_sensors.erase(std::remove(m_sensors.begin(), m_sensors.end(), this),
|
||||
m_sensors.end());
|
||||
|
||||
if (!m_sensors.empty() && wasAutomaticMode) {
|
||||
SetAutomaticMode(true);
|
||||
}
|
||||
}
|
||||
|
||||
int Ultrasonic::GetEchoChannel() const {
|
||||
return m_echoChannel->GetChannel();
|
||||
}
|
||||
|
||||
void Ultrasonic::Ping() {
|
||||
SetAutomaticMode(false); // turn off automatic round-robin if pinging
|
||||
|
||||
// Reset the counter to zero (invalid data now)
|
||||
m_counter.Reset();
|
||||
|
||||
// Do the ping to start getting a single range
|
||||
m_pingChannel->Pulse(kPingTime);
|
||||
}
|
||||
|
||||
bool Ultrasonic::IsRangeValid() const {
|
||||
if (m_simRangeValid) {
|
||||
return m_simRangeValid.Get();
|
||||
}
|
||||
return m_counter.Get() > 1;
|
||||
}
|
||||
|
||||
void Ultrasonic::SetAutomaticMode(bool enabling) {
|
||||
if (enabling == m_automaticEnabled) {
|
||||
return; // ignore the case of no change
|
||||
}
|
||||
|
||||
m_automaticEnabled = enabling;
|
||||
|
||||
if (enabling) {
|
||||
/* Clear all the counters so no data is valid. No synchronization is needed
|
||||
* because the background task is stopped.
|
||||
*/
|
||||
for (auto& sensor : m_sensors) {
|
||||
sensor->m_counter.Reset();
|
||||
}
|
||||
|
||||
m_thread = std::thread(&Ultrasonic::UltrasonicChecker);
|
||||
} else {
|
||||
// Wait for background task to stop running
|
||||
if (m_thread.joinable()) {
|
||||
m_thread.join();
|
||||
}
|
||||
|
||||
// Clear all the counters (data now invalid) since automatic mode is
|
||||
// disabled. No synchronization is needed because the background task is
|
||||
// stopped.
|
||||
for (auto& sensor : m_sensors) {
|
||||
sensor->m_counter.Reset();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
units::meter_t Ultrasonic::GetRange() const {
|
||||
if (IsRangeValid()) {
|
||||
if (m_simRange) {
|
||||
return units::inch_t{m_simRange.Get()};
|
||||
}
|
||||
return m_counter.GetPeriod() * kSpeedOfSound / 2.0;
|
||||
} else {
|
||||
return 0_m;
|
||||
}
|
||||
}
|
||||
|
||||
bool Ultrasonic::IsEnabled() const {
|
||||
return m_enabled;
|
||||
}
|
||||
|
||||
void Ultrasonic::SetEnabled(bool enable) {
|
||||
m_enabled = enable;
|
||||
}
|
||||
|
||||
void Ultrasonic::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("Ultrasonic");
|
||||
builder.AddDoubleProperty(
|
||||
"Value", [=, this] { return units::inch_t{GetRange()}.value(); },
|
||||
nullptr);
|
||||
}
|
||||
|
||||
void Ultrasonic::Initialize() {
|
||||
m_simDevice = hal::SimDevice("Ultrasonic", m_echoChannel->GetChannel());
|
||||
if (m_simDevice) {
|
||||
m_simRangeValid = m_simDevice.CreateBoolean("Range Valid", false, true);
|
||||
m_simRange = m_simDevice.CreateDouble("Range (in)", false, 0.0);
|
||||
m_pingChannel->SetSimDevice(m_simDevice);
|
||||
m_echoChannel->SetSimDevice(m_simDevice);
|
||||
}
|
||||
|
||||
bool originalMode = m_automaticEnabled;
|
||||
SetAutomaticMode(false); // Kill task when adding a new sensor
|
||||
// Link this instance on the list
|
||||
m_sensors.emplace_back(this);
|
||||
|
||||
m_counter.SetMaxPeriod(1_s);
|
||||
m_counter.SetSemiPeriodMode(true);
|
||||
m_counter.Reset();
|
||||
m_enabled = true; // Make it available for round robin scheduling
|
||||
SetAutomaticMode(originalMode);
|
||||
|
||||
static int instances = 0;
|
||||
instances++;
|
||||
HAL_Report(HALUsageReporting::kResourceType_Ultrasonic, instances);
|
||||
wpi::SendableRegistry::Add(this, "Ultrasonic", m_echoChannel->GetChannel());
|
||||
}
|
||||
|
||||
void Ultrasonic::UltrasonicChecker() {
|
||||
while (m_automaticEnabled) {
|
||||
for (auto& sensor : m_sensors) {
|
||||
if (!m_automaticEnabled) {
|
||||
break;
|
||||
}
|
||||
|
||||
if (sensor->IsEnabled()) {
|
||||
sensor->m_pingChannel->Pulse(kPingTime); // do the ping
|
||||
}
|
||||
|
||||
Wait(100_ms); // wait for ping to return
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,99 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "frc/counter/ExternalDirectionCounter.h"
|
||||
|
||||
#include <memory>
|
||||
|
||||
#include <hal/Counter.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <wpi/NullDeleter.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
#include "frc/DigitalSource.h"
|
||||
#include "frc/Errors.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
ExternalDirectionCounter::ExternalDirectionCounter(
|
||||
DigitalSource& countSource, DigitalSource& directionSource)
|
||||
: ExternalDirectionCounter(
|
||||
{&countSource, wpi::NullDeleter<DigitalSource>()},
|
||||
{&directionSource, wpi::NullDeleter<DigitalSource>()}) {}
|
||||
|
||||
ExternalDirectionCounter::ExternalDirectionCounter(
|
||||
std::shared_ptr<DigitalSource> countSource,
|
||||
std::shared_ptr<DigitalSource> directionSource) {
|
||||
if (countSource == nullptr) {
|
||||
throw FRC_MakeError(err::NullParameter, "countSource");
|
||||
}
|
||||
if (directionSource == nullptr) {
|
||||
throw FRC_MakeError(err::NullParameter, "directionSource");
|
||||
}
|
||||
|
||||
m_countSource = countSource;
|
||||
m_directionSource = directionSource;
|
||||
|
||||
int32_t status = 0;
|
||||
m_handle = HAL_InitializeCounter(
|
||||
HAL_Counter_Mode::HAL_Counter_kExternalDirection, &m_index, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
|
||||
HAL_SetCounterUpSource(m_handle, m_countSource->GetPortHandleForRouting(),
|
||||
static_cast<HAL_AnalogTriggerType>(
|
||||
m_countSource->GetAnalogTriggerTypeForRouting()),
|
||||
&status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
HAL_SetCounterUpSourceEdge(m_handle, true, false, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
|
||||
HAL_SetCounterDownSource(
|
||||
m_handle, m_directionSource->GetPortHandleForRouting(),
|
||||
static_cast<HAL_AnalogTriggerType>(
|
||||
m_directionSource->GetAnalogTriggerTypeForRouting()),
|
||||
&status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
HAL_SetCounterDownSourceEdge(m_handle, false, true, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
|
||||
Reset();
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_Counter, m_index + 1);
|
||||
wpi::SendableRegistry::Add(this, "External Direction Counter", m_index);
|
||||
}
|
||||
|
||||
int ExternalDirectionCounter::GetCount() const {
|
||||
int32_t status = 0;
|
||||
int val = HAL_GetCounter(m_handle, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
return val;
|
||||
}
|
||||
|
||||
void ExternalDirectionCounter::SetReverseDirection(bool reverseDirection) {
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterReverseDirection(m_handle, reverseDirection, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
}
|
||||
|
||||
void ExternalDirectionCounter::Reset() {
|
||||
int32_t status = 0;
|
||||
HAL_ResetCounter(m_handle, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
}
|
||||
|
||||
void ExternalDirectionCounter::SetEdgeConfiguration(
|
||||
EdgeConfiguration configuration) {
|
||||
int32_t status = 0;
|
||||
bool rising = configuration == EdgeConfiguration::kRisingEdge ||
|
||||
configuration == EdgeConfiguration::kBoth;
|
||||
bool falling = configuration == EdgeConfiguration::kFallingEdge ||
|
||||
configuration == EdgeConfiguration::kBoth;
|
||||
HAL_SetCounterUpSourceEdge(m_handle, rising, falling, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
}
|
||||
|
||||
void ExternalDirectionCounter::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("External Direction Counter");
|
||||
builder.AddDoubleProperty("Count", [&] { return GetCount(); }, nullptr);
|
||||
}
|
||||
@@ -4,37 +4,35 @@
|
||||
|
||||
#include "frc/counter/Tachometer.h"
|
||||
|
||||
#include <frc/DigitalSource.h>
|
||||
#include <string>
|
||||
|
||||
#include <hal/Counter.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <wpi/NullDeleter.h>
|
||||
#include <wpi/StackTrace.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
#include "frc/Errors.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
Tachometer::Tachometer(DigitalSource& source)
|
||||
: Tachometer({&source, wpi::NullDeleter<DigitalSource>()}) {}
|
||||
Tachometer::Tachometer(std::shared_ptr<DigitalSource> source) {
|
||||
if (source == nullptr) {
|
||||
throw FRC_MakeError(err::NullParameter, "source");
|
||||
}
|
||||
|
||||
m_source = source;
|
||||
|
||||
Tachometer::Tachometer(int channel, EdgeConfiguration configuration)
|
||||
: m_channel{channel} {
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterUpSource(m_handle, m_source->GetPortHandleForRouting(),
|
||||
static_cast<HAL_AnalogTriggerType>(
|
||||
m_source->GetAnalogTriggerTypeForRouting()),
|
||||
&status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
HAL_SetCounterUpSourceEdge(m_handle, true, false, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
std::string stackTrace = wpi::GetStackTrace(1);
|
||||
m_handle = HAL_InitializeCounter(
|
||||
channel, configuration == EdgeConfiguration::kRisingEdge,
|
||||
stackTrace.c_str(), &status);
|
||||
FRC_CheckErrorStatus(status, "{}", channel);
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_Counter, m_index + 1);
|
||||
wpi::SendableRegistry::Add(this, "Tachometer", m_index);
|
||||
HAL_Report(HALUsageReporting::kResourceType_Counter, channel + 1);
|
||||
wpi::SendableRegistry::Add(this, "Tachometer", channel);
|
||||
}
|
||||
|
||||
void Tachometer::SetEdgeConfiguration(EdgeConfiguration configuration) {
|
||||
int32_t status = 0;
|
||||
bool rising = configuration == EdgeConfiguration::kRisingEdge;
|
||||
HAL_SetCounterEdgeConfiguration(m_handle, rising, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_channel);
|
||||
}
|
||||
|
||||
units::hertz_t Tachometer::GetFrequency() const {
|
||||
@@ -48,7 +46,7 @@ units::hertz_t Tachometer::GetFrequency() const {
|
||||
units::second_t Tachometer::GetPeriod() const {
|
||||
int32_t status = 0;
|
||||
double period = HAL_GetCounterPeriod(m_handle, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_source->GetChannel());
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
|
||||
return units::second_t{period};
|
||||
}
|
||||
|
||||
@@ -79,33 +77,14 @@ units::revolutions_per_minute_t Tachometer::GetRevolutionsPerMinute() const {
|
||||
bool Tachometer::GetStopped() const {
|
||||
int32_t status = 0;
|
||||
bool stopped = HAL_GetCounterStopped(m_handle, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_source->GetChannel());
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
|
||||
return stopped;
|
||||
}
|
||||
|
||||
int Tachometer::GetSamplesToAverage() const {
|
||||
int32_t status = 0;
|
||||
int32_t samplesToAverage = HAL_GetCounterSamplesToAverage(m_handle, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_source->GetChannel());
|
||||
return samplesToAverage;
|
||||
}
|
||||
|
||||
void Tachometer::SetSamplesToAverage(int samples) {
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterSamplesToAverage(m_handle, samples, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_source->GetChannel());
|
||||
}
|
||||
|
||||
void Tachometer::SetMaxPeriod(units::second_t maxPeriod) {
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterMaxPeriod(m_handle, maxPeriod.value(), &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_source->GetChannel());
|
||||
}
|
||||
|
||||
void Tachometer::SetUpdateWhenEmpty(bool updateWhenEmpty) {
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterUpdateWhenEmpty(m_handle, updateWhenEmpty, &status);
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_source->GetChannel());
|
||||
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
|
||||
}
|
||||
|
||||
void Tachometer::InitSendable(wpi::SendableBuilder& builder) {
|
||||
|
||||
@@ -5,10 +5,11 @@
|
||||
#include "frc/counter/UpDownCounter.h"
|
||||
|
||||
#include <memory>
|
||||
#include <string>
|
||||
|
||||
#include <hal/Counter.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <wpi/NullDeleter.h>
|
||||
#include <wpi/StackTrace.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
#include "frc/DigitalSource.h"
|
||||
@@ -16,84 +17,39 @@
|
||||
|
||||
using namespace frc;
|
||||
|
||||
UpDownCounter::UpDownCounter(DigitalSource& upSource, DigitalSource& downSource)
|
||||
: UpDownCounter({&upSource, wpi::NullDeleter<DigitalSource>()},
|
||||
{&downSource, wpi::NullDeleter<DigitalSource>()}) {}
|
||||
|
||||
UpDownCounter::UpDownCounter(std::shared_ptr<DigitalSource> upSource,
|
||||
std::shared_ptr<DigitalSource> downSource) {
|
||||
m_upSource = upSource;
|
||||
m_downSource = downSource;
|
||||
|
||||
UpDownCounter::UpDownCounter(int channel, EdgeConfiguration configuration)
|
||||
: m_channel{channel} {
|
||||
int32_t status = 0;
|
||||
m_handle = HAL_InitializeCounter(HAL_Counter_Mode::HAL_Counter_kTwoPulse,
|
||||
&m_index, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
|
||||
if (m_upSource) {
|
||||
HAL_SetCounterUpSource(m_handle, m_upSource->GetPortHandleForRouting(),
|
||||
static_cast<HAL_AnalogTriggerType>(
|
||||
m_upSource->GetAnalogTriggerTypeForRouting()),
|
||||
&status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
HAL_SetCounterUpSourceEdge(m_handle, true, false, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
}
|
||||
|
||||
if (m_downSource) {
|
||||
HAL_SetCounterDownSource(
|
||||
m_handle, m_downSource->GetPortHandleForRouting(),
|
||||
static_cast<HAL_AnalogTriggerType>(
|
||||
m_downSource->GetAnalogTriggerTypeForRouting()),
|
||||
&status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
HAL_SetCounterDownSourceEdge(m_handle, true, false, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
}
|
||||
std::string stackTrace = wpi::GetStackTrace(1);
|
||||
m_handle = HAL_InitializeCounter(
|
||||
channel, configuration == EdgeConfiguration::kRisingEdge,
|
||||
stackTrace.c_str(), &status);
|
||||
FRC_CheckErrorStatus(status, "{}", channel);
|
||||
|
||||
Reset();
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_Counter, m_index + 1);
|
||||
wpi::SendableRegistry::Add(this, "UpDown Counter", m_index);
|
||||
HAL_Report(HALUsageReporting::kResourceType_Counter, channel + 1);
|
||||
wpi::SendableRegistry::Add(this, "UpDown Counter", channel);
|
||||
}
|
||||
|
||||
int UpDownCounter::GetCount() const {
|
||||
int32_t status = 0;
|
||||
int val = HAL_GetCounter(m_handle, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
FRC_CheckErrorStatus(status, "{}", m_channel);
|
||||
return val;
|
||||
}
|
||||
|
||||
void UpDownCounter::SetReverseDirection(bool reverseDirection) {
|
||||
int32_t status = 0;
|
||||
HAL_SetCounterReverseDirection(m_handle, reverseDirection, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
}
|
||||
|
||||
void UpDownCounter::Reset() {
|
||||
int32_t status = 0;
|
||||
HAL_ResetCounter(m_handle, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
FRC_CheckErrorStatus(status, "{}", m_channel);
|
||||
}
|
||||
|
||||
void UpDownCounter::SetUpEdgeConfiguration(EdgeConfiguration configuration) {
|
||||
void UpDownCounter::SetEdgeConfiguration(EdgeConfiguration configuration) {
|
||||
int32_t status = 0;
|
||||
bool rising = configuration == EdgeConfiguration::kRisingEdge ||
|
||||
configuration == EdgeConfiguration::kBoth;
|
||||
bool falling = configuration == EdgeConfiguration::kFallingEdge ||
|
||||
configuration == EdgeConfiguration::kBoth;
|
||||
HAL_SetCounterUpSourceEdge(m_handle, rising, falling, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
}
|
||||
|
||||
void UpDownCounter::SetDownEdgeConfiguration(EdgeConfiguration configuration) {
|
||||
int32_t status = 0;
|
||||
bool rising = configuration == EdgeConfiguration::kRisingEdge ||
|
||||
configuration == EdgeConfiguration::kBoth;
|
||||
bool falling = configuration == EdgeConfiguration::kFallingEdge ||
|
||||
configuration == EdgeConfiguration::kBoth;
|
||||
HAL_SetCounterDownSourceEdge(m_handle, rising, falling, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_index);
|
||||
bool rising = configuration == EdgeConfiguration::kRisingEdge;
|
||||
HAL_SetCounterEdgeConfiguration(m_handle, rising, &status);
|
||||
FRC_CheckErrorStatus(status, "{}", m_channel);
|
||||
}
|
||||
|
||||
void UpDownCounter::InitSendable(wpi::SendableBuilder& builder) {
|
||||
|
||||
@@ -1,27 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "frc/simulation/UltrasonicSim.h"
|
||||
|
||||
#include "frc/Ultrasonic.h"
|
||||
#include "frc/simulation/SimDeviceSim.h"
|
||||
|
||||
using namespace frc::sim;
|
||||
|
||||
UltrasonicSim::UltrasonicSim(const frc::Ultrasonic& ultrasonic)
|
||||
: UltrasonicSim(0, ultrasonic.GetEchoChannel()) {}
|
||||
|
||||
UltrasonicSim::UltrasonicSim(int ping, int echo) {
|
||||
frc::sim::SimDeviceSim deviceSim{"Ultrasonic", echo};
|
||||
m_simRangeValid = deviceSim.GetBoolean("Range Valid");
|
||||
m_simRange = deviceSim.GetDouble("Range (in)");
|
||||
}
|
||||
|
||||
void UltrasonicSim::SetRangeValid(bool valid) {
|
||||
m_simRangeValid.Set(valid);
|
||||
}
|
||||
|
||||
void UltrasonicSim::SetRange(units::inch_t range) {
|
||||
m_simRange.Set(range.value());
|
||||
}
|
||||
@@ -1,469 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <memory>
|
||||
|
||||
#include <hal/Counter.h>
|
||||
#include <hal/Types.h>
|
||||
#include <units/time.h>
|
||||
#include <wpi/sendable/Sendable.h>
|
||||
#include <wpi/sendable/SendableHelper.h>
|
||||
|
||||
#include "frc/AnalogTrigger.h"
|
||||
#include "frc/CounterBase.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
class DigitalGlitchFilter;
|
||||
|
||||
/**
|
||||
* Class for counting the number of ticks on a digital input channel.
|
||||
*
|
||||
* This is a general purpose class for counting repetitive events. It can return
|
||||
* the number of counts, the period of the most recent cycle, and detect when
|
||||
* the signal being counted has stopped by supplying a maximum cycle time.
|
||||
*
|
||||
* All counters will immediately start counting - Reset() them if you need them
|
||||
* to be zeroed before use.
|
||||
*/
|
||||
class Counter : public CounterBase,
|
||||
public wpi::Sendable,
|
||||
public wpi::SendableHelper<Counter> {
|
||||
public:
|
||||
enum Mode {
|
||||
kTwoPulse = 0,
|
||||
kSemiperiod = 1,
|
||||
kPulseLength = 2,
|
||||
kExternalDirection = 3
|
||||
};
|
||||
|
||||
/**
|
||||
* Create an instance of a counter where no sources are selected.
|
||||
*
|
||||
* They all must be selected by calling functions to specify the up source and
|
||||
* the down source independently.
|
||||
*
|
||||
* This creates a ChipObject counter and initializes status variables
|
||||
* appropriately.
|
||||
*
|
||||
* The counter will start counting immediately.
|
||||
*
|
||||
* @param mode The counter mode
|
||||
*/
|
||||
explicit Counter(Mode mode = kTwoPulse);
|
||||
|
||||
/**
|
||||
* Create an instance of a Counter object.
|
||||
*
|
||||
* Create an up-Counter instance given a channel.
|
||||
*
|
||||
* The counter will start counting immediately.
|
||||
*
|
||||
* @param channel The DIO channel to use as the up source. 0-9 are on-board,
|
||||
* 10-25 are on the MXP
|
||||
*/
|
||||
explicit Counter(int channel);
|
||||
|
||||
/**
|
||||
* Create an instance of a counter from a Digital Source (such as a Digital
|
||||
* Input).
|
||||
*
|
||||
* This is used if an existing digital input is to be shared by multiple other
|
||||
* objects such as encoders or if the Digital Source is not a Digital Input
|
||||
* channel (such as an Analog %Trigger).
|
||||
*
|
||||
* The counter will start counting immediately.
|
||||
* @param source A pointer to the existing DigitalSource object. It will be
|
||||
* set as the Up Source.
|
||||
*/
|
||||
explicit Counter(DigitalSource* source);
|
||||
|
||||
/**
|
||||
* Create an instance of a counter from a Digital Source (such as a Digital
|
||||
* Input).
|
||||
*
|
||||
* This is used if an existing digital input is to be shared by multiple other
|
||||
* objects such as encoders or if the Digital Source is not a Digital Input
|
||||
* channel (such as an Analog %Trigger).
|
||||
*
|
||||
* The counter will start counting immediately.
|
||||
*
|
||||
* @param source A pointer to the existing DigitalSource object. It will be
|
||||
* set as the Up Source.
|
||||
*/
|
||||
explicit Counter(std::shared_ptr<DigitalSource> source);
|
||||
|
||||
/**
|
||||
* Create an instance of a Counter object.
|
||||
*
|
||||
* Create an instance of a simple up-Counter given an analog trigger.
|
||||
* Use the trigger state output from the analog trigger.
|
||||
*
|
||||
* The counter will start counting immediately.
|
||||
*
|
||||
* @param trigger The reference to the existing AnalogTrigger object.
|
||||
*/
|
||||
explicit Counter(const AnalogTrigger& trigger);
|
||||
|
||||
/**
|
||||
* Create an instance of a Counter object.
|
||||
*
|
||||
* Creates a full up-down counter given two Digital Sources.
|
||||
*
|
||||
* @param encodingType The quadrature decoding mode (1x or 2x)
|
||||
* @param upSource The pointer to the DigitalSource to set as the up
|
||||
* source
|
||||
* @param downSource The pointer to the DigitalSource to set as the down
|
||||
* source
|
||||
* @param inverted True to invert the output (reverse the direction)
|
||||
*/
|
||||
Counter(EncodingType encodingType, DigitalSource* upSource,
|
||||
DigitalSource* downSource, bool inverted);
|
||||
|
||||
/**
|
||||
* Create an instance of a Counter object.
|
||||
*
|
||||
* Creates a full up-down counter given two Digital Sources.
|
||||
*
|
||||
* @param encodingType The quadrature decoding mode (1x or 2x)
|
||||
* @param upSource The pointer to the DigitalSource to set as the up
|
||||
* source
|
||||
* @param downSource The pointer to the DigitalSource to set as the down
|
||||
* source
|
||||
* @param inverted True to invert the output (reverse the direction)
|
||||
*/
|
||||
Counter(EncodingType encodingType, std::shared_ptr<DigitalSource> upSource,
|
||||
std::shared_ptr<DigitalSource> downSource, bool inverted);
|
||||
|
||||
Counter(Counter&&) = default;
|
||||
Counter& operator=(Counter&&) = default;
|
||||
|
||||
~Counter() override;
|
||||
|
||||
/**
|
||||
* Set the up source for the counter as a digital input channel.
|
||||
*
|
||||
* @param channel The DIO channel to use as the up source. 0-9 are on-board,
|
||||
* 10-25 are on the MXP
|
||||
*/
|
||||
void SetUpSource(int channel);
|
||||
|
||||
/**
|
||||
* Set the up counting source to be an analog trigger.
|
||||
*
|
||||
* @param analogTrigger The analog trigger object that is used for the Up
|
||||
* Source
|
||||
* @param triggerType The analog trigger output that will trigger the
|
||||
* counter.
|
||||
*/
|
||||
void SetUpSource(AnalogTrigger* analogTrigger, AnalogTriggerType triggerType);
|
||||
|
||||
/**
|
||||
* Set the up counting source to be an analog trigger.
|
||||
*
|
||||
* @param analogTrigger The analog trigger object that is used for the Up
|
||||
* Source
|
||||
* @param triggerType The analog trigger output that will trigger the
|
||||
* counter.
|
||||
*/
|
||||
void SetUpSource(std::shared_ptr<AnalogTrigger> analogTrigger,
|
||||
AnalogTriggerType triggerType);
|
||||
|
||||
void SetUpSource(DigitalSource* source);
|
||||
|
||||
/**
|
||||
* Set the source object that causes the counter to count up.
|
||||
*
|
||||
* Set the up counting DigitalSource.
|
||||
*
|
||||
* @param source Pointer to the DigitalSource object to set as the up source
|
||||
*/
|
||||
void SetUpSource(std::shared_ptr<DigitalSource> source);
|
||||
|
||||
/**
|
||||
* Set the source object that causes the counter to count up.
|
||||
*
|
||||
* Set the up counting DigitalSource.
|
||||
*
|
||||
* @param source Reference to the DigitalSource object to set as the up source
|
||||
*/
|
||||
void SetUpSource(DigitalSource& source);
|
||||
|
||||
/**
|
||||
* Set the edge sensitivity on an up counting source.
|
||||
*
|
||||
* Set the up source to either detect rising edges or falling edges or both.
|
||||
*
|
||||
* @param risingEdge True to trigger on rising edges
|
||||
* @param fallingEdge True to trigger on falling edges
|
||||
*/
|
||||
void SetUpSourceEdge(bool risingEdge, bool fallingEdge);
|
||||
|
||||
/**
|
||||
* Disable the up counting source to the counter.
|
||||
*/
|
||||
void ClearUpSource();
|
||||
|
||||
/**
|
||||
* Set the down counting source to be a digital input channel.
|
||||
*
|
||||
* @param channel The DIO channel to use as the up source. 0-9 are on-board,
|
||||
* 10-25 are on the MXP
|
||||
*/
|
||||
void SetDownSource(int channel);
|
||||
|
||||
/**
|
||||
* Set the down counting source to be an analog trigger.
|
||||
*
|
||||
* @param analogTrigger The analog trigger object that is used for the Down
|
||||
* Source
|
||||
* @param triggerType The analog trigger output that will trigger the
|
||||
* counter.
|
||||
*/
|
||||
void SetDownSource(AnalogTrigger* analogTrigger,
|
||||
AnalogTriggerType triggerType);
|
||||
|
||||
/**
|
||||
* Set the down counting source to be an analog trigger.
|
||||
*
|
||||
* @param analogTrigger The analog trigger object that is used for the Down
|
||||
* Source
|
||||
* @param triggerType The analog trigger output that will trigger the
|
||||
* counter.
|
||||
*/
|
||||
void SetDownSource(std::shared_ptr<AnalogTrigger> analogTrigger,
|
||||
AnalogTriggerType triggerType);
|
||||
|
||||
/**
|
||||
* Set the source object that causes the counter to count down.
|
||||
*
|
||||
* Set the down counting DigitalSource.
|
||||
*
|
||||
* @param source Pointer to the DigitalSource object to set as the down source
|
||||
*/
|
||||
void SetDownSource(DigitalSource* source);
|
||||
|
||||
/**
|
||||
* Set the source object that causes the counter to count down.
|
||||
*
|
||||
* Set the down counting DigitalSource.
|
||||
*
|
||||
* @param source Reference to the DigitalSource object to set as the down
|
||||
* source
|
||||
*/
|
||||
void SetDownSource(DigitalSource& source);
|
||||
|
||||
void SetDownSource(std::shared_ptr<DigitalSource> source);
|
||||
|
||||
/**
|
||||
* Set the edge sensitivity on a down counting source.
|
||||
*
|
||||
* Set the down source to either detect rising edges or falling edges.
|
||||
*
|
||||
* @param risingEdge True to trigger on rising edges
|
||||
* @param fallingEdge True to trigger on falling edges
|
||||
*/
|
||||
void SetDownSourceEdge(bool risingEdge, bool fallingEdge);
|
||||
|
||||
/**
|
||||
* Disable the down counting source to the counter.
|
||||
*/
|
||||
void ClearDownSource();
|
||||
|
||||
/**
|
||||
* Set standard up / down counting mode on this counter.
|
||||
*
|
||||
* Up and down counts are sourced independently from two inputs.
|
||||
*/
|
||||
void SetUpDownCounterMode();
|
||||
|
||||
/**
|
||||
* Set external direction mode on this counter.
|
||||
*
|
||||
* Counts are sourced on the Up counter input.
|
||||
* The Down counter input represents the direction to count.
|
||||
*/
|
||||
void SetExternalDirectionMode();
|
||||
|
||||
/**
|
||||
* Set Semi-period mode on this counter.
|
||||
*
|
||||
* Counts up on both rising and falling edges.
|
||||
*/
|
||||
void SetSemiPeriodMode(bool highSemiPeriod);
|
||||
|
||||
/**
|
||||
* Configure the counter to count in up or down based on the length of the
|
||||
* input pulse.
|
||||
*
|
||||
* This mode is most useful for direction sensitive gear tooth sensors.
|
||||
*
|
||||
* @param threshold The pulse length beyond which the counter counts the
|
||||
* opposite direction. Units are seconds.
|
||||
*/
|
||||
void SetPulseLengthMode(double threshold);
|
||||
|
||||
/**
|
||||
* Set the Counter to return reversed sensing on the direction.
|
||||
*
|
||||
* This allows counters to change the direction they are counting in the case
|
||||
* of 1X and 2X quadrature encoding only. Any other counter mode isn't
|
||||
* supported.
|
||||
*
|
||||
* @param reverseDirection true if the value counted should be negated.
|
||||
*/
|
||||
void SetReverseDirection(bool reverseDirection);
|
||||
|
||||
/**
|
||||
* Set the Samples to Average which specifies the number of samples of the
|
||||
* timer to average when calculating the period. Perform averaging to account
|
||||
* for mechanical imperfections or as oversampling to increase resolution.
|
||||
*
|
||||
* @param samplesToAverage The number of samples to average from 1 to 127.
|
||||
*/
|
||||
void SetSamplesToAverage(int samplesToAverage);
|
||||
|
||||
/**
|
||||
* Get the Samples to Average which specifies the number of samples of the
|
||||
* timer to average when calculating the period.
|
||||
*
|
||||
* Perform averaging to account for mechanical imperfections or as
|
||||
* oversampling to increase resolution.
|
||||
*
|
||||
* @return The number of samples being averaged (from 1 to 127)
|
||||
*/
|
||||
int GetSamplesToAverage() const;
|
||||
|
||||
int GetFPGAIndex() const;
|
||||
|
||||
/**
|
||||
* Set the distance per pulse for this counter. This sets the multiplier used
|
||||
* to determine the distance driven based on the count value from the encoder.
|
||||
* Set this value based on the Pulses per Revolution and factor in any gearing
|
||||
* reductions. This distance can be in any units you like, linear or angular.
|
||||
*
|
||||
* @param distancePerPulse The scale factor that will be used to convert
|
||||
* pulses to useful units.
|
||||
*/
|
||||
void SetDistancePerPulse(double distancePerPulse);
|
||||
|
||||
/**
|
||||
* Read the current scaled counter value. Read the value at this instant,
|
||||
* scaled by the distance per pulse (defaults to 1).
|
||||
*
|
||||
* @return The distance since the last reset
|
||||
*/
|
||||
double GetDistance() const;
|
||||
|
||||
/**
|
||||
* Get the current rate of the Counter. Read the current rate of the counter
|
||||
* accounting for the distance per pulse value. The default value for distance
|
||||
* per pulse (1) yields units of pulses per second.
|
||||
*
|
||||
* @return The rate in units/sec
|
||||
*/
|
||||
double GetRate() const;
|
||||
|
||||
// CounterBase interface
|
||||
/**
|
||||
* Read the current counter value.
|
||||
*
|
||||
* Read the value at this instant. It may still be running, so it reflects the
|
||||
* current value. Next time it is read, it might have a different value.
|
||||
*/
|
||||
int Get() const override;
|
||||
|
||||
/**
|
||||
* Reset the Counter to zero.
|
||||
*
|
||||
* Set the counter value to zero. This doesn't effect the running state of the
|
||||
* counter, just sets the current value to zero.
|
||||
*/
|
||||
void Reset() override;
|
||||
|
||||
/**
|
||||
* Get the Period of the most recent count.
|
||||
*
|
||||
* Returns the time interval of the most recent count. This can be used for
|
||||
* velocity calculations to determine shaft speed.
|
||||
*
|
||||
* @returns The period between the last two pulses in units of seconds.
|
||||
*/
|
||||
units::second_t GetPeriod() const override;
|
||||
|
||||
/**
|
||||
* Set the maximum period where the device is still considered "moving".
|
||||
*
|
||||
* Sets the maximum period where the device is considered moving. This value
|
||||
* is used to determine the "stopped" state of the counter using the
|
||||
* GetStopped method.
|
||||
*
|
||||
* @param maxPeriod The maximum period where the counted device is considered
|
||||
* moving in seconds.
|
||||
*/
|
||||
void SetMaxPeriod(units::second_t maxPeriod) final;
|
||||
|
||||
/**
|
||||
* Select whether you want to continue updating the event timer output when
|
||||
* there are no samples captured.
|
||||
*
|
||||
* The output of the event timer has a buffer of periods that are averaged and
|
||||
* posted to a register on the FPGA. When the timer detects that the event
|
||||
* source has stopped (based on the MaxPeriod) the buffer of samples to be
|
||||
* averaged is emptied. If you enable the update when empty, you will be
|
||||
* notified of the stopped source and the event time will report 0 samples.
|
||||
* If you disable update when empty, the most recent average will remain on
|
||||
* the output until a new sample is acquired. You will never see 0 samples
|
||||
* output (except when there have been no events since an FPGA reset) and you
|
||||
* will likely not see the stopped bit become true (since it is updated at the
|
||||
* end of an average and there are no samples to average).
|
||||
*
|
||||
* @param enabled True to enable update when empty
|
||||
*/
|
||||
void SetUpdateWhenEmpty(bool enabled);
|
||||
|
||||
/**
|
||||
* Determine if the clock is stopped.
|
||||
*
|
||||
* Determine if the clocked input is stopped based on the MaxPeriod value set
|
||||
* using the SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the
|
||||
* device (and counter) are assumed to be stopped and it returns true.
|
||||
*
|
||||
* @return Returns true if the most recent counter period exceeds the
|
||||
* MaxPeriod value set by SetMaxPeriod.
|
||||
*/
|
||||
bool GetStopped() const override;
|
||||
|
||||
/**
|
||||
* The last direction the counter value changed.
|
||||
*
|
||||
* @return The last direction the counter value changed.
|
||||
*/
|
||||
bool GetDirection() const override;
|
||||
|
||||
void InitSendable(wpi::SendableBuilder& builder) override;
|
||||
|
||||
protected:
|
||||
/// Makes the counter count up.
|
||||
std::shared_ptr<DigitalSource> m_upSource;
|
||||
|
||||
/// Makes the counter count down.
|
||||
std::shared_ptr<DigitalSource> m_downSource;
|
||||
|
||||
/// The FPGA counter object
|
||||
hal::Handle<HAL_CounterHandle, HAL_FreeCounter> m_counter;
|
||||
|
||||
private:
|
||||
/// The index of this counter.
|
||||
int m_index = 0;
|
||||
|
||||
/// Distance of travel for each tick.
|
||||
double m_distancePerPulse = 1;
|
||||
|
||||
friend class DigitalGlitchFilter;
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
@@ -11,7 +11,6 @@
|
||||
#include <wpi/sendable/Sendable.h>
|
||||
#include <wpi/sendable/SendableHelper.h>
|
||||
|
||||
#include "frc/Counter.h"
|
||||
#include "frc/CounterBase.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
@@ -1,198 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <atomic>
|
||||
#include <memory>
|
||||
#include <thread>
|
||||
#include <vector>
|
||||
|
||||
#include <hal/SimDevice.h>
|
||||
#include <units/length.h>
|
||||
#include <units/time.h>
|
||||
#include <units/velocity.h>
|
||||
#include <wpi/sendable/Sendable.h>
|
||||
#include <wpi/sendable/SendableHelper.h>
|
||||
|
||||
#include "frc/Counter.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
class DigitalInput;
|
||||
class DigitalOutput;
|
||||
|
||||
/**
|
||||
* Ultrasonic rangefinder class.
|
||||
*
|
||||
* The Ultrasonic rangefinder measures absolute distance based on the round-trip
|
||||
* time of a ping generated by the controller. These sensors use two
|
||||
* transducers, a speaker and a microphone both tuned to the ultrasonic range. A
|
||||
* common ultrasonic sensor, the Daventech SRF04 requires a short pulse to be
|
||||
* generated on a digital channel. This causes the chirp to be emitted. A second
|
||||
* line becomes high as the ping is transmitted and goes low when the echo is
|
||||
* received. The time that the line is high determines the round trip distance
|
||||
* (time of flight).
|
||||
*/
|
||||
class Ultrasonic : public wpi::Sendable,
|
||||
public wpi::SendableHelper<Ultrasonic> {
|
||||
public:
|
||||
/**
|
||||
* Create an instance of the Ultrasonic Sensor.
|
||||
*
|
||||
* This is designed to support the Daventech SRF04 and Vex ultrasonic sensors.
|
||||
*
|
||||
* @param pingChannel The digital output channel that sends the pulse to
|
||||
* initiate the sensor sending the ping.
|
||||
* @param echoChannel The digital input channel that receives the echo. The
|
||||
* length of time that the echo is high represents the
|
||||
* round trip time of the ping, and the distance.
|
||||
*/
|
||||
Ultrasonic(int pingChannel, int echoChannel);
|
||||
|
||||
/**
|
||||
* Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
|
||||
* channel and a DigitalOutput for the ping channel.
|
||||
*
|
||||
* @param pingChannel The digital output object that starts the sensor doing a
|
||||
* ping. Requires a 10uS pulse to start.
|
||||
* @param echoChannel The digital input object that times the return pulse to
|
||||
* determine the range.
|
||||
*/
|
||||
Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel);
|
||||
|
||||
/**
|
||||
* Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
|
||||
* channel and a DigitalOutput for the ping channel.
|
||||
*
|
||||
* @param pingChannel The digital output object that starts the sensor doing a
|
||||
* ping. Requires a 10uS pulse to start.
|
||||
* @param echoChannel The digital input object that times the return pulse to
|
||||
* determine the range.
|
||||
*/
|
||||
Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel);
|
||||
|
||||
/**
|
||||
* Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
|
||||
* channel and a DigitalOutput for the ping channel.
|
||||
*
|
||||
* @param pingChannel The digital output object that starts the sensor doing a
|
||||
* ping. Requires a 10uS pulse to start.
|
||||
* @param echoChannel The digital input object that times the return pulse to
|
||||
* determine the range.
|
||||
*/
|
||||
Ultrasonic(std::shared_ptr<DigitalOutput> pingChannel,
|
||||
std::shared_ptr<DigitalInput> echoChannel);
|
||||
|
||||
~Ultrasonic() override;
|
||||
|
||||
Ultrasonic(Ultrasonic&&) = default;
|
||||
Ultrasonic& operator=(Ultrasonic&&) = default;
|
||||
|
||||
/**
|
||||
* Returns the echo channel.
|
||||
*
|
||||
* @return The echo channel.
|
||||
*/
|
||||
int GetEchoChannel() const;
|
||||
|
||||
/**
|
||||
* Single ping to ultrasonic sensor.
|
||||
*
|
||||
* Send out a single ping to the ultrasonic sensor. This only works if
|
||||
* automatic (round robin) mode is disabled. A single ping is sent out, and
|
||||
* the counter should count the semi-period when it comes in. The counter is
|
||||
* reset to make the current value invalid.
|
||||
*/
|
||||
void Ping();
|
||||
|
||||
/**
|
||||
* Check if there is a valid range measurement.
|
||||
*
|
||||
* The ranges are accumulated in a counter that will increment on each edge of
|
||||
* the echo (return) signal. If the count is not at least 2, then the range
|
||||
* has not yet been measured, and is invalid.
|
||||
*/
|
||||
bool IsRangeValid() const;
|
||||
|
||||
/**
|
||||
* Turn Automatic mode on/off.
|
||||
*
|
||||
* When in Automatic mode, all sensors will fire in round robin, waiting a set
|
||||
* time between each sensor.
|
||||
*
|
||||
* @param enabling Set to true if round robin scheduling should start for all
|
||||
* the ultrasonic sensors. This scheduling method assures that
|
||||
* the sensors are non-interfering because no two sensors fire
|
||||
* at the same time. If another scheduling algorithm is
|
||||
* preferred, it can be implemented by pinging the sensors
|
||||
* manually and waiting for the results to come back.
|
||||
*/
|
||||
static void SetAutomaticMode(bool enabling);
|
||||
|
||||
/**
|
||||
* Get the range from the ultrasonic sensor.
|
||||
*
|
||||
* @return Range of the target returned from the ultrasonic sensor. If there
|
||||
* is no valid value yet, i.e. at least one measurement hasn't
|
||||
* completed, then return 0.
|
||||
*/
|
||||
units::meter_t GetRange() const;
|
||||
|
||||
bool IsEnabled() const;
|
||||
|
||||
void SetEnabled(bool enable);
|
||||
|
||||
void InitSendable(wpi::SendableBuilder& builder) override;
|
||||
|
||||
private:
|
||||
/**
|
||||
* Initialize the Ultrasonic Sensor.
|
||||
*
|
||||
* This is the common code that initializes the ultrasonic sensor given that
|
||||
* there are two digital I/O channels allocated. If the system was running in
|
||||
* automatic mode (round robin) when the new sensor is added, it is stopped,
|
||||
* the sensor is added, then automatic mode is restored.
|
||||
*/
|
||||
void Initialize();
|
||||
|
||||
/**
|
||||
* Background task that goes through the list of ultrasonic sensors and pings
|
||||
* each one in turn. The counter is configured to read the timing of the
|
||||
* returned echo pulse.
|
||||
*
|
||||
* DANGER WILL ROBINSON, DANGER WILL ROBINSON:
|
||||
* This code runs as a task and assumes that none of the ultrasonic sensors
|
||||
* will change while it's running. Make sure to disable automatic mode before
|
||||
* touching the list.
|
||||
*/
|
||||
static void UltrasonicChecker();
|
||||
|
||||
// Time (usec) for the ping trigger pulse.
|
||||
static constexpr auto kPingTime = 10_us;
|
||||
|
||||
// Max time (ms) between readings.
|
||||
static constexpr auto kMaxUltrasonicTime = 0.1_s;
|
||||
static constexpr auto kSpeedOfSound = 1130_fps;
|
||||
|
||||
// Thread doing the round-robin automatic sensing
|
||||
static std::thread m_thread;
|
||||
|
||||
// Ultrasonic sensors
|
||||
static std::vector<Ultrasonic*> m_sensors;
|
||||
|
||||
// Automatic round-robin mode
|
||||
static std::atomic<bool> m_automaticEnabled;
|
||||
|
||||
std::shared_ptr<DigitalOutput> m_pingChannel;
|
||||
std::shared_ptr<DigitalInput> m_echoChannel;
|
||||
bool m_enabled = false;
|
||||
Counter m_counter;
|
||||
|
||||
hal::SimDevice m_simDevice;
|
||||
hal::SimBoolean m_simRangeValid;
|
||||
hal::SimDouble m_simRange;
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
@@ -9,13 +9,9 @@ namespace frc {
|
||||
* Edge configuration.
|
||||
*/
|
||||
enum class EdgeConfiguration {
|
||||
/// No edge configuration (neither rising nor falling).
|
||||
kNone = 0,
|
||||
/// Rising edge configuration.
|
||||
kRisingEdge = 0x1,
|
||||
kRisingEdge = 0,
|
||||
/// Falling edge configuration.
|
||||
kFallingEdge = 0x2,
|
||||
/// Both rising and falling edges configuration.
|
||||
kBoth = 0x3
|
||||
kFallingEdge = 1,
|
||||
};
|
||||
} // namespace frc
|
||||
|
||||
@@ -1,85 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <memory>
|
||||
|
||||
#include <hal/Counter.h>
|
||||
#include <hal/Types.h>
|
||||
#include <wpi/sendable/Sendable.h>
|
||||
#include <wpi/sendable/SendableHelper.h>
|
||||
|
||||
#include "EdgeConfiguration.h"
|
||||
|
||||
namespace frc {
|
||||
class DigitalSource;
|
||||
|
||||
/** Counter using external direction.
|
||||
*
|
||||
* <p>This counts on an edge from one digital input and the whether it counts
|
||||
* up or down based on the state of a second digital input.
|
||||
*
|
||||
*/
|
||||
class ExternalDirectionCounter
|
||||
: public wpi::Sendable,
|
||||
public wpi::SendableHelper<ExternalDirectionCounter> {
|
||||
public:
|
||||
/**
|
||||
* Constructs a new ExternalDirectionCounter.
|
||||
*
|
||||
* @param countSource The source for counting.
|
||||
* @param directionSource The source for selecting count direction.
|
||||
*/
|
||||
ExternalDirectionCounter(DigitalSource& countSource,
|
||||
DigitalSource& directionSource);
|
||||
|
||||
/**
|
||||
* Constructs a new ExternalDirectionCounter.
|
||||
*
|
||||
* @param countSource The source for counting.
|
||||
* @param directionSource The source for selecting count direction.
|
||||
*/
|
||||
ExternalDirectionCounter(std::shared_ptr<DigitalSource> countSource,
|
||||
std::shared_ptr<DigitalSource> directionSource);
|
||||
|
||||
ExternalDirectionCounter(ExternalDirectionCounter&&) = default;
|
||||
ExternalDirectionCounter& operator=(ExternalDirectionCounter&&) = default;
|
||||
|
||||
~ExternalDirectionCounter() override = default;
|
||||
|
||||
/**
|
||||
* Gets the current count.
|
||||
*
|
||||
* @return The current count.
|
||||
*/
|
||||
int GetCount() const;
|
||||
|
||||
/**
|
||||
* Sets to reverse the counter direction.
|
||||
*
|
||||
* @param reverseDirection True to reverse counting direction.
|
||||
*/
|
||||
void SetReverseDirection(bool reverseDirection);
|
||||
|
||||
/** Resets the current count. */
|
||||
void Reset();
|
||||
|
||||
/**
|
||||
* Sets the edge configuration for counting.
|
||||
*
|
||||
* @param configuration The counting edge configuration.
|
||||
*/
|
||||
void SetEdgeConfiguration(EdgeConfiguration configuration);
|
||||
|
||||
protected:
|
||||
void InitSendable(wpi::SendableBuilder& builder) override;
|
||||
|
||||
private:
|
||||
std::shared_ptr<DigitalSource> m_countSource;
|
||||
std::shared_ptr<DigitalSource> m_directionSource;
|
||||
hal::Handle<HAL_CounterHandle, HAL_FreeCounter> m_handle;
|
||||
int32_t m_index = 0;
|
||||
};
|
||||
} // namespace frc
|
||||
@@ -14,6 +14,8 @@
|
||||
#include <wpi/sendable/Sendable.h>
|
||||
#include <wpi/sendable/SendableHelper.h>
|
||||
|
||||
#include "EdgeConfiguration.h"
|
||||
|
||||
namespace frc {
|
||||
class DigitalSource;
|
||||
|
||||
@@ -32,22 +34,23 @@ class Tachometer : public wpi::Sendable,
|
||||
/**
|
||||
* Constructs a new tachometer.
|
||||
*
|
||||
* @param source The source.
|
||||
* @param channel The DIO Channel.
|
||||
* @param configuration Edge configuration
|
||||
*/
|
||||
explicit Tachometer(DigitalSource& source);
|
||||
|
||||
/**
|
||||
* Constructs a new tachometer.
|
||||
*
|
||||
* @param source The source.
|
||||
*/
|
||||
explicit Tachometer(std::shared_ptr<DigitalSource> source);
|
||||
Tachometer(int channel, EdgeConfiguration configuration);
|
||||
|
||||
Tachometer(Tachometer&&) = default;
|
||||
Tachometer& operator=(Tachometer&&) = default;
|
||||
|
||||
~Tachometer() override = default;
|
||||
|
||||
/**
|
||||
* Sets the configuration for the channel.
|
||||
*
|
||||
* @param configuration The channel configuration.
|
||||
*/
|
||||
void SetEdgeConfiguration(EdgeConfiguration configuration);
|
||||
|
||||
/**
|
||||
* Gets the tachometer frequency.
|
||||
*
|
||||
@@ -101,20 +104,6 @@ class Tachometer : public wpi::Sendable,
|
||||
*/
|
||||
bool GetStopped() const;
|
||||
|
||||
/**
|
||||
* Gets the number of sample to average.
|
||||
*
|
||||
* @return Samples to average.
|
||||
*/
|
||||
int GetSamplesToAverage() const;
|
||||
|
||||
/**
|
||||
* Sets the number of samples to average.
|
||||
*
|
||||
* @param samples Samples to average.
|
||||
*/
|
||||
void SetSamplesToAverage(int samples);
|
||||
|
||||
/**
|
||||
* Sets the maximum period before the tachometer is considered stopped.
|
||||
*
|
||||
@@ -122,20 +111,12 @@ class Tachometer : public wpi::Sendable,
|
||||
*/
|
||||
void SetMaxPeriod(units::second_t maxPeriod);
|
||||
|
||||
/**
|
||||
* Sets if to update when empty.
|
||||
*
|
||||
* @param updateWhenEmpty True to update when empty.
|
||||
*/
|
||||
void SetUpdateWhenEmpty(bool updateWhenEmpty);
|
||||
|
||||
protected:
|
||||
void InitSendable(wpi::SendableBuilder& builder) override;
|
||||
|
||||
private:
|
||||
std::shared_ptr<DigitalSource> m_source;
|
||||
hal::Handle<HAL_CounterHandle, HAL_FreeCounter> m_handle;
|
||||
int m_edgesPerRevolution;
|
||||
int32_t m_index;
|
||||
int32_t m_channel;
|
||||
};
|
||||
} // namespace frc
|
||||
|
||||
@@ -28,19 +28,10 @@ class UpDownCounter : public wpi::Sendable,
|
||||
/**
|
||||
* Constructs a new UpDown Counter.
|
||||
*
|
||||
* @param upSource The up count source (can be null).
|
||||
* @param downSource The down count source (can be null).
|
||||
* @param channel The DIO channel
|
||||
* @param configuration Edge configuration
|
||||
*/
|
||||
UpDownCounter(DigitalSource& upSource, DigitalSource& downSource);
|
||||
|
||||
/**
|
||||
* Constructs a new UpDown Counter.
|
||||
*
|
||||
* @param upSource The up count source (can be null).
|
||||
* @param downSource The down count source (can be null).
|
||||
*/
|
||||
UpDownCounter(std::shared_ptr<DigitalSource> upSource,
|
||||
std::shared_ptr<DigitalSource> downSource);
|
||||
UpDownCounter(int channel, EdgeConfiguration configuration);
|
||||
|
||||
UpDownCounter(UpDownCounter&&) = default;
|
||||
UpDownCounter& operator=(UpDownCounter&&) = default;
|
||||
@@ -54,38 +45,21 @@ class UpDownCounter : public wpi::Sendable,
|
||||
*/
|
||||
int GetCount() const;
|
||||
|
||||
/**
|
||||
* Sets to revert the counter direction.
|
||||
*
|
||||
* @param reverseDirection True to reverse counting direction.
|
||||
*/
|
||||
void SetReverseDirection(bool reverseDirection);
|
||||
|
||||
/** Resets the current count. */
|
||||
void Reset();
|
||||
|
||||
/**
|
||||
* Sets the configuration for the up source.
|
||||
* Sets the configuration for the channel.
|
||||
*
|
||||
* @param configuration The up source configuration.
|
||||
* @param configuration The channel configuration.
|
||||
*/
|
||||
void SetUpEdgeConfiguration(EdgeConfiguration configuration);
|
||||
|
||||
/**
|
||||
* Sets the configuration for the down source.
|
||||
*
|
||||
* @param configuration The down source configuration.
|
||||
*/
|
||||
void SetDownEdgeConfiguration(EdgeConfiguration configuration);
|
||||
void SetEdgeConfiguration(EdgeConfiguration configuration);
|
||||
|
||||
protected:
|
||||
void InitSendable(wpi::SendableBuilder& builder) override;
|
||||
|
||||
private:
|
||||
void InitUpDownCounter();
|
||||
std::shared_ptr<DigitalSource> m_upSource;
|
||||
std::shared_ptr<DigitalSource> m_downSource;
|
||||
hal::Handle<HAL_CounterHandle, HAL_FreeCounter> m_handle;
|
||||
int32_t m_index = 0;
|
||||
int32_t m_channel;
|
||||
};
|
||||
} // namespace frc
|
||||
|
||||
@@ -1,56 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <hal/SimDevice.h>
|
||||
#include <units/length.h>
|
||||
|
||||
namespace frc {
|
||||
|
||||
class Ultrasonic;
|
||||
|
||||
namespace sim {
|
||||
|
||||
/**
|
||||
* Class to control a simulated {@link Ultrasonic}.
|
||||
*/
|
||||
class UltrasonicSim {
|
||||
public:
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param ultrasonic The real ultrasonic to simulate
|
||||
*/
|
||||
explicit UltrasonicSim(const Ultrasonic& ultrasonic);
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param ping unused.
|
||||
* @param echo the ultrasonic's echo channel.
|
||||
*/
|
||||
UltrasonicSim(int ping, int echo);
|
||||
|
||||
/**
|
||||
* Sets if the range measurement is valid.
|
||||
*
|
||||
* @param valid True if valid
|
||||
*/
|
||||
void SetRangeValid(bool valid);
|
||||
|
||||
/**
|
||||
* Sets the range measurement.
|
||||
*
|
||||
* @param range The range.
|
||||
*/
|
||||
void SetRange(units::inch_t range);
|
||||
|
||||
private:
|
||||
hal::SimBoolean m_simRangeValid;
|
||||
hal::SimDouble m_simRange;
|
||||
};
|
||||
|
||||
} // namespace sim
|
||||
} // namespace frc
|
||||
@@ -1,42 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include <gtest/gtest.h>
|
||||
|
||||
#include "frc/Ultrasonic.h"
|
||||
#include "frc/simulation/UltrasonicSim.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
TEST(UltrasonicTest, SimDevices) {
|
||||
Ultrasonic ultrasonic{0, 1};
|
||||
sim::UltrasonicSim sim{ultrasonic};
|
||||
|
||||
EXPECT_EQ(0, ultrasonic.GetRange().value());
|
||||
EXPECT_TRUE(ultrasonic.IsRangeValid());
|
||||
|
||||
sim.SetRange(units::meter_t{35.04});
|
||||
EXPECT_EQ(35.04, ultrasonic.GetRange().value());
|
||||
|
||||
sim.SetRangeValid(false);
|
||||
EXPECT_FALSE(ultrasonic.IsRangeValid());
|
||||
EXPECT_EQ(0, ultrasonic.GetRange().value());
|
||||
}
|
||||
|
||||
TEST(UltrasonicTest, AutomaticModeToggle) {
|
||||
frc::Ultrasonic ultrasonic{0, 1};
|
||||
EXPECT_NO_THROW({
|
||||
frc::Ultrasonic::SetAutomaticMode(true);
|
||||
frc::Ultrasonic::SetAutomaticMode(false);
|
||||
frc::Ultrasonic::SetAutomaticMode(true);
|
||||
});
|
||||
}
|
||||
|
||||
TEST(UltrasonicTest, AutomaticModeOnWithZeroInstances) {
|
||||
EXPECT_NO_THROW({ frc::Ultrasonic::SetAutomaticMode(true); });
|
||||
}
|
||||
|
||||
TEST(UltrasonicTest, AutomaticModeOffWithZeroInstances) {
|
||||
EXPECT_NO_THROW({ frc::Ultrasonic::SetAutomaticMode(false); });
|
||||
}
|
||||
@@ -5,7 +5,6 @@
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/Ultrasonic.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/event/BooleanEvent.h>
|
||||
@@ -18,16 +17,16 @@
|
||||
|
||||
static const auto SHOT_VELOCITY = 200_rpm;
|
||||
static const auto TOLERANCE = 8_rpm;
|
||||
static const auto KICKER_THRESHOLD = 15_mm;
|
||||
|
||||
class Robot : public frc::TimedRobot {
|
||||
public:
|
||||
Robot() {
|
||||
m_controller.SetTolerance(TOLERANCE.value());
|
||||
|
||||
frc::BooleanEvent isBallAtKicker{&m_loop, [&kickerSensor = m_kickerSensor] {
|
||||
return kickerSensor.GetRange() <
|
||||
KICKER_THRESHOLD;
|
||||
frc::BooleanEvent isBallAtKicker{&m_loop, [] {
|
||||
return false;
|
||||
// return kickerSensor.GetRange() <
|
||||
// KICKER_THRESHOLD;
|
||||
}};
|
||||
frc::BooleanEvent intakeButton{
|
||||
&m_loop, [&joystick = m_joystick] { return joystick.GetRawButton(2); }};
|
||||
@@ -88,7 +87,6 @@ class Robot : public frc::TimedRobot {
|
||||
frc::SimpleMotorFeedforward<units::radians> m_ff{0.1_V, 0.065_V / 1_rpm};
|
||||
|
||||
frc::PWMSparkMax m_kicker{1};
|
||||
frc::Ultrasonic m_kickerSensor{2, 3};
|
||||
|
||||
frc::PWMSparkMax m_intake{3};
|
||||
|
||||
|
||||
@@ -1,57 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
#include <frc/smartdashboard/SmartDashboard.h>
|
||||
#include <units/length.h>
|
||||
|
||||
Robot::Robot() {
|
||||
// Add the ultrasonic on the "Sensors" tab of the dashboard
|
||||
// Data will update automatically
|
||||
frc::SmartDashboard::PutData("Sensors", &m_rangeFinder);
|
||||
}
|
||||
|
||||
void Robot::TeleopPeriodic() {
|
||||
// We can read the distance
|
||||
units::meter_t distance = m_rangeFinder.GetRange();
|
||||
// units auto-convert
|
||||
units::millimeter_t distanceMillimeters = distance;
|
||||
units::inch_t distanceInches = distance;
|
||||
|
||||
// We can also publish the data itself periodically
|
||||
frc::SmartDashboard::PutNumber("Distance[mm]", distanceMillimeters.value());
|
||||
frc::SmartDashboard::PutNumber("Distance[inch]", distanceInches.value());
|
||||
}
|
||||
|
||||
void Robot::TestInit() {
|
||||
// By default, the Ultrasonic class polls all ultrasonic sensors in a
|
||||
// round-robin to prevent them from interfering from one another. However,
|
||||
// manual polling is also possible -- note that this disables automatic mode!
|
||||
m_rangeFinder.Ping();
|
||||
}
|
||||
|
||||
void Robot::TestPeriodic() {
|
||||
if (m_rangeFinder.IsRangeValid()) {
|
||||
// Data is valid, publish it
|
||||
units::millimeter_t distanceMillimeters = m_rangeFinder.GetRange();
|
||||
units::inch_t distanceInches = m_rangeFinder.GetRange();
|
||||
frc::SmartDashboard::PutNumber("Distance[mm]", distanceMillimeters.value());
|
||||
frc::SmartDashboard::PutNumber("Distance[inch]", distanceInches.value());
|
||||
|
||||
// Ping for next measurement
|
||||
m_rangeFinder.Ping();
|
||||
}
|
||||
}
|
||||
|
||||
void Robot::TestExit() {
|
||||
// Enable automatic mode
|
||||
frc::Ultrasonic::SetAutomaticMode(true);
|
||||
}
|
||||
|
||||
#ifndef RUNNING_FRC_TESTS
|
||||
int main() {
|
||||
return frc::StartRobot<Robot>();
|
||||
}
|
||||
#endif
|
||||
@@ -1,25 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/Ultrasonic.h>
|
||||
|
||||
/**
|
||||
* This is a sample program demonstrating how to read from a ping-response
|
||||
* ultrasonic sensor with the {@link Ultrasonic class}.
|
||||
*/
|
||||
class Robot : public frc::TimedRobot {
|
||||
public:
|
||||
Robot();
|
||||
void TeleopPeriodic() override;
|
||||
void TestInit() override;
|
||||
void TestPeriodic() override;
|
||||
void TestExit() override;
|
||||
|
||||
private:
|
||||
// Creates a ping-response Ultrasonic object on DIO 1 and 2.
|
||||
frc::Ultrasonic m_rangeFinder{1, 2};
|
||||
};
|
||||
@@ -1,30 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
Robot::Robot() {
|
||||
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_left);
|
||||
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_right);
|
||||
}
|
||||
|
||||
void Robot::AutonomousInit() {
|
||||
// Set setpoint of the pid controller
|
||||
m_pidController.SetSetpoint(kHoldDistance.value());
|
||||
}
|
||||
|
||||
void Robot::AutonomousPeriodic() {
|
||||
units::millimeter_t measurement = m_ultrasonic.GetRange();
|
||||
units::millimeter_t filteredMeasurement = m_filter.Calculate(measurement);
|
||||
double pidOutput = m_pidController.Calculate(filteredMeasurement.value());
|
||||
|
||||
// disable input squaring -- PID output is linear
|
||||
m_robotDrive.ArcadeDrive(pidOutput, 0, false);
|
||||
}
|
||||
|
||||
#ifndef RUNNING_FRC_TESTS
|
||||
int main() {
|
||||
return frc::StartRobot<Robot>();
|
||||
}
|
||||
#endif
|
||||
@@ -1,52 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/Ultrasonic.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/filter/MedianFilter.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <units/length.h>
|
||||
|
||||
/**
|
||||
* This is a sample program to demonstrate the use of a PIDController with an
|
||||
* ultrasonic sensor to reach and maintain a set distance from an object.
|
||||
*/
|
||||
class Robot : public frc::TimedRobot {
|
||||
public:
|
||||
Robot();
|
||||
void AutonomousInit() override;
|
||||
void AutonomousPeriodic() override;
|
||||
|
||||
// distance the robot wants to stay from an object
|
||||
static constexpr units::millimeter_t kHoldDistance = 1_m;
|
||||
|
||||
static constexpr int kLeftMotorPort = 0;
|
||||
static constexpr int kRightMotorPort = 1;
|
||||
static constexpr int kUltrasonicPingPort = 0;
|
||||
static constexpr int kUltrasonicEchoPort = 1;
|
||||
|
||||
private:
|
||||
// proportional speed constant
|
||||
static constexpr double kP = 0.001;
|
||||
// integral speed constant
|
||||
static constexpr double kI = 0.0;
|
||||
// derivative speed constant
|
||||
static constexpr double kD = 0.0;
|
||||
|
||||
// Ultrasonic sensors tend to be quite noisy and susceptible to sudden
|
||||
// outliers, so measurements are filtered with a 5-sample median filter
|
||||
frc::MedianFilter<units::millimeter_t> m_filter{5};
|
||||
|
||||
frc::Ultrasonic m_ultrasonic{kUltrasonicPingPort, kUltrasonicEchoPort};
|
||||
frc::PWMSparkMax m_left{kLeftMotorPort};
|
||||
frc::PWMSparkMax m_right{kRightMotorPort};
|
||||
frc::DifferentialDrive m_robotDrive{
|
||||
[&](double output) { m_left.Set(output); },
|
||||
[&](double output) { m_right.Set(output); }};
|
||||
frc::PIDController m_pidController{kP, kI, kD};
|
||||
};
|
||||
@@ -112,31 +112,6 @@
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Ultrasonic",
|
||||
"description": "View values from a ping-response ultrasonic sensor.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Ultrasonic",
|
||||
"SmartDashboard"
|
||||
],
|
||||
"foldername": "Ultrasonic",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "UltrasonicPID",
|
||||
"description": "Maintain a set distance from an obstacle with an ultrasonic sensor and PID control.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Ultrasonic",
|
||||
"PID",
|
||||
"Differential Drive"
|
||||
],
|
||||
"foldername": "UltrasonicPID",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Gyro",
|
||||
"description": "Drive a differential drive straight with a gyro sensor.",
|
||||
|
||||
@@ -1,109 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include <string>
|
||||
#include <thread>
|
||||
|
||||
#include <frc/RobotController.h>
|
||||
#include <frc/simulation/DifferentialDrivetrainSim.h>
|
||||
#include <frc/simulation/DriverStationSim.h>
|
||||
#include <frc/simulation/PWMSim.h>
|
||||
#include <frc/simulation/SimHooks.h>
|
||||
#include <frc/simulation/UltrasonicSim.h>
|
||||
#include <frc/system/plant/DCMotor.h>
|
||||
#include <frc/system/plant/LinearSystemId.h>
|
||||
#include <gtest/gtest.h>
|
||||
#include <hal/simulation/MockHooks.h>
|
||||
#include <units/angle.h>
|
||||
#include <units/length.h>
|
||||
#include <units/mass.h>
|
||||
#include <units/time.h>
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
class UltrasonicPIDTest : public testing::TestWithParam<double> {
|
||||
frc::DCMotor m_gearbox = frc::DCMotor::Falcon500(2);
|
||||
static constexpr auto kGearing =
|
||||
frc::sim::DifferentialDrivetrainSim::KitbotGearing::k10p71;
|
||||
static constexpr auto kvLinear = 1.98 * 1_V / 1_mps;
|
||||
static constexpr auto kaLinear = 0.2 * 1_V / 1_mps_sq;
|
||||
static constexpr auto kvVoltAngular = 1.5 * 1_V / 1_rad_per_s;
|
||||
static constexpr auto kaAngular = 0.3 * 1_V / 1_rad_per_s_sq;
|
||||
static constexpr auto kWheelDiameter = 0.15_m;
|
||||
static constexpr auto kTrackwidth = 0.7_m;
|
||||
|
||||
Robot m_robot;
|
||||
std::optional<std::thread> m_thread;
|
||||
|
||||
protected:
|
||||
frc::sim::DifferentialDrivetrainSim m_driveSim{
|
||||
frc::LinearSystemId::IdentifyDrivetrainSystem(
|
||||
kvLinear, kaLinear, kvVoltAngular, kaAngular, kTrackwidth),
|
||||
kTrackwidth, m_gearbox, kGearing, kWheelDiameter / 2.0};
|
||||
frc::sim::PWMSim m_leftMotorSim{Robot::kLeftMotorPort};
|
||||
frc::sim::PWMSim m_rightMotorSim{Robot::kRightMotorPort};
|
||||
frc::sim::UltrasonicSim m_ultrasonicSim{Robot::kUltrasonicPingPort,
|
||||
Robot::kUltrasonicEchoPort};
|
||||
int32_t m_callback;
|
||||
|
||||
units::millimeter_t m_distance;
|
||||
|
||||
public:
|
||||
void SimPeriodicBefore() {
|
||||
m_driveSim.SetInputs(
|
||||
m_leftMotorSim.GetSpeed() * frc::RobotController::GetBatteryVoltage(),
|
||||
m_rightMotorSim.GetSpeed() * frc::RobotController::GetBatteryVoltage());
|
||||
m_driveSim.Update(20_ms);
|
||||
|
||||
auto startingDistance = units::meter_t{GetParam()};
|
||||
m_distance = m_driveSim.GetLeftPosition() - startingDistance;
|
||||
|
||||
m_ultrasonicSim.SetRange(m_distance);
|
||||
}
|
||||
|
||||
static void CallSimPeriodicBefore(void* param) {
|
||||
static_cast<UltrasonicPIDTest*>(param)->SimPeriodicBefore();
|
||||
}
|
||||
|
||||
void SetUp() override {
|
||||
frc::sim::PauseTiming();
|
||||
frc::sim::DriverStationSim::ResetData();
|
||||
|
||||
m_callback =
|
||||
HALSIM_RegisterSimPeriodicBeforeCallback(CallSimPeriodicBefore, this);
|
||||
|
||||
m_thread = std::thread([&] { m_robot.StartCompetition(); });
|
||||
frc::sim::StepTiming(0.0_ms); // Wait for Notifiers
|
||||
}
|
||||
|
||||
void TearDown() override {
|
||||
m_robot.EndCompetition();
|
||||
m_thread->join();
|
||||
|
||||
HALSIM_CancelSimPeriodicBeforeCallback(m_callback);
|
||||
m_leftMotorSim.ResetData();
|
||||
m_rightMotorSim.ResetData();
|
||||
}
|
||||
};
|
||||
|
||||
TEST_P(UltrasonicPIDTest, Auto) {
|
||||
// auto init
|
||||
{
|
||||
frc::sim::DriverStationSim::SetAutonomous(true);
|
||||
frc::sim::DriverStationSim::SetEnabled(true);
|
||||
frc::sim::DriverStationSim::NotifyNewData();
|
||||
|
||||
EXPECT_TRUE(m_leftMotorSim.GetInitialized());
|
||||
EXPECT_TRUE(m_rightMotorSim.GetInitialized());
|
||||
}
|
||||
|
||||
{
|
||||
frc::sim::StepTiming(5_s);
|
||||
|
||||
EXPECT_NEAR(Robot::kHoldDistance.value(), m_distance.value(), 10.0);
|
||||
}
|
||||
}
|
||||
|
||||
INSTANTIATE_TEST_SUITE_P(UltrasonicPIDTests, UltrasonicPIDTest,
|
||||
testing::Values(1.3, 0.5, 5.0));
|
||||
@@ -1,16 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include <gtest/gtest.h>
|
||||
#include <hal/HALBase.h>
|
||||
|
||||
/**
|
||||
* Runs all unit tests.
|
||||
*/
|
||||
int main(int argc, char** argv) {
|
||||
HAL_Initialize(500, 0);
|
||||
::testing::InitGoogleTest(&argc, argv);
|
||||
int ret = RUN_ALL_TESTS();
|
||||
return ret;
|
||||
}
|
||||
@@ -1,535 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import edu.wpi.first.hal.CounterJNI;
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.util.sendable.Sendable;
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.util.sendable.SendableRegistry;
|
||||
import edu.wpi.first.wpilibj.AnalogTriggerOutput.AnalogTriggerType;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
/**
|
||||
* Class for counting the number of ticks on a digital input channel.
|
||||
*
|
||||
* <p>This is a general purpose class for counting repetitive events. It can return the number of
|
||||
* counts, the period of the most recent cycle, and detect when the signal being counted has stopped
|
||||
* by supplying a maximum cycle time.
|
||||
*
|
||||
* <p>All counters will immediately start counting - reset() them if you need them to be zeroed
|
||||
* before use.
|
||||
*/
|
||||
public class Counter implements CounterBase, Sendable, AutoCloseable {
|
||||
/** Mode determines how and what the counter counts. */
|
||||
public enum Mode {
|
||||
/** mode: two pulse. */
|
||||
kTwoPulse(0),
|
||||
/** mode: semi period. */
|
||||
kSemiperiod(1),
|
||||
/** mode: pulse length. */
|
||||
kPulseLength(2),
|
||||
/** mode: external direction. */
|
||||
kExternalDirection(3);
|
||||
|
||||
/** Mode value. */
|
||||
public final int value;
|
||||
|
||||
Mode(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
/** What makes the counter count up. */
|
||||
protected DigitalSource m_upSource;
|
||||
|
||||
/** What makes the counter count down. */
|
||||
protected DigitalSource m_downSource;
|
||||
|
||||
private boolean m_allocatedUpSource;
|
||||
private boolean m_allocatedDownSource;
|
||||
|
||||
/** The FPGA counter object. */
|
||||
int m_counter;
|
||||
|
||||
/** The index of this counter. */
|
||||
private int m_index;
|
||||
|
||||
/** Distance of travel for each tick. */
|
||||
private double m_distancePerPulse = 1;
|
||||
|
||||
/**
|
||||
* Create an instance of a counter with the given mode.
|
||||
*
|
||||
* @param mode The counter mode.
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public Counter(final Mode mode) {
|
||||
ByteBuffer index = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
index.order(ByteOrder.LITTLE_ENDIAN);
|
||||
m_counter = CounterJNI.initializeCounter(mode.value, index.asIntBuffer());
|
||||
m_index = index.asIntBuffer().get(0);
|
||||
|
||||
m_allocatedUpSource = false;
|
||||
m_allocatedDownSource = false;
|
||||
m_upSource = null;
|
||||
m_downSource = null;
|
||||
|
||||
setMaxPeriod(0.5);
|
||||
|
||||
HAL.report(tResourceType.kResourceType_Counter, m_index + 1, mode.value + 1);
|
||||
SendableRegistry.add(this, "Counter", m_index);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of a counter where no sources are selected. Then they all must be selected
|
||||
* by calling functions to specify the up source and the down source independently.
|
||||
*
|
||||
* <p>The counter will start counting immediately.
|
||||
*/
|
||||
public Counter() {
|
||||
this(Mode.kTwoPulse);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of a counter from a Digital Input. This is used if an existing digital input
|
||||
* is to be shared by multiple other objects such as encoders or if the Digital Source is not a
|
||||
* DIO channel (such as an Analog Trigger)
|
||||
*
|
||||
* <p>The counter will start counting immediately.
|
||||
*
|
||||
* @param source the digital source to count
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public Counter(DigitalSource source) {
|
||||
this();
|
||||
|
||||
requireNonNullParam(source, "source", "Counter");
|
||||
setUpSource(source);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of a Counter object. Create an up-Counter instance given a channel.
|
||||
*
|
||||
* <p>The counter will start counting immediately.
|
||||
*
|
||||
* @param channel the DIO channel to use as the up source. 0-9 are on-board, 10-25 are on the MXP
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public Counter(int channel) {
|
||||
this();
|
||||
setUpSource(channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of a Counter object. Create an instance of a simple up-Counter given an
|
||||
* analog trigger. Use the trigger state output from the analog trigger.
|
||||
*
|
||||
* <p>The counter will start counting immediately.
|
||||
*
|
||||
* @param encodingType which edges to count
|
||||
* @param upSource first source to count
|
||||
* @param downSource second source for direction
|
||||
* @param inverted true to invert the count
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public Counter(
|
||||
EncodingType encodingType,
|
||||
DigitalSource upSource,
|
||||
DigitalSource downSource,
|
||||
boolean inverted) {
|
||||
this(Mode.kExternalDirection);
|
||||
|
||||
requireNonNullParam(encodingType, "encodingType", "Counter");
|
||||
requireNonNullParam(upSource, "upSource", "Counter");
|
||||
requireNonNullParam(downSource, "downSource", "Counter");
|
||||
|
||||
if (encodingType != EncodingType.k1X && encodingType != EncodingType.k2X) {
|
||||
throw new IllegalArgumentException("Counters only support 1X and 2X quadrature decoding!");
|
||||
}
|
||||
|
||||
setUpSource(upSource);
|
||||
setDownSource(downSource);
|
||||
|
||||
if (encodingType == EncodingType.k1X) {
|
||||
setUpSourceEdge(true, false);
|
||||
CounterJNI.setCounterAverageSize(m_counter, 1);
|
||||
} else {
|
||||
setUpSourceEdge(true, true);
|
||||
CounterJNI.setCounterAverageSize(m_counter, 2);
|
||||
}
|
||||
|
||||
setDownSourceEdge(inverted, true);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of a Counter object. Create an instance of a simple up-Counter given an
|
||||
* analog trigger. Use the trigger state output from the analog trigger.
|
||||
*
|
||||
* <p>The counter will start counting immediately.
|
||||
*
|
||||
* @param trigger the analog trigger to count
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public Counter(AnalogTrigger trigger) {
|
||||
this();
|
||||
|
||||
requireNonNullParam(trigger, "trigger", "Counter");
|
||||
|
||||
setUpSource(trigger.createOutput(AnalogTriggerType.kState));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void close() {
|
||||
SendableRegistry.remove(this);
|
||||
|
||||
setUpdateWhenEmpty(true);
|
||||
|
||||
clearUpSource();
|
||||
clearDownSource();
|
||||
|
||||
CounterJNI.freeCounter(m_counter);
|
||||
|
||||
m_upSource = null;
|
||||
m_downSource = null;
|
||||
m_counter = 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* The counter's FPGA index.
|
||||
*
|
||||
* @return the Counter's FPGA index
|
||||
*/
|
||||
public int getFPGAIndex() {
|
||||
return m_index;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the up source for the counter as a digital input channel.
|
||||
*
|
||||
* @param channel the DIO channel to count 0-9 are on-board, 10-25 are on the MXP
|
||||
*/
|
||||
public final void setUpSource(int channel) {
|
||||
setUpSource(new DigitalInput(channel));
|
||||
m_allocatedUpSource = true;
|
||||
SendableRegistry.addChild(this, m_upSource);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the source object that causes the counter to count up. Set the up counting DigitalSource.
|
||||
*
|
||||
* @param source the digital source to count
|
||||
*/
|
||||
public void setUpSource(DigitalSource source) {
|
||||
if (m_upSource != null && m_allocatedUpSource) {
|
||||
m_upSource.close();
|
||||
m_allocatedUpSource = false;
|
||||
}
|
||||
m_upSource = source;
|
||||
CounterJNI.setCounterUpSource(
|
||||
m_counter, source.getPortHandleForRouting(), source.getAnalogTriggerTypeForRouting());
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the up counting source to be an analog trigger.
|
||||
*
|
||||
* @param analogTrigger The analog trigger object that is used for the Up Source
|
||||
* @param triggerType The analog trigger output that will trigger the counter.
|
||||
*/
|
||||
public void setUpSource(AnalogTrigger analogTrigger, AnalogTriggerType triggerType) {
|
||||
requireNonNullParam(analogTrigger, "analogTrigger", "setUpSource");
|
||||
requireNonNullParam(triggerType, "triggerType", "setUpSource");
|
||||
|
||||
setUpSource(analogTrigger.createOutput(triggerType));
|
||||
m_allocatedUpSource = true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the edge sensitivity on an up counting source. Set the up source to either detect rising
|
||||
* edges or falling edges.
|
||||
*
|
||||
* @param risingEdge true to count rising edge
|
||||
* @param fallingEdge true to count falling edge
|
||||
*/
|
||||
public void setUpSourceEdge(boolean risingEdge, boolean fallingEdge) {
|
||||
if (m_upSource == null) {
|
||||
throw new IllegalStateException("Up Source must be set before setting the edge!");
|
||||
}
|
||||
CounterJNI.setCounterUpSourceEdge(m_counter, risingEdge, fallingEdge);
|
||||
}
|
||||
|
||||
/** Disable the up counting source to the counter. */
|
||||
public void clearUpSource() {
|
||||
if (m_upSource != null && m_allocatedUpSource) {
|
||||
m_upSource.close();
|
||||
m_allocatedUpSource = false;
|
||||
}
|
||||
m_upSource = null;
|
||||
|
||||
CounterJNI.clearCounterUpSource(m_counter);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the down counting source to be a digital input channel.
|
||||
*
|
||||
* @param channel the DIO channel to count 0-9 are on-board, 10-25 are on the MXP
|
||||
*/
|
||||
public void setDownSource(int channel) {
|
||||
setDownSource(new DigitalInput(channel));
|
||||
m_allocatedDownSource = true;
|
||||
SendableRegistry.addChild(this, m_downSource);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the source object that causes the counter to count down. Set the down counting
|
||||
* DigitalSource.
|
||||
*
|
||||
* @param source the digital source to count
|
||||
*/
|
||||
public void setDownSource(DigitalSource source) {
|
||||
requireNonNullParam(source, "source", "setDownSource");
|
||||
|
||||
if (m_downSource != null && m_allocatedDownSource) {
|
||||
m_downSource.close();
|
||||
m_allocatedDownSource = false;
|
||||
}
|
||||
CounterJNI.setCounterDownSource(
|
||||
m_counter, source.getPortHandleForRouting(), source.getAnalogTriggerTypeForRouting());
|
||||
m_downSource = source;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the down counting source to be an analog trigger.
|
||||
*
|
||||
* @param analogTrigger The analog trigger object that is used for the Down Source
|
||||
* @param triggerType The analog trigger output that will trigger the counter.
|
||||
*/
|
||||
public void setDownSource(AnalogTrigger analogTrigger, AnalogTriggerType triggerType) {
|
||||
requireNonNullParam(analogTrigger, "analogTrigger", "setDownSource");
|
||||
requireNonNullParam(triggerType, "analogTrigger", "setDownSource");
|
||||
|
||||
setDownSource(analogTrigger.createOutput(triggerType));
|
||||
m_allocatedDownSource = true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the edge sensitivity on a down counting source. Set the down source to either detect rising
|
||||
* edges or falling edges.
|
||||
*
|
||||
* @param risingEdge true to count the rising edge
|
||||
* @param fallingEdge true to count the falling edge
|
||||
*/
|
||||
public void setDownSourceEdge(boolean risingEdge, boolean fallingEdge) {
|
||||
if (m_downSource == null) {
|
||||
throw new IllegalStateException("Down Source must be set before setting the edge!");
|
||||
}
|
||||
|
||||
CounterJNI.setCounterDownSourceEdge(m_counter, risingEdge, fallingEdge);
|
||||
}
|
||||
|
||||
/** Disable the down counting source to the counter. */
|
||||
public void clearDownSource() {
|
||||
if (m_downSource != null && m_allocatedDownSource) {
|
||||
m_downSource.close();
|
||||
m_allocatedDownSource = false;
|
||||
}
|
||||
m_downSource = null;
|
||||
|
||||
CounterJNI.clearCounterDownSource(m_counter);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set standard up / down counting mode on this counter. Up and down counts are sourced
|
||||
* independently from two inputs.
|
||||
*/
|
||||
public void setUpDownCounterMode() {
|
||||
CounterJNI.setCounterUpDownMode(m_counter);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set external direction mode on this counter. Counts are sourced on the Up counter input. The
|
||||
* Down counter input represents the direction to count.
|
||||
*/
|
||||
public void setExternalDirectionMode() {
|
||||
CounterJNI.setCounterExternalDirectionMode(m_counter);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set Semi-period mode on this counter. Counts up on both rising and falling edges.
|
||||
*
|
||||
* @param highSemiPeriod true to count up on both rising and falling
|
||||
*/
|
||||
public void setSemiPeriodMode(boolean highSemiPeriod) {
|
||||
CounterJNI.setCounterSemiPeriodMode(m_counter, highSemiPeriod);
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure the counter to count in up or down based on the length of the input pulse. This mode
|
||||
* is most useful for direction sensitive gear tooth sensors.
|
||||
*
|
||||
* @param threshold The pulse length beyond which the counter counts the opposite direction. Units
|
||||
* are seconds.
|
||||
*/
|
||||
public void setPulseLengthMode(double threshold) {
|
||||
CounterJNI.setCounterPulseLengthMode(m_counter, threshold);
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the current counter value. Read the value at this instant. It may still be running, so it
|
||||
* reflects the current value. Next time it is read, it might have a different value.
|
||||
*/
|
||||
@Override
|
||||
public int get() {
|
||||
return CounterJNI.getCounter(m_counter);
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the current scaled counter value. Read the value at this instant, scaled by the distance
|
||||
* per pulse (defaults to 1).
|
||||
*
|
||||
* @return The distance since the last reset
|
||||
*/
|
||||
public double getDistance() {
|
||||
return get() * m_distancePerPulse;
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the Counter to zero. Set the counter value to zero. This doesn't affect the running state
|
||||
* of the counter, just sets the current value to zero.
|
||||
*/
|
||||
@Override
|
||||
public void reset() {
|
||||
CounterJNI.resetCounter(m_counter);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the maximum period where the device is still considered "moving". Sets the maximum period
|
||||
* where the device is considered moving. This value is used to determine the "stopped" state of
|
||||
* the counter using the GetStopped method.
|
||||
*
|
||||
* @param maxPeriod The maximum period where the counted device is considered moving in seconds.
|
||||
*/
|
||||
@Override
|
||||
public final void setMaxPeriod(double maxPeriod) {
|
||||
CounterJNI.setCounterMaxPeriod(m_counter, maxPeriod);
|
||||
}
|
||||
|
||||
/**
|
||||
* Select whether you want to continue updating the event timer output when there are no samples
|
||||
* captured. The output of the event timer has a buffer of periods that are averaged and posted to
|
||||
* a register on the FPGA. When the timer detects that the event source has stopped (based on the
|
||||
* MaxPeriod) the buffer of samples to be averaged is emptied. If you enable the update when
|
||||
* empty, you will be notified of the stopped source and the event time will report 0 samples. If
|
||||
* you disable update when empty, the most recent average will remain on the output until a new
|
||||
* sample is acquired. You will never see 0 samples output (except when there have been no events
|
||||
* since an FPGA reset) and you will likely not see the stopped bit become true (since it is
|
||||
* updated at the end of an average and there are no samples to average).
|
||||
*
|
||||
* @param enabled true to continue updating
|
||||
*/
|
||||
public void setUpdateWhenEmpty(boolean enabled) {
|
||||
CounterJNI.setCounterUpdateWhenEmpty(m_counter, enabled);
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine if the clock is stopped. Determine if the clocked input is stopped based on the
|
||||
* MaxPeriod value set using the SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the
|
||||
* device (and counter) are assumed to be stopped and the method will return true.
|
||||
*
|
||||
* @return true if the most recent counter period exceeds the MaxPeriod value set by SetMaxPeriod.
|
||||
*/
|
||||
@Override
|
||||
public boolean getStopped() {
|
||||
return CounterJNI.getCounterStopped(m_counter);
|
||||
}
|
||||
|
||||
/**
|
||||
* The last direction the counter value changed.
|
||||
*
|
||||
* @return The last direction the counter value changed.
|
||||
*/
|
||||
@Override
|
||||
public boolean getDirection() {
|
||||
return CounterJNI.getCounterDirection(m_counter);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the Counter to return reversed sensing on the direction. This allows counters to change the
|
||||
* direction they are counting in the case of 1X and 2X quadrature encoding only. Any other
|
||||
* counter mode isn't supported.
|
||||
*
|
||||
* @param reverseDirection true if the value counted should be negated.
|
||||
*/
|
||||
public void setReverseDirection(boolean reverseDirection) {
|
||||
CounterJNI.setCounterReverseDirection(m_counter, reverseDirection);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the Period of the most recent count. Returns the time interval of the most recent count.
|
||||
* This can be used for velocity calculations to determine shaft speed.
|
||||
*
|
||||
* @return The period of the last two pulses in units of seconds.
|
||||
*/
|
||||
@Override
|
||||
public double getPeriod() {
|
||||
return CounterJNI.getCounterPeriod(m_counter);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the current rate of the Counter. Read the current rate of the counter accounting for the
|
||||
* distance per pulse value. The default value for distance per pulse (1) yields units of pulses
|
||||
* per second.
|
||||
*
|
||||
* @return The rate in units/sec
|
||||
*/
|
||||
public double getRate() {
|
||||
return m_distancePerPulse / getPeriod();
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the Samples to Average which specifies the number of samples of the timer to average when
|
||||
* calculating the period. Perform averaging to account for mechanical imperfections or as
|
||||
* oversampling to increase resolution.
|
||||
*
|
||||
* @param samplesToAverage The number of samples to average from 1 to 127.
|
||||
*/
|
||||
public void setSamplesToAverage(int samplesToAverage) {
|
||||
CounterJNI.setCounterSamplesToAverage(m_counter, samplesToAverage);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the Samples to Average which specifies the number of samples of the timer to average when
|
||||
* calculating the period. Perform averaging to account for mechanical imperfections or as
|
||||
* oversampling to increase resolution.
|
||||
*
|
||||
* @return SamplesToAverage The number of samples being averaged (from 1 to 127)
|
||||
*/
|
||||
public int getSamplesToAverage() {
|
||||
return CounterJNI.getCounterSamplesToAverage(m_counter);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the distance per pulse for this counter. This sets the multiplier used to determine the
|
||||
* distance driven based on the count value from the encoder. Set this value based on the Pulses
|
||||
* per Revolution and factor in any gearing reductions. This distance can be in any units you
|
||||
* like, linear or angular.
|
||||
*
|
||||
* @param distancePerPulse The scale factor that will be used to convert pulses to useful units.
|
||||
*/
|
||||
public void setDistancePerPulse(double distancePerPulse) {
|
||||
m_distancePerPulse = distancePerPulse;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initSendable(SendableBuilder builder) {
|
||||
builder.setSmartDashboardType("Counter");
|
||||
builder.addDoubleProperty("Value", this::get, null);
|
||||
}
|
||||
}
|
||||
@@ -1,328 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.hal.SimBoolean;
|
||||
import edu.wpi.first.hal.SimDevice;
|
||||
import edu.wpi.first.hal.SimDevice.Direction;
|
||||
import edu.wpi.first.hal.SimDouble;
|
||||
import edu.wpi.first.util.sendable.Sendable;
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.util.sendable.SendableRegistry;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
|
||||
/**
|
||||
* Ultrasonic rangefinder class. The Ultrasonic rangefinder measures absolute distance based on the
|
||||
* round-trip time of a ping generated by the controller. These sensors use two transducers, a
|
||||
* speaker and a microphone both tuned to the ultrasonic range. A common ultrasonic sensor, the
|
||||
* Daventech SRF04 requires a short pulse to be generated on a digital channel. This causes the
|
||||
* chirp to be emitted. A second line becomes high as the ping is transmitted and goes low when the
|
||||
* echo is received. The time that the line is high determines the round trip distance (time of
|
||||
* flight).
|
||||
*/
|
||||
public class Ultrasonic implements Sendable, AutoCloseable {
|
||||
// Time (sec) for the ping trigger pulse.
|
||||
private static final double kPingTime = 10 * 1e-6;
|
||||
private static final double kSpeedOfSoundInchesPerSec = 1130.0 * 12.0;
|
||||
// ultrasonic sensor list
|
||||
private static final List<Ultrasonic> m_sensors = new ArrayList<>();
|
||||
// automatic round robin mode
|
||||
private static volatile boolean m_automaticEnabled;
|
||||
private DigitalInput m_echoChannel;
|
||||
private DigitalOutput m_pingChannel;
|
||||
private final boolean m_allocatedChannels;
|
||||
private boolean m_enabled;
|
||||
private Counter m_counter;
|
||||
// task doing the round-robin automatic sensing
|
||||
private static Thread m_task;
|
||||
private static int m_instances;
|
||||
|
||||
@SuppressWarnings("PMD.SingularField")
|
||||
private SimDevice m_simDevice;
|
||||
|
||||
private SimBoolean m_simRangeValid;
|
||||
private SimDouble m_simRange;
|
||||
|
||||
/**
|
||||
* Background task that goes through the list of ultrasonic sensors and pings each one in turn.
|
||||
* The counter is configured to read the timing of the returned echo pulse.
|
||||
*
|
||||
* <p><b>DANGER WILL ROBINSON, DANGER WILL ROBINSON:</b> This code runs as a task and assumes that
|
||||
* none of the ultrasonic sensors will change while it's running. If one does, then this will
|
||||
* certainly break. Make sure to disable automatic mode before changing anything with the
|
||||
* sensors!!
|
||||
*/
|
||||
private static final class UltrasonicChecker extends Thread {
|
||||
@Override
|
||||
public synchronized void run() {
|
||||
while (m_automaticEnabled) {
|
||||
for (Ultrasonic sensor : m_sensors) {
|
||||
if (!m_automaticEnabled) {
|
||||
break;
|
||||
}
|
||||
|
||||
if (sensor.isEnabled()) {
|
||||
sensor.m_pingChannel.pulse(kPingTime); // do the ping
|
||||
}
|
||||
|
||||
Timer.delay(0.1); // wait for ping to return
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialize the Ultrasonic Sensor. This is the common code that initializes the ultrasonic
|
||||
* sensor given that there are two digital I/O channels allocated. If the system was running in
|
||||
* automatic mode (round-robin) when the new sensor is added, it is stopped, the sensor is added,
|
||||
* then automatic mode is restored.
|
||||
*/
|
||||
private synchronized void initialize() {
|
||||
m_simDevice = SimDevice.create("Ultrasonic", m_echoChannel.getChannel());
|
||||
if (m_simDevice != null) {
|
||||
m_simRangeValid = m_simDevice.createBoolean("Range Valid", Direction.kInput, true);
|
||||
m_simRange = m_simDevice.createDouble("Range (in)", Direction.kInput, 0.0);
|
||||
m_pingChannel.setSimDevice(m_simDevice);
|
||||
m_echoChannel.setSimDevice(m_simDevice);
|
||||
}
|
||||
final boolean originalMode = m_automaticEnabled;
|
||||
setAutomaticMode(false); // kill task when adding a new sensor
|
||||
m_sensors.add(this);
|
||||
|
||||
m_counter = new Counter(m_echoChannel); // set up counter for this
|
||||
SendableRegistry.addChild(this, m_counter);
|
||||
// sensor
|
||||
m_counter.setMaxPeriod(1.0);
|
||||
m_counter.setSemiPeriodMode(true);
|
||||
m_counter.reset();
|
||||
m_enabled = true; // make it available for round-robin scheduling
|
||||
setAutomaticMode(originalMode);
|
||||
|
||||
m_instances++;
|
||||
HAL.report(tResourceType.kResourceType_Ultrasonic, m_instances);
|
||||
SendableRegistry.add(this, "Ultrasonic", m_echoChannel.getChannel());
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the echo channel.
|
||||
*
|
||||
* @return The echo channel.
|
||||
*/
|
||||
public int getEchoChannel() {
|
||||
return m_echoChannel.getChannel();
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of the Ultrasonic Sensor. This is designed to support the Daventech SRF04
|
||||
* and Vex ultrasonic sensors.
|
||||
*
|
||||
* @param pingChannel The digital output channel that sends the pulse to initiate the sensor
|
||||
* sending the ping.
|
||||
* @param echoChannel The digital input channel that receives the echo. The length of time that
|
||||
* the echo is high represents the round trip time of the ping, and the distance.
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public Ultrasonic(final int pingChannel, final int echoChannel) {
|
||||
m_pingChannel = new DigitalOutput(pingChannel);
|
||||
m_echoChannel = new DigitalInput(echoChannel);
|
||||
SendableRegistry.addChild(this, m_pingChannel);
|
||||
SendableRegistry.addChild(this, m_echoChannel);
|
||||
m_allocatedChannels = true;
|
||||
initialize();
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo channel and a
|
||||
* DigitalOutput for the ping channel.
|
||||
*
|
||||
* @param pingChannel The digital output object that starts the sensor doing a ping. Requires a
|
||||
* 10uS pulse to start.
|
||||
* @param echoChannel The digital input object that times the return pulse to determine the range.
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public Ultrasonic(DigitalOutput pingChannel, DigitalInput echoChannel) {
|
||||
requireNonNullParam(pingChannel, "pingChannel", "Ultrasonic");
|
||||
requireNonNullParam(echoChannel, "echoChannel", "Ultrasonic");
|
||||
|
||||
m_allocatedChannels = false;
|
||||
m_pingChannel = pingChannel;
|
||||
m_echoChannel = echoChannel;
|
||||
initialize();
|
||||
}
|
||||
|
||||
/**
|
||||
* Destructor for the ultrasonic sensor. Delete the instance of the ultrasonic sensor by freeing
|
||||
* the allocated digital channels. If the system was in automatic mode (round-robin), then it is
|
||||
* stopped, then started again after this sensor is removed (provided this wasn't the last
|
||||
* sensor).
|
||||
*/
|
||||
@Override
|
||||
public synchronized void close() {
|
||||
SendableRegistry.remove(this);
|
||||
final boolean wasAutomaticMode = m_automaticEnabled;
|
||||
setAutomaticMode(false);
|
||||
if (m_allocatedChannels) {
|
||||
if (m_pingChannel != null) {
|
||||
m_pingChannel.close();
|
||||
}
|
||||
if (m_echoChannel != null) {
|
||||
m_echoChannel.close();
|
||||
}
|
||||
}
|
||||
|
||||
if (m_counter != null) {
|
||||
m_counter.close();
|
||||
m_counter = null;
|
||||
}
|
||||
|
||||
m_pingChannel = null;
|
||||
m_echoChannel = null;
|
||||
synchronized (m_sensors) {
|
||||
m_sensors.remove(this);
|
||||
}
|
||||
if (!m_sensors.isEmpty() && wasAutomaticMode) {
|
||||
setAutomaticMode(true);
|
||||
}
|
||||
|
||||
if (m_simDevice != null) {
|
||||
m_simDevice.close();
|
||||
m_simDevice = null;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Turn Automatic mode on/off for all sensors.
|
||||
*
|
||||
* <p>When in Automatic mode, all sensors will fire in round-robin, waiting a set time between
|
||||
* each sensor.
|
||||
*
|
||||
* @param enabling Set to true if round-robin scheduling should start for all the ultrasonic
|
||||
* sensors. This scheduling method assures that the sensors are non-interfering because no two
|
||||
* sensors fire at the same time. If another scheduling algorithm is preferred, it can be
|
||||
* implemented by pinging the sensors manually and waiting for the results to come back.
|
||||
*/
|
||||
public static synchronized void setAutomaticMode(boolean enabling) {
|
||||
if (enabling == m_automaticEnabled) {
|
||||
return; // ignore the case of no change
|
||||
}
|
||||
m_automaticEnabled = enabling;
|
||||
|
||||
if (enabling) {
|
||||
/* Clear all the counters so no data is valid. No synchronization is
|
||||
* needed because the background task is stopped.
|
||||
*/
|
||||
for (Ultrasonic u : m_sensors) {
|
||||
u.m_counter.reset();
|
||||
}
|
||||
|
||||
// Start round robin task
|
||||
m_task = new UltrasonicChecker();
|
||||
m_task.start();
|
||||
} else {
|
||||
if (m_task != null) {
|
||||
// Wait for background task to stop running
|
||||
try {
|
||||
m_task.join();
|
||||
m_task = null;
|
||||
} catch (InterruptedException ex) {
|
||||
Thread.currentThread().interrupt();
|
||||
ex.printStackTrace();
|
||||
}
|
||||
}
|
||||
|
||||
/* Clear all the counters (data now invalid) since automatic mode is
|
||||
* disabled. No synchronization is needed because the background task is
|
||||
* stopped.
|
||||
*/
|
||||
for (Ultrasonic u : m_sensors) {
|
||||
u.m_counter.reset();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Single ping to ultrasonic sensor. Send out a single ping to the ultrasonic sensor. This only
|
||||
* works if automatic (round-robin) mode is disabled. A single ping is sent out, and the counter
|
||||
* should count the semi-period when it comes in. The counter is reset to make the current value
|
||||
* invalid.
|
||||
*/
|
||||
public void ping() {
|
||||
setAutomaticMode(false); // turn off automatic round-robin if pinging
|
||||
// single sensor
|
||||
m_counter.reset(); // reset the counter to zero (invalid data now)
|
||||
// do the ping to start getting a single range
|
||||
m_pingChannel.pulse(kPingTime);
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if there is a valid range measurement. The ranges are accumulated in a counter that will
|
||||
* increment on each edge of the echo (return) signal. If the count is not at least 2, then the
|
||||
* range has not yet been measured, and is invalid.
|
||||
*
|
||||
* @return true if the range is valid
|
||||
*/
|
||||
public boolean isRangeValid() {
|
||||
if (m_simRangeValid != null) {
|
||||
return m_simRangeValid.get();
|
||||
}
|
||||
return m_counter.get() > 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the range in inches from the ultrasonic sensor. If there is no valid value yet, i.e. at
|
||||
* least one measurement hasn't completed, then return 0.
|
||||
*
|
||||
* @return double Range in inches of the target returned from the ultrasonic sensor.
|
||||
*/
|
||||
public double getRangeInches() {
|
||||
if (isRangeValid()) {
|
||||
if (m_simRange != null) {
|
||||
return m_simRange.get();
|
||||
}
|
||||
return m_counter.getPeriod() * kSpeedOfSoundInchesPerSec / 2.0;
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the range in millimeters from the ultrasonic sensor. If there is no valid value yet, i.e.
|
||||
* at least one measurement hasn't completed, then return 0.
|
||||
*
|
||||
* @return double Range in millimeters of the target returned by the ultrasonic sensor.
|
||||
*/
|
||||
public double getRangeMM() {
|
||||
return getRangeInches() * 25.4;
|
||||
}
|
||||
|
||||
/**
|
||||
* Is the ultrasonic enabled.
|
||||
*
|
||||
* @return true if the ultrasonic is enabled
|
||||
*/
|
||||
public boolean isEnabled() {
|
||||
return m_enabled;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set if the ultrasonic is enabled.
|
||||
*
|
||||
* @param enable set to true to enable the ultrasonic
|
||||
*/
|
||||
public void setEnabled(boolean enable) {
|
||||
m_enabled = enable;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initSendable(SendableBuilder builder) {
|
||||
builder.setSmartDashboardType("Ultrasonic");
|
||||
builder.addDoubleProperty("Value", this::getRangeInches, null);
|
||||
}
|
||||
}
|
||||
@@ -6,25 +6,16 @@ package edu.wpi.first.wpilibj.counter;
|
||||
|
||||
/** Edge configuration. */
|
||||
public enum EdgeConfiguration {
|
||||
/** No edge configuration (neither rising nor falling). */
|
||||
kNone(false, false),
|
||||
/** Rising edge configuration. */
|
||||
kRisingEdge(true, false),
|
||||
kRisingEdge(true),
|
||||
/** Falling edge configuration. */
|
||||
kFallingEdge(false, true),
|
||||
/** Both rising and falling edge configuration. */
|
||||
kBoth(true, true);
|
||||
kFallingEdge(false);
|
||||
|
||||
/** True if triggering on rising edge. */
|
||||
@SuppressWarnings("MemberName")
|
||||
public final boolean rising;
|
||||
|
||||
/** True if triggering on falling edge. */
|
||||
@SuppressWarnings("MemberName")
|
||||
public final boolean falling;
|
||||
|
||||
EdgeConfiguration(boolean rising, boolean falling) {
|
||||
EdgeConfiguration(boolean rising) {
|
||||
this.rising = rising;
|
||||
this.falling = falling;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,111 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj.counter;
|
||||
|
||||
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import edu.wpi.first.hal.CounterJNI;
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.util.sendable.Sendable;
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.util.sendable.SendableRegistry;
|
||||
import edu.wpi.first.wpilibj.DigitalSource;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
/**
|
||||
* Counter using external direction.
|
||||
*
|
||||
* <p>This counts on an edge from one digital input and the whether it counts up or down based on
|
||||
* the state of a second digital input.
|
||||
*/
|
||||
public class ExternalDirectionCounter implements Sendable, AutoCloseable {
|
||||
private final DigitalSource m_countSource;
|
||||
private final DigitalSource m_directionSource;
|
||||
|
||||
private final int m_handle;
|
||||
|
||||
/**
|
||||
* Constructs a new ExternalDirectionCounter.
|
||||
*
|
||||
* @param countSource The source for counting.
|
||||
* @param directionSource The source for selecting count direction.
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public ExternalDirectionCounter(DigitalSource countSource, DigitalSource directionSource) {
|
||||
m_countSource = requireNonNullParam(countSource, "countSource", "ExternalDirectionCounter");
|
||||
m_directionSource =
|
||||
requireNonNullParam(directionSource, "directionSource", "ExternalDirectionCounter");
|
||||
|
||||
ByteBuffer index = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
index.order(ByteOrder.LITTLE_ENDIAN);
|
||||
m_handle = CounterJNI.initializeCounter(CounterJNI.EXTERNAL_DIRECTION, index.asIntBuffer());
|
||||
|
||||
CounterJNI.setCounterUpSource(
|
||||
m_handle,
|
||||
countSource.getPortHandleForRouting(),
|
||||
countSource.getAnalogTriggerTypeForRouting());
|
||||
CounterJNI.setCounterUpSourceEdge(m_handle, true, false);
|
||||
|
||||
CounterJNI.setCounterDownSource(
|
||||
m_handle,
|
||||
directionSource.getPortHandleForRouting(),
|
||||
directionSource.getAnalogTriggerTypeForRouting());
|
||||
CounterJNI.setCounterDownSourceEdge(m_handle, false, true);
|
||||
CounterJNI.resetCounter(m_handle);
|
||||
|
||||
int intIndex = index.getInt();
|
||||
HAL.report(tResourceType.kResourceType_Counter, intIndex + 1);
|
||||
SendableRegistry.add(this, "External Direction Counter", intIndex);
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the current count.
|
||||
*
|
||||
* @return The current count.
|
||||
*/
|
||||
public int getCount() {
|
||||
return CounterJNI.getCounter(m_handle);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets to reverse the counter direction.
|
||||
*
|
||||
* @param reverseDirection True to reverse counting direction.
|
||||
*/
|
||||
public void setReverseDirection(boolean reverseDirection) {
|
||||
CounterJNI.setCounterReverseDirection(m_handle, reverseDirection);
|
||||
}
|
||||
|
||||
/** Resets the current count. */
|
||||
public void reset() {
|
||||
CounterJNI.resetCounter(m_handle);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the edge configuration for counting.
|
||||
*
|
||||
* @param configuration The counting edge configuration.
|
||||
*/
|
||||
public void setEdgeConfiguration(EdgeConfiguration configuration) {
|
||||
CounterJNI.setCounterUpSourceEdge(m_handle, configuration.rising, configuration.falling);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void close() {
|
||||
SendableRegistry.remove(this);
|
||||
CounterJNI.freeCounter(m_handle);
|
||||
CounterJNI.suppressUnused(m_countSource);
|
||||
CounterJNI.suppressUnused(m_directionSource);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initSendable(SendableBuilder builder) {
|
||||
builder.setSmartDashboardType("External Direction Counter");
|
||||
builder.addDoubleProperty("Count", this::getCount, null);
|
||||
}
|
||||
}
|
||||
@@ -4,17 +4,12 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.counter;
|
||||
|
||||
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import edu.wpi.first.hal.CounterJNI;
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.util.sendable.Sendable;
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.util.sendable.SendableRegistry;
|
||||
import edu.wpi.first.wpilibj.DigitalSource;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
/**
|
||||
* Tachometer.
|
||||
@@ -25,38 +20,27 @@ import java.nio.ByteOrder;
|
||||
* encoders, this class only needs a single digital input.
|
||||
*/
|
||||
public class Tachometer implements Sendable, AutoCloseable {
|
||||
private final DigitalSource m_source;
|
||||
private final int m_handle;
|
||||
private int m_edgesPerRevolution = 1;
|
||||
|
||||
/**
|
||||
* Constructs a new tachometer.
|
||||
*
|
||||
* @param source The DigitalSource (e.g. DigitalInput) of the Tachometer.
|
||||
* @param channel The channel of the Tachometer.
|
||||
* @param configuration The edge configuration
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public Tachometer(DigitalSource source) {
|
||||
m_source = requireNonNullParam(source, "source", "Tachometer");
|
||||
public Tachometer(int channel, EdgeConfiguration configuration) {
|
||||
m_handle = CounterJNI.initializeCounter(channel, configuration.rising);
|
||||
|
||||
ByteBuffer index = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
index.order(ByteOrder.LITTLE_ENDIAN);
|
||||
m_handle = CounterJNI.initializeCounter(CounterJNI.TWO_PULSE, index.asIntBuffer());
|
||||
|
||||
CounterJNI.setCounterUpSource(
|
||||
m_handle, source.getPortHandleForRouting(), source.getAnalogTriggerTypeForRouting());
|
||||
CounterJNI.setCounterUpSourceEdge(m_handle, true, false);
|
||||
|
||||
int intIndex = index.getInt();
|
||||
HAL.report(tResourceType.kResourceType_Counter, intIndex + 1);
|
||||
SendableRegistry.add(this, "Tachometer", intIndex);
|
||||
HAL.report(tResourceType.kResourceType_Counter, channel + 1);
|
||||
SendableRegistry.add(this, "Tachometer", channel);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void close() {
|
||||
SendableRegistry.remove(this);
|
||||
CounterJNI.freeCounter(m_handle);
|
||||
CounterJNI.suppressUnused(m_source);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -138,24 +122,6 @@ public class Tachometer implements Sendable, AutoCloseable {
|
||||
return CounterJNI.getCounterStopped(m_handle);
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the number of samples to average.
|
||||
*
|
||||
* @return Samples to average.
|
||||
*/
|
||||
public int getSamplesToAverage() {
|
||||
return CounterJNI.getCounterSamplesToAverage(m_handle);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the number of samples to average.
|
||||
*
|
||||
* @param samplesToAverage Samples to average.
|
||||
*/
|
||||
public void setSamplesToAverage(int samplesToAverage) {
|
||||
CounterJNI.setCounterSamplesToAverage(m_handle, samplesToAverage);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the maximum period before the tachometer is considered stopped.
|
||||
*
|
||||
@@ -165,15 +131,6 @@ public class Tachometer implements Sendable, AutoCloseable {
|
||||
CounterJNI.setCounterMaxPeriod(m_handle, maxPeriod);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets if to update when empty.
|
||||
*
|
||||
* @param updateWhenEmpty Update when empty if true.
|
||||
*/
|
||||
public void setUpdateWhenEmpty(boolean updateWhenEmpty) {
|
||||
CounterJNI.setCounterUpdateWhenEmpty(m_handle, updateWhenEmpty);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initSendable(SendableBuilder builder) {
|
||||
builder.setSmartDashboardType("Tachometer");
|
||||
|
||||
@@ -10,9 +10,6 @@ import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.util.sendable.Sendable;
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.util.sendable.SendableRegistry;
|
||||
import edu.wpi.first.wpilibj.DigitalSource;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
/**
|
||||
* Up Down Counter.
|
||||
@@ -21,57 +18,28 @@ import java.nio.ByteOrder;
|
||||
* digital input and down on an edge from another digital input.
|
||||
*/
|
||||
public class UpDownCounter implements Sendable, AutoCloseable {
|
||||
private final DigitalSource m_upSource;
|
||||
private final DigitalSource m_downSource;
|
||||
|
||||
private final int m_handle;
|
||||
|
||||
/**
|
||||
* Constructs a new UpDown Counter.
|
||||
*
|
||||
* @param upSource The up count source (can be null).
|
||||
* @param downSource The down count source (can be null).
|
||||
* @param channel The up count source (can be null).
|
||||
* @param configuration The edge configuration.
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public UpDownCounter(DigitalSource upSource, DigitalSource downSource) {
|
||||
ByteBuffer index = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
index.order(ByteOrder.LITTLE_ENDIAN);
|
||||
m_handle = CounterJNI.initializeCounter(CounterJNI.TWO_PULSE, index.asIntBuffer());
|
||||
|
||||
if (upSource != null) {
|
||||
m_upSource = upSource;
|
||||
CounterJNI.setCounterUpSource(
|
||||
m_handle, upSource.getPortHandleForRouting(), upSource.getAnalogTriggerTypeForRouting());
|
||||
CounterJNI.setCounterUpSourceEdge(m_handle, true, false);
|
||||
} else {
|
||||
m_upSource = null;
|
||||
}
|
||||
|
||||
if (downSource != null) {
|
||||
m_downSource = downSource;
|
||||
CounterJNI.setCounterDownSource(
|
||||
m_handle,
|
||||
downSource.getPortHandleForRouting(),
|
||||
downSource.getAnalogTriggerTypeForRouting());
|
||||
CounterJNI.setCounterDownSourceEdge(m_handle, true, false);
|
||||
} else {
|
||||
m_downSource = null;
|
||||
}
|
||||
public UpDownCounter(int channel, EdgeConfiguration configuration) {
|
||||
m_handle = CounterJNI.initializeCounter(channel, configuration.rising);
|
||||
|
||||
reset();
|
||||
|
||||
int intIndex = index.getInt();
|
||||
HAL.report(tResourceType.kResourceType_Counter, intIndex + 1);
|
||||
SendableRegistry.add(this, "UpDown Counter", intIndex);
|
||||
HAL.report(tResourceType.kResourceType_Counter, channel);
|
||||
SendableRegistry.add(this, "UpDown Counter", channel);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void close() {
|
||||
SendableRegistry.remove(this);
|
||||
CounterJNI.freeCounter(m_handle);
|
||||
CounterJNI.suppressUnused(m_upSource);
|
||||
CounterJNI.suppressUnused(m_downSource);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -79,17 +47,8 @@ public class UpDownCounter implements Sendable, AutoCloseable {
|
||||
*
|
||||
* @param configuration The up source configuration.
|
||||
*/
|
||||
public void setUpEdgeConfiguration(EdgeConfiguration configuration) {
|
||||
CounterJNI.setCounterUpSourceEdge(m_handle, configuration.rising, configuration.falling);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the configuration for the down source.
|
||||
*
|
||||
* @param configuration The down source configuration.
|
||||
*/
|
||||
public void setDownEdgeConfiguration(EdgeConfiguration configuration) {
|
||||
CounterJNI.setCounterDownSourceEdge(m_handle, configuration.rising, configuration.falling);
|
||||
public void setEdgeConfiguration(EdgeConfiguration configuration) {
|
||||
CounterJNI.setCounterEdgeConfiguration(m_handle, configuration.rising);
|
||||
}
|
||||
|
||||
/** Resets the current count. */
|
||||
@@ -97,15 +56,6 @@ public class UpDownCounter implements Sendable, AutoCloseable {
|
||||
CounterJNI.resetCounter(m_handle);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets to reverse the counter direction.
|
||||
*
|
||||
* @param reverseDirection True to reverse counting direction.
|
||||
*/
|
||||
public void setReverseDirection(boolean reverseDirection) {
|
||||
CounterJNI.setCounterReverseDirection(m_handle, reverseDirection);
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the current count.
|
||||
*
|
||||
|
||||
@@ -1,65 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj.simulation;
|
||||
|
||||
import edu.wpi.first.hal.SimBoolean;
|
||||
import edu.wpi.first.hal.SimDouble;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.Ultrasonic;
|
||||
|
||||
/** Class to control a simulated {@link edu.wpi.first.wpilibj.Ultrasonic}. */
|
||||
public class UltrasonicSim {
|
||||
private final SimBoolean m_simRangeValid;
|
||||
private final SimDouble m_simRange;
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param ultrasonic The real ultrasonic to simulate
|
||||
*/
|
||||
public UltrasonicSim(Ultrasonic ultrasonic) {
|
||||
// ping parameter is unused
|
||||
this(-1, ultrasonic.getEchoChannel());
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param ping unused.
|
||||
* @param echo the ultrasonic's echo channel.
|
||||
*/
|
||||
public UltrasonicSim(@SuppressWarnings("unused") int ping, int echo) {
|
||||
SimDeviceSim simDevice = new SimDeviceSim("Ultrasonic", echo);
|
||||
m_simRangeValid = simDevice.getBoolean("Range Valid");
|
||||
m_simRange = simDevice.getDouble("Range (in)");
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets if the range measurement is valid.
|
||||
*
|
||||
* @param valid True if valid
|
||||
*/
|
||||
public void setRangeValid(boolean valid) {
|
||||
m_simRangeValid.set(valid);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the range measurement.
|
||||
*
|
||||
* @param inches The range in inches.
|
||||
*/
|
||||
public void setRangeInches(double inches) {
|
||||
m_simRange.set(inches);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the range measurement.
|
||||
*
|
||||
* @param meters The range in meters.
|
||||
*/
|
||||
public void setRangeMeters(double meters) {
|
||||
m_simRange.set(Units.metersToInches(meters));
|
||||
}
|
||||
}
|
||||
@@ -1,53 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import edu.wpi.first.wpilibj.simulation.UltrasonicSim;
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.junit.jupiter.params.ParameterizedTest;
|
||||
import org.junit.jupiter.params.provider.ValueSource;
|
||||
|
||||
class UltrasonicTest {
|
||||
@Test
|
||||
void testUltrasonic() {
|
||||
try (Ultrasonic ultrasonic = new Ultrasonic(0, 1)) {
|
||||
UltrasonicSim sim = new UltrasonicSim(ultrasonic);
|
||||
|
||||
assertEquals(0, ultrasonic.getRangeInches());
|
||||
assertTrue(ultrasonic.isRangeValid());
|
||||
|
||||
sim.setRangeInches(35.04);
|
||||
assertEquals(35.04, ultrasonic.getRangeInches());
|
||||
|
||||
sim.setRangeValid(false);
|
||||
assertFalse(ultrasonic.isRangeValid());
|
||||
assertEquals(0, ultrasonic.getRangeInches());
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void automaticModeToggle() {
|
||||
try (@SuppressWarnings("unused")
|
||||
Ultrasonic ultrasonic = new Ultrasonic(0, 1)) {
|
||||
assertDoesNotThrow(
|
||||
() -> {
|
||||
Ultrasonic.setAutomaticMode(true);
|
||||
Ultrasonic.setAutomaticMode(false);
|
||||
Ultrasonic.setAutomaticMode(true);
|
||||
});
|
||||
}
|
||||
}
|
||||
|
||||
@ValueSource(booleans = {true, false})
|
||||
@ParameterizedTest
|
||||
void automaticModeWithZeroInstances(boolean enabling) {
|
||||
assertDoesNotThrow(() -> Ultrasonic.setAutomaticMode(enabling));
|
||||
}
|
||||
}
|
||||
@@ -9,7 +9,6 @@ import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.Ultrasonic;
|
||||
import edu.wpi.first.wpilibj.event.BooleanEvent;
|
||||
import edu.wpi.first.wpilibj.event.EventLoop;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
@@ -17,7 +16,6 @@ import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
public class Robot extends TimedRobot {
|
||||
public static final int SHOT_VELOCITY = 200; // rpm
|
||||
public static final int TOLERANCE = 8; // rpm
|
||||
public static final int KICKER_THRESHOLD = 15; // mm
|
||||
|
||||
private final PWMSparkMax m_shooter = new PWMSparkMax(0);
|
||||
private final Encoder m_shooterEncoder = new Encoder(0, 1);
|
||||
@@ -25,7 +23,6 @@ public class Robot extends TimedRobot {
|
||||
private final SimpleMotorFeedforward m_ff = new SimpleMotorFeedforward(0.1, 0.065);
|
||||
|
||||
private final PWMSparkMax m_kicker = new PWMSparkMax(1);
|
||||
private final Ultrasonic m_kickerSensor = new Ultrasonic(2, 3);
|
||||
|
||||
private final PWMSparkMax m_intake = new PWMSparkMax(2);
|
||||
|
||||
@@ -37,7 +34,7 @@ public class Robot extends TimedRobot {
|
||||
m_controller.setTolerance(TOLERANCE);
|
||||
|
||||
BooleanEvent isBallAtKicker =
|
||||
new BooleanEvent(m_loop, () -> m_kickerSensor.getRangeMM() < KICKER_THRESHOLD);
|
||||
new BooleanEvent(m_loop, () -> false); // m_kickerSensor.getRangeMM() < KICKER_THRESHOLD);
|
||||
BooleanEvent intakeButton = new BooleanEvent(m_loop, () -> m_joystick.getRawButton(2));
|
||||
|
||||
// if the thumb button is held
|
||||
|
||||
@@ -101,33 +101,6 @@
|
||||
"mainclass": "Main",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Ultrasonic",
|
||||
"description": "View values from a ping-response ultrasonic sensor.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"Ultrasonic",
|
||||
"SmartDashboard"
|
||||
],
|
||||
"foldername": "ultrasonic",
|
||||
"gradlebase": "java",
|
||||
"mainclass": "Main",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Ultrasonic PID",
|
||||
"description": "Maintain a set distance from an obstacle with an ultrasonic sensor and PID control.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Ultrasonic",
|
||||
"PID",
|
||||
"Differential Drive"
|
||||
],
|
||||
"foldername": "ultrasonicpid",
|
||||
"gradlebase": "java",
|
||||
"mainclass": "Main",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Potentiometer PID",
|
||||
"description": "Maintain elevator position setpoints with a potentiometer and PID control.",
|
||||
|
||||
@@ -1,25 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.ultrasonic;
|
||||
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
*
|
||||
* <p>If you change your main robot class, change the parameter type.
|
||||
*/
|
||||
public static void main(String... args) {
|
||||
RobotBase.startRobot(Robot::new);
|
||||
}
|
||||
}
|
||||
@@ -1,63 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.ultrasonic;
|
||||
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.Ultrasonic;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
|
||||
/**
|
||||
* This is a sample program demonstrating how to read from a ping-response ultrasonic sensor with
|
||||
* the {@link Ultrasonic class}.
|
||||
*/
|
||||
public class Robot extends TimedRobot {
|
||||
// Creates a ping-response Ultrasonic object on DIO 1 and 2.
|
||||
Ultrasonic m_rangeFinder = new Ultrasonic(1, 2);
|
||||
|
||||
/** Called once at the beginning of the robot program. */
|
||||
public Robot() {
|
||||
// Add the ultrasonic on the "Sensors" tab of the dashboard
|
||||
// Data will update automatically
|
||||
SmartDashboard.putData("Sensors", m_rangeFinder);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
// We can read the distance in millimeters
|
||||
double distanceMillimeters = m_rangeFinder.getRangeMM();
|
||||
// ... or in inches
|
||||
double distanceInches = m_rangeFinder.getRangeInches();
|
||||
|
||||
// We can also publish the data itself periodically
|
||||
SmartDashboard.putNumber("Distance[mm]", distanceMillimeters);
|
||||
SmartDashboard.putNumber("Distance[inch]", distanceInches);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void testInit() {
|
||||
// By default, the Ultrasonic class polls all ultrasonic sensors in a round-robin to prevent
|
||||
// them from interfering from one another.
|
||||
// However, manual polling is also possible -- note that this disables automatic mode!
|
||||
m_rangeFinder.ping();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void testPeriodic() {
|
||||
if (m_rangeFinder.isRangeValid()) {
|
||||
// Data is valid, publish it
|
||||
SmartDashboard.putNumber("Distance[mm]", m_rangeFinder.getRangeMM());
|
||||
SmartDashboard.putNumber("Distance[inch]", m_rangeFinder.getRangeInches());
|
||||
|
||||
// Ping for next measurement
|
||||
m_rangeFinder.ping();
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void testExit() {
|
||||
// Enable automatic mode
|
||||
Ultrasonic.setAutomaticMode(true);
|
||||
}
|
||||
}
|
||||
@@ -1,25 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.ultrasonicpid;
|
||||
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
*
|
||||
* <p>If you change your main robot class, change the parameter type.
|
||||
*/
|
||||
public static void main(String... args) {
|
||||
RobotBase.startRobot(Robot::new);
|
||||
}
|
||||
}
|
||||
@@ -1,77 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.ultrasonicpid;
|
||||
|
||||
import edu.wpi.first.math.controller.PIDController;
|
||||
import edu.wpi.first.math.filter.MedianFilter;
|
||||
import edu.wpi.first.util.sendable.SendableRegistry;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.Ultrasonic;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
|
||||
/**
|
||||
* This is a sample program to demonstrate the use of a PIDController with an ultrasonic sensor to
|
||||
* reach and maintain a set distance from an object.
|
||||
*/
|
||||
public class Robot extends TimedRobot {
|
||||
// distance the robot wants to stay from an object
|
||||
// (one meter)
|
||||
static final double kHoldDistanceMillimeters = 1.0e3;
|
||||
|
||||
// proportional speed constant
|
||||
private static final double kP = 0.001;
|
||||
// integral speed constant
|
||||
private static final double kI = 0.0;
|
||||
// derivative speed constant
|
||||
private static final double kD = 0.0;
|
||||
|
||||
static final int kLeftMotorPort = 0;
|
||||
static final int kRightMotorPort = 1;
|
||||
|
||||
static final int kUltrasonicPingPort = 0;
|
||||
static final int kUltrasonicEchoPort = 1;
|
||||
|
||||
// Ultrasonic sensors tend to be quite noisy and susceptible to sudden outliers,
|
||||
// so measurements are filtered with a 5-sample median filter
|
||||
private final MedianFilter m_filter = new MedianFilter(5);
|
||||
|
||||
private final Ultrasonic m_ultrasonic = new Ultrasonic(kUltrasonicPingPort, kUltrasonicEchoPort);
|
||||
private final PWMSparkMax m_leftMotor = new PWMSparkMax(kLeftMotorPort);
|
||||
private final PWMSparkMax m_rightMotor = new PWMSparkMax(kRightMotorPort);
|
||||
private final DifferentialDrive m_robotDrive =
|
||||
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
|
||||
private final PIDController m_pidController = new PIDController(kP, kI, kD);
|
||||
|
||||
public Robot() {
|
||||
SendableRegistry.addChild(m_robotDrive, m_leftMotor);
|
||||
SendableRegistry.addChild(m_robotDrive, m_rightMotor);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void autonomousInit() {
|
||||
// Set setpoint of the pid controller
|
||||
m_pidController.setSetpoint(kHoldDistanceMillimeters);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void autonomousPeriodic() {
|
||||
double measurement = m_ultrasonic.getRangeMM();
|
||||
double filteredMeasurement = m_filter.calculate(measurement);
|
||||
double pidOutput = m_pidController.calculate(filteredMeasurement);
|
||||
|
||||
// disable input squaring -- PID output is linear
|
||||
m_robotDrive.arcadeDrive(pidOutput, 0, false);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void close() {
|
||||
m_leftMotor.close();
|
||||
m_rightMotor.close();
|
||||
m_ultrasonic.close();
|
||||
m_robotDrive.close();
|
||||
super.close();
|
||||
}
|
||||
}
|
||||
@@ -1,134 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.ultrasonicpid;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.hal.HAL.SimPeriodicBeforeCallback;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
|
||||
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim.KitbotGearing;
|
||||
import edu.wpi.first.wpilibj.simulation.DriverStationSim;
|
||||
import edu.wpi.first.wpilibj.simulation.PWMSim;
|
||||
import edu.wpi.first.wpilibj.simulation.SimHooks;
|
||||
import edu.wpi.first.wpilibj.simulation.UltrasonicSim;
|
||||
import org.junit.jupiter.api.AfterEach;
|
||||
import org.junit.jupiter.api.parallel.ResourceLock;
|
||||
import org.junit.jupiter.params.ParameterizedTest;
|
||||
import org.junit.jupiter.params.provider.ValueSource;
|
||||
|
||||
@ResourceLock("timing")
|
||||
class UltrasonicPIDTest {
|
||||
private final DCMotor m_gearbox = DCMotor.getFalcon500(2);
|
||||
private static final double kGearing = KitbotGearing.k10p71.value;
|
||||
public static final double kvVoltSecondsPerMeter = 1.98;
|
||||
public static final double kaVoltSecondsSquaredPerMeter = 0.2;
|
||||
private static final double kvVoltSecondsPerRadian = 1.5;
|
||||
private static final double kaVoltSecondsSquaredPerRadian = 0.3;
|
||||
private static final double kWheelDiameterMeters = 0.15;
|
||||
private static final double kTrackwidthMeters = 0.7;
|
||||
|
||||
private Robot m_robot;
|
||||
private Thread m_thread;
|
||||
|
||||
private DifferentialDrivetrainSim m_driveSim;
|
||||
private PWMSim m_leftMotorSim;
|
||||
private PWMSim m_rightMotorSim;
|
||||
private UltrasonicSim m_ultrasonicSim;
|
||||
private SimPeriodicBeforeCallback m_callback;
|
||||
|
||||
// distance between the robot's starting position and the object
|
||||
// we will update this in a moment
|
||||
private double m_startToObject = Double.POSITIVE_INFINITY;
|
||||
private double m_distanceMM;
|
||||
|
||||
// We're not using @BeforeEach so m_startToObject gets initialized properly
|
||||
private void startThread() {
|
||||
HAL.initialize(500, 0);
|
||||
SimHooks.pauseTiming();
|
||||
DriverStationSim.resetData();
|
||||
m_robot = new Robot();
|
||||
m_thread = new Thread(m_robot::startCompetition);
|
||||
m_driveSim =
|
||||
new DifferentialDrivetrainSim(
|
||||
LinearSystemId.identifyDrivetrainSystem(
|
||||
kvVoltSecondsPerMeter,
|
||||
kaVoltSecondsSquaredPerMeter,
|
||||
kvVoltSecondsPerRadian,
|
||||
kaVoltSecondsSquaredPerRadian),
|
||||
m_gearbox,
|
||||
kGearing,
|
||||
kTrackwidthMeters,
|
||||
kWheelDiameterMeters / 2.0,
|
||||
null);
|
||||
m_ultrasonicSim = new UltrasonicSim(Robot.kUltrasonicPingPort, Robot.kUltrasonicEchoPort);
|
||||
m_leftMotorSim = new PWMSim(Robot.kLeftMotorPort);
|
||||
m_rightMotorSim = new PWMSim(Robot.kRightMotorPort);
|
||||
|
||||
m_callback =
|
||||
HAL.registerSimPeriodicBeforeCallback(
|
||||
() -> {
|
||||
m_driveSim.setInputs(
|
||||
m_leftMotorSim.getSpeed() * RobotController.getBatteryVoltage(),
|
||||
m_rightMotorSim.getSpeed() * RobotController.getBatteryVoltage());
|
||||
m_driveSim.update(0.02);
|
||||
|
||||
double startingDistance = m_startToObject;
|
||||
double range = m_driveSim.getLeftPositionMeters() - startingDistance;
|
||||
|
||||
m_ultrasonicSim.setRangeMeters(range);
|
||||
m_distanceMM = range * 1.0e3;
|
||||
});
|
||||
|
||||
m_thread.start();
|
||||
SimHooks.stepTiming(0.0); // Wait for Notifiers
|
||||
SimHooks.stepTiming(0.02); // Have once iteration on disabled
|
||||
}
|
||||
|
||||
@AfterEach
|
||||
void stopThread() {
|
||||
m_robot.endCompetition();
|
||||
try {
|
||||
m_thread.interrupt();
|
||||
m_thread.join();
|
||||
} catch (InterruptedException ex) {
|
||||
Thread.currentThread().interrupt();
|
||||
}
|
||||
m_robot.close();
|
||||
m_callback.close();
|
||||
m_leftMotorSim.resetData();
|
||||
m_rightMotorSim.resetData();
|
||||
}
|
||||
|
||||
@ValueSource(doubles = {1.3, 0.5, 5.0})
|
||||
@ParameterizedTest
|
||||
void autoTest(double distance) {
|
||||
// set up distance
|
||||
{
|
||||
m_startToObject = distance;
|
||||
}
|
||||
startThread();
|
||||
|
||||
// auto init
|
||||
{
|
||||
DriverStationSim.setAutonomous(true);
|
||||
DriverStationSim.setEnabled(true);
|
||||
DriverStationSim.notifyNewData();
|
||||
|
||||
assertTrue(m_leftMotorSim.getInitialized());
|
||||
assertTrue(m_rightMotorSim.getInitialized());
|
||||
}
|
||||
|
||||
{
|
||||
SimHooks.stepTiming(5.0);
|
||||
|
||||
assertEquals(Robot.kHoldDistanceMillimeters, m_distanceMM, 10.0);
|
||||
}
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user