diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index b03bd9d..6aeb04d 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -4,6 +4,7 @@ package frc.robot; +import edu.wpi.first.epilogue.Logged; import edu.wpi.first.net.PortForwarder; import edu.wpi.first.wpilibj.DataLogManager; import edu.wpi.first.wpilibj.DriverStation; @@ -11,6 +12,7 @@ import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; +import edu.wpi.first.epilogue.logging.*;; /** * The VM is configured to automatically run this class, and to call the @@ -21,6 +23,7 @@ * build.gradle file in the * project. */ +@Logged public class Robot extends TimedRobot { private Command m_autonomousCommand; @@ -28,6 +31,25 @@ public class Robot extends TimedRobot { private Timer disabledTimer; + public Robot() { + // 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.dataLogger = new FileLogger(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(); + // } + // // Change the root data path + // config.root = "Telemetry"; + // // 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. + // }); + Epilogue.bind(this); + } + /** * This function is run when the robot is first started up and should be used * for any diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 6a3cc09..226906c 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -38,6 +38,7 @@ import frc.robot.subsystems.Drivetrain; import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; +import edu.wpi.first.epilogue.Logged; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; @@ -65,6 +66,7 @@ * the robot (including * subsystems, commands, and trigger mappings) should be declared here. */ +@Logged public class RobotContainer { // The robot's subsystems and commands are defined here... private final ShuffleboardInfo shuffleboard; diff --git a/src/main/java/frc/robot/subsystems/Arm.java b/src/main/java/frc/robot/subsystems/Arm.java index b3894c2..3a8de10 100644 --- a/src/main/java/frc/robot/subsystems/Arm.java +++ b/src/main/java/frc/robot/subsystems/Arm.java @@ -23,6 +23,7 @@ import com.revrobotics.spark.SparkClosedLoopController; import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; +import edu.wpi.first.epilogue.Logged; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.ArmFeedforward; import edu.wpi.first.math.controller.ElevatorFeedforward; @@ -40,6 +41,7 @@ import frc.robot.shuffleboard.MotorTab; // import frc.robot.util.TunableNumber; +@Logged public class Arm extends SubsystemBase { // Arm /** this is the right arm motor */