diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index a8f7cabe..386c043a 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -34,9 +34,6 @@ public Robot() { PowerDistribution distribution = new PowerDistribution(1, ModuleType.kRev); // Enables power distribution logging } else { setUseTiming(false); // Run as fast as possible - String logPath = LogFileUtil.findReplayLog(); // Pull the replay log from AdvantageScope (or prompt the user) - Logger.setReplaySource(new WPILOGReader(logPath)); // Read replay log - Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"))); // Save outputs to a new log } Logger.start(); // Start logging! No more data receivers, replay sources, or metadata values may be added. diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 1009471b..8617a793 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -6,15 +6,14 @@ import static edu.wpi.first.units.Units.*; -import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType; +import org.littletonrobotics.junction.networktables.LoggedDashboardChooser; + + import com.pathplanner.lib.auto.AutoBuilder; import com.ctre.phoenix6.swerve.SwerveRequest; - import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.kinematics.ChassisSpeeds; -import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.lib.controller.LogitechController; @@ -39,7 +38,7 @@ public class RobotContainer { public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain(); - private SendableChooser autoChooser = new SendableChooser(); + private final LoggedDashboardChooser autoChooser; // Use open-loop control for drive motors private final SwerveRequest.SwerveDriveBrake brake = new SwerveRequest.SwerveDriveBrake(); @@ -49,8 +48,8 @@ public RobotContainer() { configureBindings(); drivetrain.setUpPathPlanner(); - autoChooser = AutoBuilder.buildAutoChooser(); - SmartDashboard.putData("Auto Chooser", autoChooser); + autoChooser = new LoggedDashboardChooser<>("Auto Routine", AutoBuilder.buildAutoChooser()); + } private void configureBindings() { @@ -61,7 +60,7 @@ private void configureBindings() { drivetrain.applyRequest( () -> { ChassisSpeeds driverDesiredSpeeds = new ChassisSpeeds( - sps(deadband(leftDriveController.getYAxis().get(), .1)) * GlobalConstants.MAX_TRANSLATIONAL_SPEED, + sps(deadband(leftDriveController.getYAxis().get(), 0.1)) * GlobalConstants.MAX_TRANSLATIONAL_SPEED, -sps(deadband(leftDriveController.getXAxis().get(),0.1)) * GlobalConstants.MAX_TRANSLATIONAL_SPEED, -sps(deadband(rightDriveController.getXAxis().get(),0.1)) * GlobalConstants.MAX_ROTATIONAL_SPEED ); @@ -108,7 +107,7 @@ private double sps(double value) { public Command getAutonomousCommand() { - return autoChooser.getSelected(); + return autoChooser.get(); } }