Merge branch 'main' into 2027

This commit is contained in:
Peter Johnson
2026-02-15 00:51:21 -08:00
98 changed files with 3031 additions and 219 deletions

View File

@@ -11,6 +11,7 @@ import org.wpilib.command2.Command;
import org.wpilib.command2.CommandScheduler;
import org.wpilib.event.EventLoop;
import org.wpilib.math.filter.Debouncer;
import org.wpilib.math.filter.EdgeCounterFilter;
/**
* This class provides an easy way to link commands to conditions.
@@ -287,4 +288,31 @@ public class Trigger implements BooleanSupplier {
}
});
}
/**
* 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());
}
});
}
}

View File

@@ -8,6 +8,7 @@
#include "wpi/commands2/CommandPtr.hpp"
#include "wpi/math/filter/Debouncer.hpp"
#include "wpi/math/filter/EdgeCounterFilter.hpp"
using namespace wpi;
using namespace wpi::cmd;
@@ -183,6 +184,14 @@ Trigger Trigger::Debounce(wpi::units::second_t debounceTime,
});
}
Trigger Trigger::MultiPress(int requiredPresses, units::second_t windowTime) {
return Trigger(m_loop, [filter = wpi::math::EdgeCounterFilter(requiredPresses,
windowTime),
condition = m_condition]() mutable {
return filter.Calculate(condition());
});
}
bool Trigger::Get() const {
return m_condition();
}

View File

@@ -283,6 +283,22 @@ class Trigger {
wpi::math::Debouncer::DebounceType type =
wpi::math::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.
*