Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

DutyCycle: Add warning about frequency measurements to docs #7751

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,9 @@ public class DutyCycleJNI extends JNIWrapper {
/**
* Get the frequency of the duty cycle signal.
*
* <p><b>Warning: This will return inaccurate values for up to 2 seconds after the duty cycle
* input is initialized.</b>
*
* @param handle the duty cycle handle
* @return frequency in Hertz
* @see "HAL_GetDutyCycleFrequency"
Expand Down
3 changes: 3 additions & 0 deletions hal/src/main/native/include/hal/DutyCycle.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,9 @@ void HAL_SetDutyCycleSimDevice(HAL_DutyCycleHandle handle,
/**
* Get the frequency of the duty cycle signal.
*
* @warning This will return inaccurate values for up to 2 seconds after the
* duty cycle input is initialized.
*
* @param[in] dutyCycleHandle the duty cycle handle
* @param[out] status Error status variable. 0 on success.
* @return frequency in Hertz
Expand Down
3 changes: 3 additions & 0 deletions wpilibc/src/main/native/include/frc/DutyCycle.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,9 @@ class DutyCycle : public wpi::Sendable, public wpi::SendableHelper<DutyCycle> {
/**
* Get the frequency of the duty cycle signal.
*
* @warning This will return inaccurate values for up to 2 seconds after this
* duty cycle input is initialized.
*
* @return frequency in Hertz
*/
int GetFrequency() const;
Expand Down
32 changes: 24 additions & 8 deletions wpilibc/src/main/native/include/frc/DutyCycleEncoder.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,12 @@ class DigitalSource;
* Class for supporting duty cycle/PWM encoders, such as the US Digital MA3 with
* PWM Output, the CTRE Mag Encoder, the Rev Hex Encoder, and the AM Mag
* Encoder.
*
* @warning By default, position readings from Get() will be inaccurate for up
* to 2 seconds after this object is initialized. Setting the frequency of the
* encoder's output using {@link #setAssumedFrequency(double)} can be used to
* mitigate this, though users should verify the true frequency of the specific
* encoder in use as it can vary between devices.
*/
class DutyCycleEncoder : public wpi::Sendable,
public wpi::SendableHelper<DutyCycleEncoder> {
Expand Down Expand Up @@ -93,7 +99,7 @@ class DutyCycleEncoder : public wpi::Sendable,
*
* @param channel the channel to attach to
* @param fullRange the value to report at maximum travel
* @param expectedZero the reading where you would expect a 0 from get()
* @param expectedZero the reading where you would expect a 0 from Get()
*/
DutyCycleEncoder(int channel, double fullRange, double expectedZero);

Expand All @@ -102,7 +108,7 @@ class DutyCycleEncoder : public wpi::Sendable,
*
* @param dutyCycle the duty cycle to attach to
* @param fullRange the value to report at maximum travel
* @param expectedZero the reading where you would expect a 0 from get()
* @param expectedZero the reading where you would expect a 0 from Get()
*/
DutyCycleEncoder(DutyCycle& dutyCycle, double fullRange, double expectedZero);

Expand All @@ -111,7 +117,7 @@ class DutyCycleEncoder : public wpi::Sendable,
*
* @param dutyCycle the duty cycle to attach to
* @param fullRange the value to report at maximum travel
* @param expectedZero the reading where you would expect a 0 from get()
* @param expectedZero the reading where you would expect a 0 from Get()
*/
DutyCycleEncoder(DutyCycle* dutyCycle, double fullRange, double expectedZero);

Expand All @@ -120,7 +126,7 @@ class DutyCycleEncoder : public wpi::Sendable,
*
* @param dutyCycle the duty cycle to attach to
* @param fullRange the value to report at maximum travel
* @param expectedZero the reading where you would expect a 0 from get()
* @param expectedZero the reading where you would expect a 0 from Get()
*/
DutyCycleEncoder(std::shared_ptr<DutyCycle> dutyCycle, double fullRange,
double expectedZero);
Expand All @@ -130,7 +136,7 @@ class DutyCycleEncoder : public wpi::Sendable,
*
* @param digitalSource the digital source to attach to
* @param fullRange the value to report at maximum travel
* @param expectedZero the reading where you would expect a 0 from get()
* @param expectedZero the reading where you would expect a 0 from Get()
*/
DutyCycleEncoder(DigitalSource& digitalSource, double fullRange,
double expectedZero);
Expand All @@ -140,7 +146,7 @@ class DutyCycleEncoder : public wpi::Sendable,
*
* @param digitalSource the digital source to attach to
* @param fullRange the value to report at maximum travel
* @param expectedZero the reading where you would expect a 0 from get()
* @param expectedZero the reading where you would expect a 0 from Get()
*/
DutyCycleEncoder(DigitalSource* digitalSource, double fullRange,
double expectedZero);
Expand All @@ -150,7 +156,7 @@ class DutyCycleEncoder : public wpi::Sendable,
*
* @param digitalSource the digital source to attach to
* @param fullRange the value to report at maximum travel
* @param expectedZero the reading where you would expect a 0 from get()
* @param expectedZero the reading where you would expect a 0 from Get()
*/
DutyCycleEncoder(std::shared_ptr<DigitalSource> digitalSource,
double fullRange, double expectedZero);
Expand All @@ -163,6 +169,9 @@ class DutyCycleEncoder : public wpi::Sendable,
/**
* Get the frequency in Hz of the duty cycle signal from the encoder.
*
* @warning This will return inaccurate values for up to 2 seconds after this
* encoder is initialized.
*
* @return duty cycle frequency in Hz
*/
int GetFrequency() const;
Expand All @@ -174,6 +183,9 @@ class DutyCycleEncoder : public wpi::Sendable,
* By default, a value of 100 Hz is used as the threshold, and this value can
* be changed with SetConnectedFrequencyThreshold.
*
* @warning This will return inaccurate values for up to 2 seconds after this
* encoder is initialized.
*
* @return true if the sensor is connected
*/
bool IsConnected() const;
Expand All @@ -189,6 +201,9 @@ class DutyCycleEncoder : public wpi::Sendable,
/**
* Get the encoder value.
*
* @warning This will return inaccurate values for up to 2 seconds after this
* encoder is initialized unless SetAssumedFrequency() is used.
*
* @return the encoder value scaled by the full range input
*/
double Get() const;
Expand All @@ -215,7 +230,8 @@ class DutyCycleEncoder : public wpi::Sendable,
* input signal. This can result in both delayed readings and jumpy readings.
* To solve this, you can pass the expected frequency of the sensor to this
* function. This will use that frequency to compute the DutyCycle percentage,
* rather than the computed frequency.
* rather than the computed frequency. Users should verify the true frequency
* of the specific encoder in use as it can vary between devices.
*
* @param frequency the assumed frequency of the sensor
*/
Expand Down
3 changes: 3 additions & 0 deletions wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,9 @@ public void close() {
/**
* Get the frequency of the duty cycle signal.
*
* <p><b>Warning: This will return inaccurate values for up to 2 seconds after the duty cycle
* input is initialized.</b>
*
* @return frequency in Hertz
*/
public int getFrequency() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,11 @@
/**
* Class for supporting duty cycle/PWM encoders, such as the US Digital MA3 with PWM Output, the
* CTRE Mag Encoder, the Rev Hex Encoder, and the AM Mag Encoder.
*
* <p><b>Warning: By default, position readings from {@link #get()} will be inaccurate for up to 2
* seconds after this encoder is initialized.</b> Setting the frequency of the encoder's output
* using {@link #setAssumedFrequency(double)} can be used to mitigate this, though users should
* verify the true frequency of the specific encoder in use as it can vary between devices.
*/
public class DutyCycleEncoder implements Sendable, AutoCloseable {
private final DutyCycle m_dutyCycle;
Expand Down Expand Up @@ -137,11 +142,12 @@ private double mapSensorRange(double pos) {
}

/**
* Get the encoder value since the last reset.
* Get the encoder value.
*
* <p>This is reported in rotations since the last reset.
* <p><b> Warning: This will return inaccurate values for up to 2 seconds after this encoder is
* initialized unless {@link #setAssumedFrequency(double)} is used.</b>
*
* @return the encoder value in rotations
* @return the encoder value scaled by the full range input
*/
public double get() {
if (m_simPosition != null) {
Expand Down Expand Up @@ -191,14 +197,18 @@ public void setDutyCycleRange(double min, double max) {
/**
* Get the frequency in Hz of the duty cycle signal from the encoder.
*
* <p><b>Warning: This will return inaccurate values for up to 2 seconds after this encoder is
* initialized.</b>
*
* @return duty cycle frequency in Hz
*/
public int getFrequency() {
return m_dutyCycle.getFrequency();
}

/**
* Get if the sensor is connected
* Get if the sensor is connected <b>Warning: This will return inaccurate values for up to 2
* seconds after the duty cycle input is initialized.</b>
*
* <p>This uses the duty cycle frequency to determine if the sensor is connected. By default, a
* value of 100 Hz is used as the threshold, and this value can be changed with {@link
Expand Down Expand Up @@ -232,7 +242,8 @@ public void setConnectedFrequencyThreshold(int frequency) {
* <p>By default, the DutyCycle engine has to compute the frequency of the input signal. This can
* result in both delayed readings and jumpy readings. To solve this, you can pass the expected
* frequency of the sensor to this function. This will use that frequency to compute the DutyCycle
* percentage, rather than the computed frequency.
* percentage, rather than the computed frequency. Users should verify the true frequency of the
* specific encoder in use as it can vary between devices.
*
* @param frequency the assumed frequency of the sensor
*/
Expand Down
Loading