Skip to content

Commit

Permalink
added switching between file-only and nt + file-only logging dependin…
Browse files Browse the repository at this point in the history
…g on fms
  • Loading branch information
PGgit08 committed Dec 21, 2024
1 parent 4455977 commit 55e9d39
Show file tree
Hide file tree
Showing 7 changed files with 93 additions and 19 deletions.
8 changes: 4 additions & 4 deletions simgui-ds.json
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
{
"FMS": {
"Keyboard 0 Settings": {
"window": {
"visible": false
"visible": true
}
},
"Keyboard 0 Settings": {
"System Joysticks": {
"window": {
"visible": true
"visible": false
}
},
"keyboardJoysticks": [
Expand Down
42 changes: 36 additions & 6 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,10 @@
import edu.wpi.first.epilogue.Epilogue;
import edu.wpi.first.epilogue.Logged;
import edu.wpi.first.epilogue.Logged.Strategy;
import edu.wpi.first.epilogue.logging.DataLogger;
import edu.wpi.first.epilogue.logging.FileLogger;
import edu.wpi.first.epilogue.logging.NTDataLogger;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.DataLogManager;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.TimedRobot;
Expand Down Expand Up @@ -45,20 +49,33 @@ public class Robot extends TimedRobot {

private Command _autonomousCommand = Autos.none();

private final NetworkTableInstance _ntInst;

private boolean _fileOnlySet = false;

/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
public Robot() {
this(NetworkTableInstance.getDefault());
}

/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
public Robot(NetworkTableInstance ntInst) {
_ntInst = ntInst;

// set up loggers
DogLog.setOptions(new DogLogOptions().withCaptureDs(true));
Epilogue.bind(this);
SignalLogger.start();

setFileOnly(false); // file-only once connected to fms

Epilogue.bind(this);
SignalLogger.start();

DriverStation.silenceJoystickConnectionWarning(isSimulation());

FaultLogger.setup();
Expand All @@ -80,10 +97,16 @@ public Robot() {
private void setFileOnly(boolean fileOnly) {
DogLog.setOptions(DogLog.getOptions().withNtPublish(!fileOnly));

Epilogue.configure(
config -> {
// TODO
});
if (fileOnly) {
Epilogue.getConfig().dataLogger = new FileLogger(DataLogManager.getLog());
return;
}

// if doing both file and nt logging, use the datalogger multilogger setup
Epilogue.getConfig().dataLogger =
DataLogger.multi(
new NTDataLogger(_ntInst), // TODO: watch out unit tests
new FileLogger(DataLogManager.getLog()));
}

private void configureBindings() {
Expand Down Expand Up @@ -150,4 +173,11 @@ public void testInit() {
// Cancels all running commands at the start of test mode.
CommandScheduler.getInstance().cancelAll();
}

@Override
public void close() {
super.close();

_swerve.close();
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ public class Swerve extends SwerveDrivetrain implements Subsystem, SelfChecked {
private FaultsTable _faultsTable =
new FaultsTable(
NetworkTableInstance.getDefault().getTable("Self Check"),
getName() + " Faults"); // TODO: watch out if unit testing
getName() + " Faults"); // TODO: watch out unit tests

private boolean _hasError = false;

Expand Down
3 changes: 1 addition & 2 deletions src/test/java/frc/lib/AdvancedSubsystemTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,7 @@

import static edu.wpi.first.wpilibj2.command.Commands.*;
import static frc.lib.UnitTestingUtil.*;
import static frc.lib.UnitTestingUtil.run;
import static org.junit.jupiter.api.Assertions.assertEquals;
import static org.junit.jupiter.api.Assertions.*;

import edu.wpi.first.wpilibj2.command.Command;
import frc.lib.FaultsTable.Fault;
Expand Down
5 changes: 2 additions & 3 deletions src/test/java/frc/lib/CTREUtilTest.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,7 @@
package frc.lib;

import static frc.lib.UnitTestingUtil.reset;
import static frc.lib.UnitTestingUtil.setupTests;
import static org.junit.jupiter.api.Assertions.assertEquals;
import static frc.lib.UnitTestingUtil.*;
import static org.junit.jupiter.api.Assertions.*;

import com.ctre.phoenix6.StatusCode;
import com.ctre.phoenix6.hardware.CANcoder;
Expand Down
48 changes: 48 additions & 0 deletions src/test/java/frc/robot/RobotTest.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
package frc.robot;

import static frc.lib.UnitTestingUtil.*;
import static org.junit.jupiter.api.Assertions.*;

import dev.doglog.DogLog;
import edu.wpi.first.epilogue.Epilogue;
import edu.wpi.first.epilogue.logging.FileLogger;
import edu.wpi.first.epilogue.logging.MultiLogger;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.simulation.DriverStationSim;
import org.junit.jupiter.api.AfterEach;
import org.junit.jupiter.api.BeforeEach;
import org.junit.jupiter.api.Test;

public class RobotTest {
private Robot _robot;

@BeforeEach
public void setup() {
setupTests();

_robot = new Robot(getNtInst());
}

@AfterEach
public void close() throws Exception {
reset(_robot);
}

@Test
public void fmsFileOnly() {
// at the start should be both nt and file logging
assert Epilogue.getConfig().dataLogger instanceof MultiLogger; // multilogger setup
assert DogLog.getOptions().ntPublish();

DriverStationSim.setFmsAttached(true);
DriverStationSim.notifyNewData();

assert DriverStation.isFMSAttached();

_robot.robotPeriodic();

// once the fms connects, it should be file only
assert Epilogue.getConfig().dataLogger instanceof FileLogger;
assertFalse(DogLog.getOptions().ntPublish());
}
}
4 changes: 1 addition & 3 deletions src/test/java/frc/robot/VisionPoseEstimatorTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.util.Units;
import frc.lib.UnitTestingUtil;
import frc.robot.utils.VisionPoseEstimator;
import frc.robot.utils.VisionPoseEstimator.VisionPoseEstimate;
import frc.robot.utils.VisionPoseEstimator.VisionPoseEstimatorConstants;
Expand Down Expand Up @@ -75,8 +74,7 @@ public void setup() {
3,
7);

_testCam =
VisionPoseEstimator.buildFromConstants(testCam, UnitTestingUtil.getNtInst(), _fieldLayout);
_testCam = VisionPoseEstimator.buildFromConstants(testCam, getNtInst(), _fieldLayout);

_visionSystemSim = new VisionSystemSim("");
_visionSystemSim.addCamera(_testCam.getCameraSim(), _testCam.robotToCam);
Expand Down

0 comments on commit 55e9d39

Please sign in to comment.