Adding some basic logging

This commit is contained in:
2025-03-08 22:21:56 -05:00
parent 99fd6bea13
commit e636f02e47
3 changed files with 41 additions and 0 deletions

View File

@@ -1,5 +1,7 @@
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.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
@@ -94,6 +96,7 @@ public class DifferentialDrivetrain extends SubsystemBase implements IDrivetrain
}
@Override
@Logged(name = "DD Pose", importance = Importance.INFO)
public Pose2d getPose() {
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() {
return gyro.getAngle() * (DifferentialDriveConstants.kInvertGyro ? -1 : 1);
}
@Logged(name = "DD Left Encoder Meters", importance = Importance.DEBUG)
public double getLeftEncoderMeters() {
return leftEncoder.getDistance() * (DifferentialDriveConstants.kInvertEncoders ? -1 : 1);
}
@Logged(name = "DD Right Encoder Meters", importance = Importance.DEBUG)
public double getRightEncoderMeters() {
return rightEncoder.getDistance() * (DifferentialDriveConstants.kInvertEncoders ? -1 : 1);
}
@Logged(name = "DD Left Encoder Meters Per Second", importance = Importance.DEBUG)
public double getLeftEncoderMetersPerSecond() {
return leftEncoder.getRate() * (DifferentialDriveConstants.kInvertEncoders ? -1 : 1);
}
@Logged(name = "DD Right Encoder Meters Per Second", importance = Importance.DEBUG)
public double getRightEncoderMetersPerSecond() {
return rightEncoder.getRate() * (DifferentialDriveConstants.kInvertEncoders ? -1 : 1);
}