Adding some basic logging
This commit is contained in:
parent
99fd6bea13
commit
e636f02e47
@ -4,16 +4,42 @@
|
|||||||
|
|
||||||
package frc.robot;
|
package frc.robot;
|
||||||
|
|
||||||
|
import edu.wpi.first.epilogue.Epilogue;
|
||||||
|
import edu.wpi.first.epilogue.Logged;
|
||||||
|
import edu.wpi.first.epilogue.logging.FileBackend;
|
||||||
|
import edu.wpi.first.epilogue.logging.errors.ErrorHandler;
|
||||||
|
import edu.wpi.first.wpilibj.DataLogManager;
|
||||||
import edu.wpi.first.wpilibj.TimedRobot;
|
import edu.wpi.first.wpilibj.TimedRobot;
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
||||||
|
import frc.robot.constants.LoggingConstants;
|
||||||
|
|
||||||
|
@Logged
|
||||||
public class Robot extends TimedRobot {
|
public class Robot extends TimedRobot {
|
||||||
private Command m_autonomousCommand;
|
private Command m_autonomousCommand;
|
||||||
|
|
||||||
private final RobotContainer m_robotContainer;
|
private final RobotContainer m_robotContainer;
|
||||||
|
|
||||||
public Robot() {
|
public Robot() {
|
||||||
|
DataLogManager.start();
|
||||||
|
Epilogue.configure(config -> {
|
||||||
|
// Log only to disk, instead of the default NetworkTables logging
|
||||||
|
// Note that this means data cannot be analyzed in realtime by a dashboard
|
||||||
|
config.backend = new FileBackend(DataLogManager.getLog());
|
||||||
|
|
||||||
|
if (isSimulation()) {
|
||||||
|
// If running in simulation, then we'd want to re-throw any errors that
|
||||||
|
// occur so we can debug and fix them!
|
||||||
|
config.errorHandler = ErrorHandler.crashOnError();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Only log critical information instead of the default DEBUG level.
|
||||||
|
// This can be helpful in a pinch to reduce network bandwidth or log file size
|
||||||
|
// while still logging important information.
|
||||||
|
config.minimumImportance = LoggingConstants.kImportance;
|
||||||
|
});
|
||||||
|
Epilogue.bind(this);
|
||||||
|
|
||||||
m_robotContainer = new RobotContainer();
|
m_robotContainer = new RobotContainer();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
7
src/main/java/frc/robot/constants/LoggingConstants.java
Normal file
7
src/main/java/frc/robot/constants/LoggingConstants.java
Normal file
@ -0,0 +1,7 @@
|
|||||||
|
package frc.robot.constants;
|
||||||
|
|
||||||
|
import edu.wpi.first.epilogue.Logged.Importance;
|
||||||
|
|
||||||
|
public class LoggingConstants {
|
||||||
|
public static final Importance kImportance = Importance.DEBUG;
|
||||||
|
}
|
@ -1,5 +1,7 @@
|
|||||||
package frc.robot.subsystems;
|
package frc.robot.subsystems;
|
||||||
|
|
||||||
|
import edu.wpi.first.epilogue.Logged;
|
||||||
|
import edu.wpi.first.epilogue.Logged.Importance;
|
||||||
import edu.wpi.first.math.estimator.DifferentialDrivePoseEstimator;
|
import edu.wpi.first.math.estimator.DifferentialDrivePoseEstimator;
|
||||||
import edu.wpi.first.math.geometry.Pose2d;
|
import edu.wpi.first.math.geometry.Pose2d;
|
||||||
import edu.wpi.first.math.geometry.Rotation2d;
|
import edu.wpi.first.math.geometry.Rotation2d;
|
||||||
@ -94,6 +96,7 @@ public class DifferentialDrivetrain extends SubsystemBase implements IDrivetrain
|
|||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
|
@Logged(name = "DD Pose", importance = Importance.INFO)
|
||||||
public Pose2d getPose() {
|
public Pose2d getPose() {
|
||||||
return poseEstimator.getEstimatedPosition();
|
return poseEstimator.getEstimatedPosition();
|
||||||
}
|
}
|
||||||
@ -185,22 +188,27 @@ public class DifferentialDrivetrain extends SubsystemBase implements IDrivetrain
|
|||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@Logged(name = "DD Gyro Angle", importance = Importance.DEBUG)
|
||||||
public double getGyroAngle() {
|
public double getGyroAngle() {
|
||||||
return gyro.getAngle() * (DifferentialDriveConstants.kInvertGyro ? -1 : 1);
|
return gyro.getAngle() * (DifferentialDriveConstants.kInvertGyro ? -1 : 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@Logged(name = "DD Left Encoder Meters", importance = Importance.DEBUG)
|
||||||
public double getLeftEncoderMeters() {
|
public double getLeftEncoderMeters() {
|
||||||
return leftEncoder.getDistance() * (DifferentialDriveConstants.kInvertEncoders ? -1 : 1);
|
return leftEncoder.getDistance() * (DifferentialDriveConstants.kInvertEncoders ? -1 : 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@Logged(name = "DD Right Encoder Meters", importance = Importance.DEBUG)
|
||||||
public double getRightEncoderMeters() {
|
public double getRightEncoderMeters() {
|
||||||
return rightEncoder.getDistance() * (DifferentialDriveConstants.kInvertEncoders ? -1 : 1);
|
return rightEncoder.getDistance() * (DifferentialDriveConstants.kInvertEncoders ? -1 : 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@Logged(name = "DD Left Encoder Meters Per Second", importance = Importance.DEBUG)
|
||||||
public double getLeftEncoderMetersPerSecond() {
|
public double getLeftEncoderMetersPerSecond() {
|
||||||
return leftEncoder.getRate() * (DifferentialDriveConstants.kInvertEncoders ? -1 : 1);
|
return leftEncoder.getRate() * (DifferentialDriveConstants.kInvertEncoders ? -1 : 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@Logged(name = "DD Right Encoder Meters Per Second", importance = Importance.DEBUG)
|
||||||
public double getRightEncoderMetersPerSecond() {
|
public double getRightEncoderMetersPerSecond() {
|
||||||
return rightEncoder.getRate() * (DifferentialDriveConstants.kInvertEncoders ? -1 : 1);
|
return rightEncoder.getRate() * (DifferentialDriveConstants.kInvertEncoders ? -1 : 1);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user