Skip to content

Commit

Permalink
Use Pair objects as the key for axis caches
Browse files Browse the repository at this point in the history
  • Loading branch information
Gold856 committed Jun 15, 2024
1 parent 61ee5cd commit cd7a489
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

package edu.wpi.first.wpilibj2.command.button;

import edu.wpi.first.math.Pair;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.event.EventLoop;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
Expand All @@ -18,7 +19,7 @@
public class CommandGenericHID {
private final GenericHID m_hid;
private final Map<EventLoop, Map<Integer, Trigger>> m_buttonCache = new HashMap<>();
private final Map<EventLoop, Map<Double, Trigger>> m_axisCache = new HashMap<>();
private final Map<EventLoop, Map<Pair<Integer, Double>, Trigger>> m_axisCache = new HashMap<>();
private final Map<EventLoop, Map<Integer, Trigger>> m_povCache = new HashMap<>();

/**
Expand Down Expand Up @@ -223,7 +224,7 @@ public Trigger axisLessThan(int axis, double threshold) {
public Trigger axisLessThan(int axis, double threshold, EventLoop loop) {
var cache = m_axisCache.computeIfAbsent(loop, k -> new HashMap<>());
return cache.computeIfAbsent(
axis * 100 - threshold, k -> new Trigger(loop, () -> getRawAxis(axis) < threshold));
new Pair<>(axis, threshold), k -> new Trigger(loop, () -> getRawAxis(axis) < threshold));
}

/**
Expand Down Expand Up @@ -253,7 +254,7 @@ public Trigger axisGreaterThan(int axis, double threshold) {
public Trigger axisGreaterThan(int axis, double threshold, EventLoop loop) {
var cache = m_axisCache.computeIfAbsent(loop, k -> new HashMap<>());
return cache.computeIfAbsent(
axis * 100 + threshold, k -> new Trigger(loop, () -> getRawAxis(axis) > threshold));
new Pair<>(axis, threshold), k -> new Trigger(loop, () -> getRawAxis(axis) > threshold));
}

/**
Expand Down
10 changes: 7 additions & 3 deletions wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@

import edu.wpi.first.hal.DriverStationJNI;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.Pair;
import edu.wpi.first.wpilibj.event.BooleanEvent;
import edu.wpi.first.wpilibj.event.EventLoop;
import java.util.HashMap;
Expand Down Expand Up @@ -98,7 +99,8 @@ public static HIDType of(int value) {
private int m_leftRumble;
private int m_rightRumble;
private final Map<EventLoop, Map<Integer, BooleanEvent>> m_buttonCache = new HashMap<>();
private final Map<EventLoop, Map<Double, BooleanEvent>> m_axisCache = new HashMap<>();
private final Map<EventLoop, Map<Pair<Integer, Double>, BooleanEvent>> m_axisCache =
new HashMap<>();
private final Map<EventLoop, Map<Integer, BooleanEvent>> m_povCache = new HashMap<>();

/**
Expand Down Expand Up @@ -344,7 +346,8 @@ public BooleanEvent povCenter(EventLoop loop) {
public BooleanEvent axisLessThan(int axis, double threshold, EventLoop loop) {
var cache = m_axisCache.computeIfAbsent(loop, k -> new HashMap<>());
return cache.computeIfAbsent(
axis * 100 - threshold, k -> new BooleanEvent(loop, () -> getRawAxis(axis) < threshold));
new Pair<>(axis, -threshold),
k -> new BooleanEvent(loop, () -> getRawAxis(axis) < threshold));
}

/**
Expand All @@ -360,7 +363,8 @@ public BooleanEvent axisLessThan(int axis, double threshold, EventLoop loop) {
public BooleanEvent axisGreaterThan(int axis, double threshold, EventLoop loop) {
var cache = m_axisCache.computeIfAbsent(loop, k -> new HashMap<>());
return cache.computeIfAbsent(
axis * 100 + threshold, k -> new BooleanEvent(loop, () -> getRawAxis(axis) > threshold));
new Pair<>(axis, threshold),
k -> new BooleanEvent(loop, () -> getRawAxis(axis) > threshold));
}

/**
Expand Down

0 comments on commit cd7a489

Please sign in to comment.