Skip to content
This repository has been archived by the owner on Feb 18, 2024. It is now read-only.

Commit

Permalink
Fix bug with Modules accessing tuneable numbers from a static context…
Browse files Browse the repository at this point in the history
… in a non-static manner

Object concurrency issues, see doc
  • Loading branch information
srimanachanta committed Dec 14, 2023
1 parent 1d17d12 commit f4f29f0
Show file tree
Hide file tree
Showing 2 changed files with 32 additions and 16 deletions.
10 changes: 7 additions & 3 deletions src/main/java/frc/robot/subsystems/drive/Module.java
Original file line number Diff line number Diff line change
Expand Up @@ -91,13 +91,17 @@ public void updateInputs() {
public void periodic() {
Logger.processInputs("Drive/Module" + kModuleIndex, m_inputs);

if (driveKs.hasChanged() || driveKv.hasChanged()) {
if (driveKs.hasChanged(kModuleIndex) || driveKv.hasChanged(kModuleIndex)) {
m_driveFeedforward = new SimpleMotorFeedforward(driveKs.get(), driveKv.get());
}
if (driveKp.hasChanged() || driveKi.hasChanged() || driveKd.hasChanged()) {
if (driveKp.hasChanged(kModuleIndex)
|| driveKi.hasChanged(kModuleIndex)
|| driveKd.hasChanged(kModuleIndex)) {
m_driveController.setPID(driveKp.get(), driveKi.get(), driveKd.get());
}
if (turnKp.hasChanged() || turnKi.hasChanged() || turnKd.hasChanged()) {
if (turnKp.hasChanged(kModuleIndex)
|| turnKi.hasChanged(kModuleIndex)
|| turnKd.hasChanged(kModuleIndex)) {
m_turnController.setPID(turnKp.get(), turnKi.get(), turnKd.get());
}

Expand Down
38 changes: 25 additions & 13 deletions src/main/java/frc/robot/util/LoggedTunableNumber.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
package frc.robot.util;

import frc.robot.constants.Constants;
import java.util.HashMap;
import java.util.Map;
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;

/**
Expand All @@ -12,7 +14,9 @@ public class LoggedTunableNumber {

private final String key;
private Double defaultValue = null;
private Double lastValue = null;

private final Map<Integer, Double> lastValues = new HashMap<>();

private LoggedDashboardNumber dashboardNumber;

/**
Expand Down Expand Up @@ -41,11 +45,15 @@ public LoggedTunableNumber(String dashboardKey, double defaultValue) {
* @param defaultValue The default value
*/
public void initDefault(double defaultValue) {
if (this.defaultValue == null) {
this.defaultValue = defaultValue;
if (Constants.TUNING_MODE) {
dashboardNumber = new LoggedDashboardNumber(key, defaultValue);
}
if (this.defaultValue != null) {
throw new IllegalStateException(
String.format(
"[LoggedTunableNumber][%s] Has already been initialized with a default value.", key));
}

this.defaultValue = defaultValue;
if (Constants.TUNING_MODE) {
dashboardNumber = new LoggedDashboardNumber(key, defaultValue);
}
}

Expand All @@ -66,17 +74,21 @@ public double get() {
}

/**
* Checks whether the number has changed since the last time this method was called.
* Checks whether the number has changed since the last time this method was called. Returns true
* the first time this method is called.
*
* @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 Whether the value has changed since the last time this method was called
*/
public boolean hasChanged() {
var currentVal = get();
if (lastValue == null || lastValue != currentVal) {
lastValue = currentVal;
public boolean hasChanged(int id) {
double currentValue = get();
var lastValue = lastValues.get(id);
if (lastValue == null || currentValue != lastValue) {
lastValues.put(id, currentValue);
return true;
} else {
return false;
}

return false;
}
}

0 comments on commit f4f29f0

Please sign in to comment.