Skip to content

Commit

Permalink
Add mutex
Browse files Browse the repository at this point in the history
  • Loading branch information
Gold856 committed Jul 28, 2024
1 parent eadf7dd commit 319d6c0
Showing 1 changed file with 22 additions and 12 deletions.
34 changes: 22 additions & 12 deletions wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java
Original file line number Diff line number Diff line change
Expand Up @@ -166,8 +166,10 @@ public boolean getRawButtonReleased(int button) {
* @return an event instance representing the button's digital signal attached to the given loop.
*/
public BooleanEvent button(int button, EventLoop loop) {
var cache = m_buttonCache.computeIfAbsent(loop, k -> new HashMap<>());
return cache.computeIfAbsent(button, k -> new BooleanEvent(loop, () -> getRawButton(k)));
synchronized (m_buttonCache) {
var cache = m_buttonCache.computeIfAbsent(loop, k -> new HashMap<>());
return cache.computeIfAbsent(button, k -> new BooleanEvent(loop, () -> getRawButton(k)));
}
}

/**
Expand Down Expand Up @@ -231,10 +233,12 @@ public BooleanEvent pov(int angle, EventLoop loop) {
* @return a BooleanEvent instance based around this angle of a POV on the HID.
*/
public BooleanEvent pov(int pov, int angle, EventLoop loop) {
var cache = m_povCache.computeIfAbsent(loop, k -> new HashMap<>());
// angle can be -1, so use 3600 instead of 360
return cache.computeIfAbsent(
pov * 3600 + angle, k -> new BooleanEvent(loop, () -> getPOV(pov) == angle));
synchronized (m_povCache) {
var cache = m_povCache.computeIfAbsent(loop, k -> new HashMap<>());
// angle can be -1, so use 3600 instead of 360
return cache.computeIfAbsent(
pov * 3600 + angle, k -> new BooleanEvent(loop, () -> getPOV(pov) == angle));
}
}

/**
Expand Down Expand Up @@ -346,9 +350,12 @@ public BooleanEvent povCenter(EventLoop loop) {
* @return an event instance that is true when the axis value is less than the provided threshold.
*/
public BooleanEvent axisLessThan(int axis, double threshold, EventLoop loop) {
var cache = m_axisLessThanCache.computeIfAbsent(loop, k -> new HashMap<>());
return cache.computeIfAbsent(
Pair.of(axis, threshold), k -> new BooleanEvent(loop, () -> getRawAxis(axis) < threshold));
synchronized (m_axisLessThanCache) {
var cache = m_axisLessThanCache.computeIfAbsent(loop, k -> new HashMap<>());
return cache.computeIfAbsent(
Pair.of(axis, threshold),
k -> new BooleanEvent(loop, () -> getRawAxis(axis) < threshold));
}
}

/**
Expand All @@ -362,9 +369,12 @@ public BooleanEvent axisLessThan(int axis, double threshold, EventLoop loop) {
* threshold.
*/
public BooleanEvent axisGreaterThan(int axis, double threshold, EventLoop loop) {
var cache = m_axisGreaterThanCache.computeIfAbsent(loop, k -> new HashMap<>());
return cache.computeIfAbsent(
Pair.of(axis, threshold), k -> new BooleanEvent(loop, () -> getRawAxis(axis) > threshold));
synchronized (m_axisGreaterThanCache) {
var cache = m_axisGreaterThanCache.computeIfAbsent(loop, k -> new HashMap<>());
return cache.computeIfAbsent(
Pair.of(axis, threshold),
k -> new BooleanEvent(loop, () -> getRawAxis(axis) > threshold));
}
}

/**
Expand Down

0 comments on commit 319d6c0

Please sign in to comment.