Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 1 addition & 18 deletions src/main/java/frc/robot/DataLogging.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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 {
Expand All @@ -48,21 +44,8 @@ private DataLogging() {
final DataLog log = DataLogManager.getLog();

// Record the starting values of preferences
NetworkTable prefTable = NetworkTableInstance.getDefault().getTable("Preferences");
Set<String> 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);
Expand Down
65 changes: 65 additions & 0 deletions src/main/java/frc/robot/RobotPreferences.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
// 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. */
// 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() {
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<String> 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));
}
}
}
}
31 changes: 11 additions & 20 deletions src/test/java/frc/robot/ArmSubsystemTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -123,11 +124,14 @@ void testSensors() {
verify(mockMotor).setVoltage(0.0);
verify(mockMotor, times(1)).setVoltage(AdditionalMatchers.gt(0.0));

// 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));
// 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. Instead 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));

// Alternative method: capture values and then use them in a test criteria
// ArgumentCaptor<Double> argument = ArgumentCaptor.forClass(Double.class);
Expand All @@ -141,7 +145,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),
Expand Down Expand Up @@ -210,18 +213,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 */
Expand Down
14 changes: 4 additions & 10 deletions src/test/java/frc/robot/RobotCommandTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -34,10 +33,6 @@ class RobotCommandTest {

@BeforeEach
void startThread() {
Set<Thread> threadSet = Thread.getAllStackTraces().keySet();
for (Thread x : threadSet) {
System.out.println(x.getName());
}
System.out.println(" =================== Starting Robot for Unit Test =================== ");
HAL.initialize(500, 0);
SimHooks.pauseTiming();
Expand All @@ -50,6 +45,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
Expand All @@ -66,10 +64,6 @@ void stopThread() {
DriverStationSim.resetData();
DriverStationSim.notifyNewData();
System.out.println(" =================== Stopped Robot for Unit Test =================== ");
Set<Thread> threadSet = Thread.getAllStackTraces().keySet();
for (Thread x : threadSet) {
System.out.println(x.getName());
}
}

@Disabled("Needs rework")
Expand Down Expand Up @@ -102,7 +96,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());
Expand Down