Skip to content
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
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;

import edu.wpi.first.math.filter.Debouncer;
import edu.wpi.first.math.filter.EdgeCounterFilter;
import edu.wpi.first.wpilibj.event.EventLoop;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
Expand Down Expand Up @@ -287,4 +288,31 @@ public boolean getAsBoolean() {
}
});
}

/**
* Creates a new multi-press trigger from this trigger - it will become active when this trigger
* has been activated the required number of times within the specified time window.
*
* <p>This is useful for implementing "double-click" style functionality.
*
* <p>Input for this must be stable, consider using a Debouncer before this to avoid counting
* noise as multiple presses.
*
* @param requiredPresses The number of presses required.
* @param windowTime The number of seconds in which the presses must occur.
* @return The multi-press trigger.
*/
public Trigger multiPress(int requiredPresses, double windowTime) {
return new Trigger(
m_loop,
new BooleanSupplier() {
final EdgeCounterFilter m_edgeCounterFilter =
new EdgeCounterFilter(requiredPresses, windowTime);

@Override
public boolean getAsBoolean() {
return m_edgeCounterFilter.calculate(m_condition.getAsBoolean());
}
});
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#include <utility>

#include <frc/filter/Debouncer.h>
#include <frc/filter/EdgeCountFilter.h>

#include "frc2/command/CommandPtr.h"

Expand Down Expand Up @@ -184,6 +185,14 @@ Trigger Trigger::Debounce(units::second_t debounceTime,
});
}

Trigger Trigger::MultiPress(int requiredPresses, units::second_t windowTime) {
return Trigger(m_loop,
[filter = frc::EdgeCounterFilter(requiredPresses, windowTime),
condition = m_condition]() mutable {
return filter.Calculate(condition());
});
}

bool Trigger::Get() const {
return m_condition();
}
Original file line number Diff line number Diff line change
Expand Up @@ -284,6 +284,22 @@ class Trigger {
frc::Debouncer::DebounceType type =
frc::Debouncer::DebounceType::kRising);

/**
* Creates a new multi-press trigger from this trigger - it will become active
* when this trigger has been activated the required number of times within
* the specified time window.
*
* <p>This is useful for implementing "double-click" style functionality.
*
* <p>Input for this must be stable, consider using a Debouncer before this to
* avoid counting noise as multiple presses.
*
* @param requiredPresses The number of presses required.
* @param windowTime The time in which the presses must occur.
* @return The multi-press trigger.
*/
Trigger MultiPress(int requiredPresses, units::second_t windowTime);

/**
* Returns the current state of this trigger.
*
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,120 @@
// 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.math.filter;

import edu.wpi.first.math.MathSharedStore;

/**
* A rising edge counter for boolean streams. Requires that the boolean change value to true for a
* specified number of times within a specified time window after the first rising edge before the
* filtered value changes.
*
* <p>The filter activates when the input has risen (transitioned from false to true) the required
* number of times within the time window. Once activated, the output remains true as long as the
* input is true. The edge count resets when the time window expires or when the input goes false
* after activation.
*
* <p>Input must be stable; consider using a Debouncer before this filter to avoid counting noise as
* multiple edges.
*/
public class EdgeCounterFilter {
private int m_requiredEdges;
private double m_windowTimeSeconds;

private double m_firstEdgeTimeSeconds;
private int m_currentCount;

private boolean m_lastInput;

/**
* Creates a new EdgeCounterFilter.
*
* @param requiredEdges The number of rising edges required before the output goes true.
* @param windowTime The maximum number of seconds in which all required edges must occur after
* the first rising edge.
*/
public EdgeCounterFilter(int requiredEdges, double windowTime) {
m_requiredEdges = requiredEdges;
m_windowTimeSeconds = windowTime;

resetTimer();
}

private void resetTimer() {
m_firstEdgeTimeSeconds = MathSharedStore.getTimestamp();
}

private boolean hasElapsed() {
return MathSharedStore.getTimestamp() - m_firstEdgeTimeSeconds >= m_windowTimeSeconds;
}

/**
* Applies the edge counter filter to the input stream.
*
* @param input The current value of the input stream.
* @return True if the required number of edges have occurred within the time window and the input
* is currently true; false otherwise.
*/
public boolean calculate(boolean input) {
boolean enoughEdges = m_currentCount >= m_requiredEdges;

boolean expired = hasElapsed() && !enoughEdges;
boolean activationEnded = !input && enoughEdges;

if (expired || activationEnded) {
m_currentCount = 0;
}

if (input && !m_lastInput) {
if (m_currentCount == 0) {
resetTimer(); // Start timer on first rising edge
}

m_currentCount++;
}

m_lastInput = input;

return input && m_currentCount >= m_requiredEdges;
}

/**
* Sets the time window duration.
*
* @param windowTime The maximum window of seconds in which all required edges must occur after
* the first rising edge.
*/
public void setWindowTime(double windowTime) {
m_windowTimeSeconds = windowTime;
}

/**
* Gets the time window duration.
*
* @return The maximum window of seconds in which all required edges must occur after the first
* rising edge.
*/
public double getWindowTime() {
return m_windowTimeSeconds;
}

/**
* Sets the required number of edges.
*
* @param requiredEdges The number of rising edges required before the output goes true.
*/
public void setRequiredEdges(int requiredEdges) {
m_requiredEdges = requiredEdges;
}

/**
* Gets the required number of edges.
*
* @return The number of rising edges required before the output goes true.
*/
public int getRequiredEdges() {
return m_requiredEdges;
}
}
46 changes: 46 additions & 0 deletions wpimath/src/main/native/cpp/filter/EdgeCountFilter.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
// 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/filter/EdgeCountFilter.h"

#include "wpimath/MathShared.h"

using namespace frc;

EdgeCounterFilter::EdgeCounterFilter(int requiredEdges, units::second_t window)
: m_requiredEdges(requiredEdges), m_windowTime(window) {
ResetTimer();
}

void EdgeCounterFilter::ResetTimer() {
m_firstEdgeTime = wpi::math::MathSharedStore::GetTimestamp();
}

bool EdgeCounterFilter::HasElapsed() const {
return wpi::math::MathSharedStore::GetTimestamp() - m_firstEdgeTime >=
m_windowTime;
}

bool EdgeCounterFilter::Calculate(bool input) {
bool enoughEdges = m_currentCount >= m_requiredEdges;

bool expired = HasElapsed() && !enoughEdges;
bool activationEnded = !input && enoughEdges;

if (expired || activationEnded) {
m_currentCount = 0;
}

if (input && !m_lastInput) {
if (m_currentCount == 0) {
ResetTimer(); // Start timer on first rising edge
}

m_currentCount++;
}

m_lastInput = input;

return input && m_currentCount >= m_requiredEdges;
}
94 changes: 94 additions & 0 deletions wpimath/src/main/native/include/frc/filter/EdgeCountFilter.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,94 @@
// 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 <wpi/SymbolExports.h>

#include "units/time.h"

namespace frc {
/**
* A rising edge counter for boolean streams. Requires that the boolean change
* value to true for a specified number of times within a specified time window
* after the first rising edge before the filtered value changes.
*
* The filter activates when the input has risen (transitioned from false to
* true) the required number of times within the time window. Once activated,
* the output remains true as long as the input is true. The edge count resets
* when the time window expires or when the input goes false after activation.
*
* Input must be stable; consider using a Debouncer before this filter to avoid
* counting noise as multiple edges.
*/
class WPILIB_DLLEXPORT EdgeCounterFilter {
public:
/**
* Creates a new EdgeCounterFilter.
*
* @param requiredEdges The number of rising edges required before the output
* goes true.
* @param windowTime The maximum time window in which all required edges must
* occur after the first rising edge.
*/
explicit EdgeCounterFilter(int requiredEdges, units::second_t windowTime);

/**
* Applies the edge counter filter to the input stream.
*
* @param input The current value of the input stream.
* @return True if the required number of edges have occurred within the time
* window and the input is currently true; false otherwise.
*/
bool Calculate(bool input);

/**
* Sets the time window duration.
*
* @param windowTime The maximum time window in which all required edges must
* occur after the first rising edge.
*/
constexpr void SetWindowTime(units::second_t windowTime) {
m_windowTime = windowTime;
}

/**
* Gets the time window duration.
*
* @return The maximum time window in which all required edges must occur
* after the first rising edge.
*/
constexpr units::second_t GetWindowTime() const { return m_windowTime; }

/**
* Sets the required number of edges.
*
* @param requiredEdges The number of rising edges required before the output
* goes true.
*/
constexpr void SetRequiredEdges(int requiredEdges) {
m_requiredEdges = requiredEdges;
}

/**
* Gets the required number of edges.
*
* @return The number of rising edges required before the output goes true.
*/
constexpr int GetRequiredEdges() const { return m_requiredEdges; }

private:
int m_requiredEdges;
units::second_t m_windowTime;

units::second_t m_firstEdgeTime;
int m_currentCount = 0;

bool m_lastInput = false;

void ResetTimer();

bool HasElapsed() const;
};
} // namespace frc
Loading
Loading