From 231c2aeefc660fb4879bc489c9600fd26f5649e5 Mon Sep 17 00:00:00 2001 From: Jay Tarbotton Date: Fri, 12 Jan 2024 15:40:01 -0500 Subject: [PATCH 1/4] Reset Preferences before each unit test. Remove flaky tests. --- src/main/java/frc/robot/DataLogging.java | 19 +----- src/main/java/frc/robot/RobotPreferences.java | 63 +++++++++++++++++++ src/test/java/frc/robot/ArmSubsystemTest.java | 23 ++----- src/test/java/frc/robot/RobotCommandTest.java | 5 +- 4 files changed, 74 insertions(+), 36 deletions(-) create mode 100644 src/main/java/frc/robot/RobotPreferences.java diff --git a/src/main/java/frc/robot/DataLogging.java b/src/main/java/frc/robot/DataLogging.java index 8e47494..971b8ba 100644 --- a/src/main/java/frc/robot/DataLogging.java +++ b/src/main/java/frc/robot/DataLogging.java @@ -2,9 +2,6 @@ // Forked from FRC Team 2832 "The Livonia Warriors" -import edu.wpi.first.networktables.NetworkTable; -import edu.wpi.first.networktables.NetworkTableInstance; -import edu.wpi.first.networktables.NetworkTableType; import edu.wpi.first.util.datalog.DataLog; import edu.wpi.first.util.datalog.DoubleLogEntry; import edu.wpi.first.util.datalog.StringLogEntry; @@ -26,7 +23,6 @@ import frc.robot.subsystems.ArmSubsystem; import frc.robot.subsystems.DriveSubsystem; import java.util.Map; -import java.util.Set; /** The DataLogging class contains all the logic for using telemetry. */ public class DataLogging { @@ -48,21 +44,8 @@ private DataLogging() { final DataLog log = DataLogManager.getLog(); // Record the starting values of preferences - NetworkTable prefTable = NetworkTableInstance.getDefault().getTable("Preferences"); - Set prefKeys = prefTable.getKeys(); DataLogManager.log("Starting Preference Values:"); - - for (String keyName : prefKeys) { - NetworkTableType prefType = prefTable.getEntry(keyName).getType(); - - if (prefType == NetworkTableType.kDouble) { - DataLogManager.log( - "Preferences/" + keyName + ": " + prefTable.getEntry(keyName).getDouble(-1)); - } else if (prefType == NetworkTableType.kBoolean) { - DataLogManager.log( - "Preferences/" + keyName + ": " + prefTable.getEntry(keyName).getBoolean(false)); - } - } + RobotPreferences.logPreferences(); // Record both DS control and joystick data. To DriverStation.startDataLog(DataLogManager.getLog(), Constants.LOG_JOYSTICK_DATA); diff --git a/src/main/java/frc/robot/RobotPreferences.java b/src/main/java/frc/robot/RobotPreferences.java new file mode 100644 index 0000000..d8e9c13 --- /dev/null +++ b/src/main/java/frc/robot/RobotPreferences.java @@ -0,0 +1,63 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot; + +import edu.wpi.first.networktables.NetworkTable; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.networktables.NetworkTableType; +import edu.wpi.first.wpilibj.DataLogManager; +import edu.wpi.first.wpilibj.Preferences; +import java.util.Set; + +/** Utility class for managing preferences. */ +public class RobotPreferences { + + private RobotPreferences() { + throw new IllegalStateException("RobotPreferences Utility class"); + } + + /** Reset the Preferences table to default values. */ + public static void resetPreferences() { + + // Reset the arm subsystem preferences + + // Preferences for PID controller + Preferences.setDouble(Constants.ArmConstants.ARM_KP_KEY, Constants.ArmConstants.DEFAULT_ARM_KP); + + // Preferences for Trapezoid Profile + Preferences.setDouble( + Constants.ArmConstants.ARM_VELOCITY_MAX_KEY, + Constants.ArmConstants.DEFAULT_MAX_VELOCITY_RAD_PER_SEC); + Preferences.setDouble( + Constants.ArmConstants.ARM_ACCELERATION_MAX_KEY, + Constants.ArmConstants.DEFAULT_MAX_ACCELERATION_RAD_PER_SEC); + + // Preferences for Feedforward + Preferences.setDouble( + Constants.ArmConstants.ARM_KS_KEY, Constants.ArmConstants.DEFAULT_KS_VOLTS); + Preferences.setDouble( + Constants.ArmConstants.ARM_KG_KEY, Constants.ArmConstants.DEFAULT_KG_VOLTS); + Preferences.setDouble( + Constants.ArmConstants.ARM_KV_KEY, Constants.ArmConstants.DEFAULT_KV_VOLTS_PER_SEC_PER_RAD); + } + + /** Log the values of all entries in the Preferences table. */ + public static void logPreferences() { + NetworkTable prefTable = NetworkTableInstance.getDefault().getTable("Preferences"); + Set prefKeys = prefTable.getKeys(); + + for (String keyName : prefKeys) { + NetworkTableType prefType = prefTable.getEntry(keyName).getType(); + + if (prefType == NetworkTableType.kDouble) { + DataLogManager.log( + "Preferences/" + keyName + ": " + prefTable.getEntry(keyName).getDouble(-1)); + } else if (prefType == NetworkTableType.kBoolean) { + DataLogManager.log( + "Preferences/" + keyName + ": " + prefTable.getEntry(keyName).getBoolean(false)); + } + } + } +} diff --git a/src/test/java/frc/robot/ArmSubsystemTest.java b/src/test/java/frc/robot/ArmSubsystemTest.java index 438aafd..a2555ce 100644 --- a/src/test/java/frc/robot/ArmSubsystemTest.java +++ b/src/test/java/frc/robot/ArmSubsystemTest.java @@ -16,7 +16,6 @@ import com.revrobotics.RelativeEncoder; import edu.wpi.first.math.util.Units; import edu.wpi.first.networktables.NetworkTable; -import edu.wpi.first.networktables.NetworkTableEntry; import edu.wpi.first.networktables.NetworkTableInstance; import edu.wpi.first.networktables.NetworkTableType; import edu.wpi.first.wpilibj2.command.Command; @@ -47,6 +46,9 @@ public void initEach() { mockMotor = mock(CANSparkMax.class); mockEncoder = mock(RelativeEncoder.class); + // Reset preferences to default values so test results are consistent + RobotPreferences.resetPreferences(); + // Create subsystem object using mock hardware armHardware = new ArmSubsystem.Hardware(mockMotor, mockEncoder); arm = new ArmSubsystem(armHardware); @@ -93,7 +95,6 @@ void testMoveCommand() { assertThat(telemetryBooleanMap.get("Arm Enabled")).isTrue(); // When disabled mMotor should be commanded to zero - verify(mockMotor, times(1)).setVoltage(0.0); arm.disable(); arm.periodic(); readTelemetry(); @@ -123,11 +124,12 @@ void testSensors() { verify(mockMotor).setVoltage(0.0); verify(mockMotor, times(1)).setVoltage(AdditionalMatchers.gt(0.0)); + // An example of looking for a specific value. // This value was cheated by running working code as an example. May be better to just // check direction of command for complex controllers and leave controller response tests // to simulation checking desired response over time. - final double expectedCommand = 0.33199; - verify(mockMotor, times(1)).setVoltage(AdditionalMatchers.eq(expectedCommand, DELTA)); + // final double expectedCommand = 0.34092; + // verify(mockMotor, times(1)).setVoltage(AdditionalMatchers.eq(expectedCommand, DELTA)); // Alternative method: capture values and then use them in a test criteria // ArgumentCaptor argument = ArgumentCaptor.forClass(Double.class); @@ -141,7 +143,6 @@ void testSensors() { // Check that telemetry was sent to dashboard arm.periodic(); readTelemetry(); - assertEquals(expectedCommand, telemetryDoubleMap.get("Arm Voltage"), DELTA); assertEquals(fakeCurrent, telemetryDoubleMap.get("Arm Current"), DELTA); assertEquals( Units.radiansToDegrees(ArmConstants.ARM_OFFSET_RADS + fakePosition), @@ -210,18 +211,6 @@ void testShiftDownCommand() { DELTA); } - @Test - @DisplayName("Test Preferences Table") - void testPrefs() { - NetworkTable prefTable = NetworkTableInstance.getDefault().getTable("Preferences"); - - // Currently just reading and setting values, but could set value and check effects - String keyName = "ArmKP"; - NetworkTableEntry entry = prefTable.getEntry(keyName); - entry.setDouble(10.1); - assertEquals(10.1, entry.getDouble(-1), DELTA); - } - // ---------- Utility Functions -------------------------------------- /* Read in telemetry values from the network table and store in maps */ diff --git a/src/test/java/frc/robot/RobotCommandTest.java b/src/test/java/frc/robot/RobotCommandTest.java index db3775e..1a397db 100644 --- a/src/test/java/frc/robot/RobotCommandTest.java +++ b/src/test/java/frc/robot/RobotCommandTest.java @@ -44,6 +44,9 @@ void startThread() { SimHooks.stepTiming(0.0); // Wait for Notifiers container = robot.getRobotContainer(); arm = container.getArmSubsystem(); + + // Reset preferences to default values so test results are consistent + RobotPreferences.resetPreferences(); } @AfterEach @@ -90,7 +93,7 @@ void armStartupTest() { xboxControllerSim.notifyNewData(); // advance to let arm reach the new goal - SimHooks.stepTiming(2.0); + SimHooks.stepTiming(3.0); assertEquals(Constants.ArmConstants.ARM_HIGH_POSITION, arm.getMeasurement(), POS_DELTA); assertTrue(arm.atGoalPosition()); From ce6cd36119902761a0ec7f9474abf4b7af0e859e Mon Sep 17 00:00:00 2001 From: Jay Tarbotton Date: Fri, 12 Jan 2024 16:09:45 -0500 Subject: [PATCH 2/4] Unit tests may fail due to modified preferences Fixes #96 --- src/main/java/frc/robot/RobotPreferences.java | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/java/frc/robot/RobotPreferences.java b/src/main/java/frc/robot/RobotPreferences.java index d8e9c13..636a9ea 100644 --- a/src/main/java/frc/robot/RobotPreferences.java +++ b/src/main/java/frc/robot/RobotPreferences.java @@ -12,6 +12,8 @@ import java.util.Set; /** Utility class for managing preferences. */ +// TODO - Add functions to manage preferences more automatically with lists of keys and +// default values defined in the constants file. public class RobotPreferences { private RobotPreferences() { From f3e6eb3c7300745e6d6b31bb53e627c714a21bde Mon Sep 17 00:00:00 2001 From: Jay Tarbotton Date: Mon, 15 Jan 2024 12:55:11 -0500 Subject: [PATCH 3/4] Improved explanation of unused example code --- src/main/java/frc/robot/RobotPreferences.java | 2 +- src/test/java/frc/robot/ArmSubsystemTest.java | 10 ++++++---- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/src/main/java/frc/robot/RobotPreferences.java b/src/main/java/frc/robot/RobotPreferences.java index 636a9ea..16f9940 100644 --- a/src/main/java/frc/robot/RobotPreferences.java +++ b/src/main/java/frc/robot/RobotPreferences.java @@ -12,7 +12,7 @@ import java.util.Set; /** Utility class for managing preferences. */ -// TODO - Add functions to manage preferences more automatically with lists of keys and +// TODO - Add functions to manage preferences more automatically with lists of keys and // default values defined in the constants file. public class RobotPreferences { diff --git a/src/test/java/frc/robot/ArmSubsystemTest.java b/src/test/java/frc/robot/ArmSubsystemTest.java index a2555ce..e7ea17b 100644 --- a/src/test/java/frc/robot/ArmSubsystemTest.java +++ b/src/test/java/frc/robot/ArmSubsystemTest.java @@ -124,10 +124,12 @@ void testSensors() { verify(mockMotor).setVoltage(0.0); verify(mockMotor, times(1)).setVoltage(AdditionalMatchers.gt(0.0)); - // An example of looking for a specific value. - // This value was cheated by running working code as an example. May be better to just - // check direction of command for complex controllers and leave controller response tests - // to simulation checking desired response over time. + // This unused code is provided as an example of looking for a specific value. + // This value was cheated by running working code as an example since calculating actual + // controller expected values is difficult. Insteat the test above just checks direction + // of the command, and controller response tests are done in simulation by checking desired + // response over time. + // // final double expectedCommand = 0.34092; // verify(mockMotor, times(1)).setVoltage(AdditionalMatchers.eq(expectedCommand, DELTA)); From cfe8ebbbba5a9a03ed75d24d567a1d5301753784 Mon Sep 17 00:00:00 2001 From: Jay Tarbotton Date: Fri, 19 Jan 2024 08:15:17 -0500 Subject: [PATCH 4/4] Unit tests may fail due to modified preferences Fixes #96 --- src/test/java/frc/robot/RobotCommandTest.java | 1 - 1 file changed, 1 deletion(-) diff --git a/src/test/java/frc/robot/RobotCommandTest.java b/src/test/java/frc/robot/RobotCommandTest.java index bef9721..7be47de 100644 --- a/src/test/java/frc/robot/RobotCommandTest.java +++ b/src/test/java/frc/robot/RobotCommandTest.java @@ -14,7 +14,6 @@ import edu.wpi.first.wpilibj.simulation.SimHooks; import edu.wpi.first.wpilibj.simulation.XboxControllerSim; import frc.robot.subsystems.ArmSubsystem; -import java.util.Set; import org.junit.jupiter.api.AfterEach; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Disabled;