Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add new logger system #27

Open
wants to merge 21 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 2 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
8 changes: 8 additions & 0 deletions simgui.json
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,14 @@
"NTProvider": {
"types": {
"/FMSInfo": "FMSInfo",
"/LiveWindow/Ungrouped/DigitalInput[10]": "Digital Input",
"/LiveWindow/Ungrouped/DigitalInput[11]": "Digital Input",
"/LiveWindow/Ungrouped/DigitalInput[12]": "Digital Input",
"/LiveWindow/Ungrouped/DigitalInput[13]": "Digital Input",
"/LiveWindow/Ungrouped/DigitalInput[6]": "Digital Input",
"/LiveWindow/Ungrouped/DigitalInput[7]": "Digital Input",
"/LiveWindow/Ungrouped/DigitalInput[8]": "Digital Input",
"/LiveWindow/Ungrouped/DigitalInput[9]": "Digital Input",
"/LiveWindow/Ungrouped/navX-Sensor[4]": "Gyro"
},
"windows": {
Expand Down
36 changes: 18 additions & 18 deletions src/main/java/frc/robot/Climber.java
Original file line number Diff line number Diff line change
Expand Up @@ -424,37 +424,37 @@ public void checkMotorState() {
}

@Override
public void setupLogging(Logger logger) {
this.timer.setupLogging(logger);
public void logHeaders(Logger logger) {
this.timer.logHeaders(logger);

// logger.addLoggable(this.leftFilter);
// logger.addLoggable(this.rightFilter);
// this.leftFilter.setupLogging(logger);
// this.rightFilter.setupLogging(logger);

logger.addAttribute("Climber/Left/Current");
logger.addAttribute("Climber/Right/Current");
logger.addHeader("Climber/Left/Current");
logger.addHeader("Climber/Right/Current");

logger.addAttribute("Climber/Speed");
logger.addAttribute("Climber/Position");
logger.addHeader("Climber/Speed");
logger.addHeader("Climber/Position");

logger.addAttribute("Climber/State/Name");
logger.addAttribute("Climber/State/Id");
logger.addAttribute("Climber/State/Ordinal");
logger.addHeader("Climber/State/Name");
logger.addHeader("Climber/State/Id");
logger.addHeader("Climber/State/Ordinal");
}

@Override
public void log(Logger logger) {
this.timer.log(logger);
logger.log("Climber/Left/Current", getLeftCurrent());
logger.log("Climber/Right/Current", getRightCurrent());
public void logData(Logger logger) {
this.timer.logData(logger);
logger.addData("Climber/Left/Current", getLeftCurrent());
logger.addData("Climber/Right/Current", getRightCurrent());

logger.log("Climber/Speed", getSpeed());
logger.log("Climber/Position", climbingMotor.getSelectedSensorPosition());
logger.addData("Climber/Speed", getSpeed());
logger.addData("Climber/Position", climbingMotor.getSelectedSensorPosition());

logger.log("Climber/State/Name", this.currentClimberState.name);
logger.log("Climber/State/Id", this.currentClimberState.id);
logger.log("Climber/State/Ordinal", this.currentClimberState.ordinal());
logger.addData("Climber/State/Name", this.currentClimberState.name);
logger.addData("Climber/State/Id", this.currentClimberState.id);
logger.addData("Climber/State/Ordinal", this.currentClimberState.ordinal());
}

public boolean getClimberSolenoidAState() {
Expand Down
18 changes: 10 additions & 8 deletions src/main/java/frc/robot/ClimberGates.java
Original file line number Diff line number Diff line change
Expand Up @@ -35,16 +35,18 @@ public boolean getC() {
}

@Override
public void setupLogging(Logger logger) {
logger.log("GateA", this.getA());
logger.log("GateB1", this.getB1());
logger.log("GateB2", this.getB2());
logger.log("GateC", this.getC());
public void logHeaders(Logger logger) {
logger.addHeader("GateA");
logger.addHeader("GateB1");
logger.addHeader("GateB2");
logger.addHeader("GateC");
}

@Override
public void log(Logger logger) {
// TODO Auto-generated method stub

public void logData(Logger logger) {
logger.addData("GateA", this.getA());
logger.addData("GateB1", this.getB1());
logger.addData("GateB2", this.getB2());
logger.addData("GateC", this.getC());
}
}
15 changes: 8 additions & 7 deletions src/main/java/frc/robot/ClimberSensors.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,15 +29,16 @@ public boolean getC() {
}

@Override
public void setupLogging(Logger logger) {
logger.log("TouchA", this.getA());
logger.log("TouchB", this.getB());
logger.log("TouchC", this.getC());
public void logHeaders(Logger logger) {
logger.addHeader("TouchA");
logger.addHeader("TouchB");
logger.addHeader("TouchC");
}

@Override
public void log(Logger logger) {
// TODO Auto-generated method stub

public void logData(Logger logger) {
logger.addData("TouchA", this.getA());
logger.addData("TouchB", this.getB());
logger.addData("TouchC", this.getC());
}
}
32 changes: 16 additions & 16 deletions src/main/java/frc/robot/DriveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

public class DriveModule implements Loggable {

private final double VELOCITY_COEFFICIENT = 600 / 2048;
// private final double VELOCITY_COEFFICIENT = 600 / 2048;
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This block of commented-out lines of code should be removed.


private TalonFX main;
private TalonFX sub;
Expand All @@ -24,7 +24,7 @@ public class DriveModule implements Loggable {
/**
* Constructor.
*
* @param moduleName Name of the attribute to log speed
* @param moduleName Name of the attribute to addData speed
* @param mainID CAN id of the main TalonFX
* @param subID CAN id of the sub TalonFX
*/
Expand Down Expand Up @@ -127,22 +127,22 @@ public double getAverageCurrent() {
}

@Override
public void setupLogging(Logger logger) {
logger.addAttribute(this.moduleName + "/MotorPower");
logger.addAttribute(this.moduleName + "/Distance");
logger.addAttribute(this.moduleName + "/EncoderRate");
logger.addAttribute(this.moduleName + "/MotorVelocity");
logger.addAttribute(this.moduleName + "/MotorCurrent");
logger.addAttribute(this.moduleName + "/MotorAverageCurrent");
public void logHeaders(Logger logger) {
logger.addHeader(this.moduleName + "/MotorPower");
logger.addHeader(this.moduleName + "/Distance");
logger.addHeader(this.moduleName + "/EncoderRate");
logger.addHeader(this.moduleName + "/MotorVelocity");
logger.addHeader(this.moduleName + "/MotorCurrent");
logger.addHeader(this.moduleName + "/MotorAverageCurrent");
}

@Override
public void log(Logger logger) {
logger.log(this.moduleName + "/MotorPower", power);
logger.log(this.moduleName + "/Distance", this.encoder.getDistance());
logger.log(this.moduleName + "/EncoderRate", this.encoder.getRate());
logger.log(this.moduleName + "/MotorVelocity", getSpeed());
logger.log(this.moduleName + "/MotorCurrent", getCurrent());
logger.log(this.moduleName + "/MotorAverageCurrent", getAverageCurrent());
public void logData(Logger logger) {
logger.addData(this.moduleName + "/MotorPower", power);
logger.addData(this.moduleName + "/Distance", this.encoder.getDistance());
logger.addData(this.moduleName + "/EncoderRate", this.encoder.getRate());
logger.addData(this.moduleName + "/MotorVelocity", getSpeed());
logger.addData(this.moduleName + "/MotorCurrent", getCurrent());
logger.addData(this.moduleName + "/MotorAverageCurrent", getAverageCurrent());
}
}
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -119,13 +119,13 @@ public void checkGears() {
}

@Override
public void setupLogging(Logger logger) {
public void logHeaders(Logger logger) {
// logger.addLoggable(left);
// logger.addLoggable(right);
}

@Override
public void log(Logger logger) {
public void logData(Logger logger) {
// TODO Auto-generated method stub
}
}
45 changes: 31 additions & 14 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,21 @@

package frc.robot;

import edu.wpi.first.wpilibj.Notifier;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.PowerDistribution.ModuleType;
import edu.wpi.first.wpilibj.Solenoid;
import edu.wpi.first.wpilibj.TimedRobot;
import frc.robot.Climber.MotorStates;
import frc.robot.logging.LoggableCompressor;
import frc.robot.logging.LoggableController;
import frc.robot.logging.LoggableGyro;
// import frc.robot.logging.LoggableGyro;
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This block of commented-out lines of code should be removed.

import frc.robot.logging.LoggablePowerDistribution;
import frc.robot.logging.LoggableTimer;
import frc.robot.logging.Logger;

import java.io.IOException;
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Extra separation in import group before 'java.io.IOException'


/**
* The VM is configured to automatically run this class, and to call the functions corresponding to
* each mode, as described in the TimedRobot documentation. If you change the name of this class or
Expand All @@ -24,6 +27,9 @@
*/
public class Robot extends TimedRobot {

Notifier notif;
Runnable runnable;

Logger logger;
LoggableTimer timer;

Expand Down Expand Up @@ -62,11 +68,28 @@ public double deadband(double in) {
@Override
public void robotInit() {
logger = new Logger();
runnable = new Runnable() {
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Make this anonymous inner class a lambda (sonar.java.source not set. Assuming 8 or greater.)

@Override
public void run() {
logger.logAll();
}
};

notif = new Notifier(runnable);

timer = new LoggableTimer();
logger.addLoggable(timer);
// gyro = new LoggableGyro();

pdp = new LoggablePowerDistribution(1, ModuleType.kRev);
logger.addLoggable(pdp);

try {
logger.createLog();
} catch (IOException e) {
// TODO Auto-generated catch block
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

TODO found

e.printStackTrace();
}

driver = new LoggableController("Driver", 0);
operator = new LoggableController("Operator", 1);
Expand Down Expand Up @@ -112,6 +135,10 @@ public void robotInit() {
logger.addLoggable(driver);
logger.addLoggable(operator);
logger.addLoggable(compressor);

logger.logAllHeaders();

notif.startPeriodic(1/30);
}

@Override
Expand All @@ -129,8 +156,6 @@ public void autonomousInit() {
@Override
public void autonomousPeriodic() {
// Robot code goes here
logger.log();
logger.writeLine();
}

@Override
Expand Down Expand Up @@ -179,21 +204,17 @@ public void teleopPeriodic() {
}
// TODO: Enable this when we're ready to test the climber
}

logger.log();
logger.writeLine();
}

@Override
public void disabledInit() {
logger.close();
timer.stop();
notif.stop();
}

@Override
public void disabledPeriodic() {
// Robot code goes here
// logger.log();
}

@Override
Expand All @@ -209,16 +230,12 @@ public void testPeriodic() {
// climber.setPower(operator.getRightY()); // Deadband
// climber.checkClimbingState();
// }

logger.log();
logger.writeLine();
}

private void resetLogging() {
logger.open();
logger.setup();

timer.reset();
timer.start();

logger.logAllHeaders();
}
}
23 changes: 9 additions & 14 deletions src/main/java/frc/robot/logging/Loggable.java
Original file line number Diff line number Diff line change
@@ -1,18 +1,13 @@
package frc.robot.logging;

/** A class for a loggable subsystem. */
public interface Loggable {
/**
* Sets up all the keys in the given Logger object.
*
* @param logger Logger class to setup keys in
*/
public abstract void setupLogging(Logger logger);
/**
* Logs all the headers provided by the Loggable object.
*/
public abstract void logHeaders(Logger logger);

/**
* Logs data in the given Logger object.
*
* @param logger Logger class to log data to
*/
public abstract void log(Logger logger);
}
/**
* Logs all the data provided by the Loggable object.
*/
public abstract void logData(Logger logger);
}
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/logging/LoggableCompressor.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,12 +13,12 @@ public LoggableCompressor(PneumaticsModuleType moduleType) {
}

@Override
public void setupLogging(Logger logger) {
logger.addAttribute("PH/pressure");
public void logHeaders(Logger logger) {
logger.addHeader("PH/pressure");
}

@Override
public void log(Logger logger) {
logger.log("PH/pressure", this.getPressure());
public void logData(Logger logger) {
logger.addData("PH/pressure", this.getPressure());
}
}
20 changes: 10 additions & 10 deletions src/main/java/frc/robot/logging/LoggableController.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,22 +14,22 @@ public LoggableController(String name, int port) {
/**
* Sets up logging for the controller.
*/
public void setupLogging(Logger logger) {
logger.addAttribute(name + "/LeftX");
logger.addAttribute(name + "/LeftY");
logger.addAttribute(name + "/RightX");
logger.addAttribute(name + "/RightY");
public void logHeaders(Logger logger) {
logger.addHeader(name + "/LeftX");
logger.addHeader(name + "/LeftY");
logger.addHeader(name + "/RightX");
logger.addHeader(name + "/RightY");
}

@Override
/**
* Logs the controller's values.
*/
public void log(Logger logger) {
logger.log(name + "/LeftX", this.getLeftX());
logger.log(name + "/LeftY", this.getLeftY());
logger.log(name + "/RightX", this.getRightX());
logger.log(name + "/RightY", this.getRightY());
public void logData(Logger logger) {
logger.addData(name + "/LeftX", this.getLeftX());
logger.addData(name + "/LeftY", this.getLeftY());
logger.addData(name + "/RightX", this.getRightX());
logger.addData(name + "/RightY", this.getRightY());
}

}
Loading