-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathLoggedTunableNumber.java
More file actions
126 lines (111 loc) · 4.11 KB
/
LoggedTunableNumber.java
File metadata and controls
126 lines (111 loc) · 4.11 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
package frc.lib.NinjasLib;
import java.util.Arrays;
import java.util.HashMap;
import java.util.Map;
import java.util.function.Consumer;
import java.util.function.DoubleSupplier;
import frc.robot.RobotState;
import org.littletonrobotics.junction.networktables.LoggedNetworkNumber;
/**
* Class for a tunable number. Gets value from dashboard in tuning mode, returns default if not or
* value not in dashboard.
*/
@SuppressWarnings("unused")
public class LoggedTunableNumber implements DoubleSupplier {
private static final String tableKey = "/Tuning";
private final String key;
private boolean hasDefault = false;
private double defaultValue;
private LoggedNetworkNumber dashboardNumber;
private Map<Integer, Double> lastHasChangedValues = new HashMap<>();
private final boolean tuningMode;
/**
* Create a new LoggedTunableNumber
*
* @param dashboardKey Key on dashboard
* @param isTuning Get whether the value is in tuning mode
*/
public LoggedTunableNumber(String dashboardKey, boolean isTuning) {
this.key = tableKey + "/" + dashboardKey;
this.tuningMode = isTuning;
}
/**
* Create a new LoggedTunableNumber with the default value
*
* @param dashboardKey Key on dashboard
* @param isTuning Get whether the value is in tuning mode
* @param defaultValue Default value
*/
public LoggedTunableNumber(String dashboardKey, double defaultValue, boolean isTuning) {
this(dashboardKey, isTuning);
initDefault(defaultValue);
}
/**
* Set the default value of the number. The default value can only be set once.
*
* @param defaultValue The default value
*/
public void initDefault(double defaultValue) {
if (!hasDefault) {
hasDefault = true;
this.defaultValue = defaultValue;
if (tuningMode) {
dashboardNumber = new LoggedNetworkNumber(key, defaultValue);
}
}
}
/**
* Get the current value, from dashboard if available and in tuning mode.
*
* @return The current value
*/
public double get() {
if (!hasDefault) {
return 0.0;
} else {
return tuningMode ? dashboardNumber.get() : defaultValue;
}
}
/**
* Checks whether the number has changed since our last check
*
* @param id Unique identifier for the caller to avoid conflicts when shared between multiple
* objects. Recommended approach is to pass the result of "hashCode()"
* @return True if the number has changed since the last time this method was called, false
* otherwise.
*/
public boolean hasChanged(int id) {
if (!tuningMode)
return false;
double currentValue = get();
Double lastValue = lastHasChangedValues.get(id);
if (lastValue == null || currentValue != lastValue) {
lastHasChangedValues.put(id, currentValue);
return true;
}
return false;
}
/**
* Runs action if any of the tunableNumbers have changed
*
* @param id Unique identifier for the caller to avoid conflicts when shared between multiple *
* objects. Recommended approach is to pass the result of "hashCode()"
* @param action Callback to run when any of the tunable numbers have changed. Access tunable
* numbers in order inputted in method
* @param tunableNumbers All tunable numbers to check
*/
public static void ifChanged(
int id, Consumer<double[]> action, LoggedTunableNumber... tunableNumbers) {
if (Arrays.stream(tunableNumbers).anyMatch(tunableNumber -> tunableNumber.hasChanged(id))) {
action.accept(Arrays.stream(tunableNumbers).mapToDouble(LoggedTunableNumber::get).toArray());
}
}
/** Runs action if any of the tunableNumbers have changed */
public static void ifChanged(int id, Runnable action, LoggedTunableNumber... tunableNumbers) {
ifChanged(id, values -> action.run(), tunableNumbers);
}
@Override
public double getAsDouble() {
return get();
}
}