Skip to content

Commit

Permalink
Add overloads for logging int32 values
Browse files Browse the repository at this point in the history
  • Loading branch information
jwbonner committed Nov 4, 2023
1 parent 97ea88b commit 28650c4
Show file tree
Hide file tree
Showing 9 changed files with 128 additions and 56 deletions.
2 changes: 1 addition & 1 deletion docs/DATA-FLOW.md
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ Below are definitions of each component:

Data is stored using string keys where slashes are used to denote subtables (similar to NetworkTables). Each subsystem stores data in a separate subtable. Like NetworkTables, **all logged values are persistent (they will continue to appear on subsequent cycles until updated**). The following simple data types are currently supported:

`boolean, long, float, double, String, boolean[], long[], float[], double[], String[], byte[]`
`boolean, int, long, float, double, String, boolean[], int[], long[], float[], double[], String[], byte[]`

## Structured Data Types

Expand Down
Original file line number Diff line number Diff line change
@@ -1,3 +1,16 @@
// Copyright 2021-2023 FRC 6328
// http://github.com/Mechanical-Advantage
//
// This program is free software; you can redistribute it and/or
// modify it under the terms of the GNU General Public License
// version 3 as published by the Free Software Foundation or
// available in the root directory of this project.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package org.littletonrobotics.junction;

import com.squareup.javapoet.*;
Expand Down Expand Up @@ -30,33 +43,18 @@ private static String getPackageName(Element e) {
private static final TypeName LOG_TABLE_TYPE = ClassName.get("org.littletonrobotics.junction", "LogTable");
private static final TypeName LOGGABLE_INPUTS_TYPE = ClassName.get("org.littletonrobotics.junction.inputs",
"LoggableInputs");
private static final Map<String, String> LOGGABLE_TYPES_LOOKUP = new HashMap<>();
private static final Map<String, String> UNLOGGABLE_TYPES_SUGGESTIONS = new HashMap<>();

static {
LOGGABLE_TYPES_LOOKUP.put("byte[]", "Raw");
LOGGABLE_TYPES_LOOKUP.put("boolean", "Boolean");
LOGGABLE_TYPES_LOOKUP.put("long", "Integer");
LOGGABLE_TYPES_LOOKUP.put("float", "Float");
LOGGABLE_TYPES_LOOKUP.put("double", "Double");
LOGGABLE_TYPES_LOOKUP.put("java.lang.String", "String");
LOGGABLE_TYPES_LOOKUP.put("boolean[]", "BooleanArray");
LOGGABLE_TYPES_LOOKUP.put("long[]", "IntegerArray");
LOGGABLE_TYPES_LOOKUP.put("float[]", "FloatArray");
LOGGABLE_TYPES_LOOKUP.put("double[]", "DoubleArray");
LOGGABLE_TYPES_LOOKUP.put("java.lang.String[]", "StringArray");

UNLOGGABLE_TYPES_SUGGESTIONS.put("java.lang.Byte[]", "byte[]");
UNLOGGABLE_TYPES_SUGGESTIONS.put("java.lang.Boolean", "boolean");
UNLOGGABLE_TYPES_SUGGESTIONS.put("java.lang.Integer", "int");
UNLOGGABLE_TYPES_SUGGESTIONS.put("java.lang.Long", "long");
UNLOGGABLE_TYPES_SUGGESTIONS.put("int", "long");
UNLOGGABLE_TYPES_SUGGESTIONS.put("java.lang.Integer", "long");
UNLOGGABLE_TYPES_SUGGESTIONS.put("java.lang.Float", "float");
UNLOGGABLE_TYPES_SUGGESTIONS.put("java.lang.Double", "double");
UNLOGGABLE_TYPES_SUGGESTIONS.put("java.lang.Boolean[]", "boolean[]");
UNLOGGABLE_TYPES_SUGGESTIONS.put("java.lang.Integer[]", "int[]");
UNLOGGABLE_TYPES_SUGGESTIONS.put("java.lang.Long[]", "long[]");
UNLOGGABLE_TYPES_SUGGESTIONS.put("int[]", "long[]");
UNLOGGABLE_TYPES_SUGGESTIONS.put("java.lang.Integer[]", "long[]");
UNLOGGABLE_TYPES_SUGGESTIONS.put("java.lang.Float[]", "float[]");
UNLOGGABLE_TYPES_SUGGESTIONS.put("java.lang.Double[]", "double[]");
}
Expand Down Expand Up @@ -93,11 +91,10 @@ public boolean process(Set<? extends TypeElement> annotations, RoundEnvironment
String logName = simpleName.substring(0, 1).toUpperCase() + simpleName.substring(1);

String fieldType = fieldElement.asType().toString();
String logType = LOGGABLE_TYPES_LOOKUP.get(fieldType);
String typeSuggestion = UNLOGGABLE_TYPES_SUGGESTIONS.get(fieldType);

// Check for unloggable types
if (typeSuggestion != null || (logType == null && fieldType.startsWith("java"))) {
if (typeSuggestion != null || (fieldType.startsWith("java") && !fieldType.startsWith("java.lang.String"))) {
String extraText = "";
if (typeSuggestion != null) {
extraText = "Did you mean to use \"" + typeSuggestion + "\" instead?";
Expand Down
47 changes: 47 additions & 0 deletions junction/core/src/org/littletonrobotics/junction/LogTable.java
Original file line number Diff line number Diff line change
Expand Up @@ -186,6 +186,14 @@ public void put(String key, boolean value) {
put(key, new LogValue(value, null));
}

/**
* Writes a new Integer value to the table. Skipped if the key already exists as
* a different type.
*/
public void put(String key, int value) {
put(key, (long) value);
}

/**
* Writes a new Integer value to the table. Skipped if the key already exists as
* a different type.
Expand Down Expand Up @@ -228,6 +236,18 @@ public void put(String key, boolean[] value) {
put(key, new LogValue(valueClone, null));
}

/**
* Writes a new IntegerArray value to the table. Skipped if the key already
* exists as a different type.
*/
public void put(String key, int[] value) {
long[] valueClone = new long[value.length];
for (int i = 0; i < value.length; i++) {
valueClone[i] = value[i];
}
put(key, new LogValue(valueClone, null));
}

/**
* Writes a new IntegerArray value to the table. Skipped if the key already
* exists as a different type.
Expand Down Expand Up @@ -454,6 +474,15 @@ public boolean get(String key, boolean defaultValue) {
}
}

/** Reads an Integer value from the table. */
public int get(String key, int defaultValue) {
if (data.containsKey(prefix + key)) {
return (int) get(key).getInteger(defaultValue);
} else {
return defaultValue;
}
}

/** Reads an Integer value from the table. */
public long get(String key, long defaultValue) {
if (data.containsKey(prefix + key)) {
Expand Down Expand Up @@ -499,6 +528,24 @@ public boolean[] get(String key, boolean[] defaultValue) {
}
}

/** Reads an IntegerArray value from the table. */
public int[] get(String key, int[] defaultValue) {
if (data.containsKey(prefix + key)) {
long[] defaultValueLong = new long[defaultValue.length];
for (int i = 0; i < defaultValue.length; i++) {
defaultValueLong[i] = defaultValue[i];
}
long[] valueLong = get(key).getIntegerArray(defaultValueLong);
int[] valueInt = new int[valueLong.length];
for (int i = 0; i < valueLong.length; i++) {
valueInt[i] = (int) valueLong[i];
}
return valueInt;
} else {
return defaultValue;
}
}

/** Reads an IntegerArray value from the table. */
public long[] get(String key, long[] defaultValue) {
if (data.containsKey(prefix + key)) {
Expand Down
28 changes: 28 additions & 0 deletions junction/core/src/org/littletonrobotics/junction/Logger.java
Original file line number Diff line number Diff line change
Expand Up @@ -424,6 +424,20 @@ public static void recordOutput(String key, boolean value) {
}
}

/**
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
*/
public static void recordOutput(String key, int value) {
if (running) {
outputTable.put(key, value);
}
}

/**
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
Expand Down Expand Up @@ -494,6 +508,20 @@ public static void recordOutput(String key, boolean[] value) {
}
}

/**
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
*
* @param key The name of the field to record. It will be stored under
* "/RealOutputs" or "/ReplayOutputs"
* @param value The value of the field.
*/
public static void recordOutput(String key, int[] value) {
if (running) {
outputTable.put(key, value);
}
}

/**
* Records a single output field for easy access when viewing the log. On the
* simulator, use this method to record extra data based on the original inputs.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,12 +41,12 @@ private LoggedDriverStation() {
* General driver station data that needs to be updated throughout the match.
*/
public static class DriverStationInputs implements LoggableInputs {
public long allianceStation = 0;
public int allianceStation = 0;
public String eventName = "";
public String gameSpecificMessage = "";
public long matchNumber = 0;
public long replayNumber = 0;
public long matchType = 0;
public int matchNumber = 0;
public int replayNumber = 0;
public int matchType = 0;
public double matchTime = 0.00;

public boolean enabled = false;
Expand Down Expand Up @@ -96,13 +96,13 @@ public void fromLog(LogTable table) {
*/
public static class JoystickInputs implements LoggableInputs {
public String name = "";
public long type = 0;
public int type = 0;
public boolean xbox = false;
public long buttonCount = 0;
public long buttonValues = 0;
public long[] povs = {};
public int buttonCount = 0;
public int buttonValues = 0;
public int[] povs = {};
public float[] axisValues = {};
public long[] axisTypes = {};
public int[] axisTypes = {};

public void toLog(LogTable table) {
table.put("Name", name);
Expand Down Expand Up @@ -162,7 +162,7 @@ public static void periodic() {
// POVs
int povCount = conduit.getPovCount(id);
int[] povValues = conduit.getPovValues(id);
joystick.povs = new long[povCount];
joystick.povs = new int[povCount];
for (int i = 0; i < povCount; i++) {
joystick.povs[i] = povValues[i];
}
Expand All @@ -172,7 +172,7 @@ public static void periodic() {
float[] axisValues = conduit.getAxisValues(id);
int[] axisTypes = conduit.getAxisTypes(id);
joystick.axisValues = new float[axisCount];
joystick.axisTypes = new long[axisCount];
joystick.axisTypes = new int[axisCount];
for (int i = 0; i < axisCount; i++) {
joystick.axisValues[i] = axisValues[i];
joystick.axisTypes[i] = axisTypes[i];
Expand Down Expand Up @@ -256,7 +256,7 @@ private static class MatchDataSender {
private void sendMatchData(DriverStationInputs dsInputs) {
boolean isRedAlliance = false;
int stationNumber = 1;
switch ((int) dsInputs.allianceStation) {
switch (dsInputs.allianceStation) {
case 0:
isRedAlliance = true;
stationNumber = 1;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,8 +86,8 @@ public void toLog(LogTable table) {
table.put("TotalEnergy", pdpTotalEnergy);

table.put("ChannelCount", channelCount);
table.put("Faults", (int) faults);
table.put("StickyFaults", (int) stickyFaults);
table.put("Faults", faults);
table.put("StickyFaults", stickyFaults);
}

@Override
Expand All @@ -99,7 +99,7 @@ public void fromLog(LogTable table) {
pdpTotalPower = table.get("TotalPower", pdpTotalPower);
pdpTotalEnergy = table.get("TotalEnergy", pdpTotalEnergy);

channelCount = (int) table.get("ChannelCount", channelCount);
channelCount = table.get("ChannelCount", channelCount);
faults = table.get("Faults", faults);
stickyFaults = table.get("StickyFaults", stickyFaults);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -103,11 +103,11 @@ public void toLog(LogTable table) {

@Override
public void fromLog(LogTable table) {
fpgaVersion = (int) table.get("FPGAVersion", fpgaVersion);
fpgaRevision = (int) table.get("FPGARevision", fpgaRevision);
fpgaVersion = table.get("FPGAVersion", fpgaVersion);
fpgaRevision = table.get("FPGARevision", fpgaRevision);
serialNumber = table.get("SerialNumber", serialNumber);
comments = table.get("Comments", comments);
teamNumber = (int) table.get("TeamNumber", teamNumber);
teamNumber = table.get("TeamNumber", teamNumber);
fpgaButton = table.get("FPGAButton", fpgaButton);
systemActive = table.get("SystemActive", systemActive);
brownedOut = table.get("BrownedOut", brownedOut);
Expand All @@ -120,27 +120,27 @@ public void fromLog(LogTable table) {
userVoltage3v3 = table.get("3v3Rail/Voltage", userVoltage3v3);
userCurrent3v3 = table.get("3v3Rail/Current", userCurrent3v3);
userActive3v3 = table.get("3v3Rail/Active", userActive3v3);
userCurrentFaults3v3 = (int) table.get("3v3Rail/CurrentFaults", userCurrentFaults3v3);
userCurrentFaults3v3 = table.get("3v3Rail/CurrentFaults", userCurrentFaults3v3);

userVoltage5v = table.get("5vRail/Voltage", userVoltage5v);
userCurrent5v = table.get("5vRail/Current", userCurrent5v);
userActive5v = table.get("5vRail/Active", userActive5v);
userCurrentFaults5v = (int) table.get("5vRail/CurrentFaults", userCurrentFaults5v);
userCurrentFaults5v = table.get("5vRail/CurrentFaults", userCurrentFaults5v);

userVoltage6v = table.get("6vRail/Voltage", userVoltage6v);
userCurrent6v = table.get("6vRail/Current", userCurrent6v);
userActive6v = table.get("6vRail/Active", userActive6v);
userCurrentFaults6v = (int) table.get("6vRail/CurrentFaults", userCurrentFaults6v);
userCurrentFaults6v = table.get("6vRail/CurrentFaults", userCurrentFaults6v);

brownoutVoltage = table.get("BrownoutVoltage", brownoutVoltage);
cpuTemp = table.get("CPUTempCelcius", cpuTemp);

canStatus.setStatus(
table.get("CANBus/Utilization", canStatus.percentBusUtilization),
(int) table.get("CANBus/OffCount", canStatus.busOffCount),
(int) table.get("CANBus/TxFullCount", canStatus.txFullCount),
(int) table.get("CANBus/ReceiveErrorCount", canStatus.receiveErrorCount),
(int) table.get("CANBus/TransmitErrorCount", canStatus.transmitErrorCount));
table.get("CANBus/OffCount", canStatus.busOffCount),
table.get("CANBus/TxFullCount", canStatus.txFullCount),
table.get("CANBus/ReceiveErrorCount", canStatus.receiveErrorCount),
table.get("CANBus/TransmitErrorCount", canStatus.transmitErrorCount));

epochTime = table.get("EpochTimeMicros", epochTime);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ public void putTable(LogTable table) {

// Update match
MatchType matchType;
switch ((int) table.get("DriverStation/MatchType", 0)) {
switch (table.get("DriverStation/MatchType", 0)) {
case 1:
matchType = MatchType.Practice;
break;
Expand Down Expand Up @@ -150,7 +150,7 @@ public void putTable(LogTable table) {
default:
break;
}
logMatchText += Long.toString(table.get("DriverStation/MatchNumber", 0));
logMatchText += Integer.toString(table.get("DriverStation/MatchNumber", 0));
}

// Update filename
Expand Down
Loading

0 comments on commit 28650c4

Please sign in to comment.