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

40 baseline auto #58

Merged
merged 15 commits into from
Jan 29, 2024
8 changes: 5 additions & 3 deletions src/main/java/org/jmhsrobotics/frc2024/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
import org.jmhsrobotics.frc2024.subsystems.LED.commands.RainbowLEDCommand;
import org.jmhsrobotics.frc2024.subsystems.drive.DriveSubsystem;
import org.jmhsrobotics.frc2024.subsystems.drive.commands.DriveCommand;
import org.jmhsrobotics.frc2024.subsystems.drive.commands.auto.DriveTimeCommand;
import org.jmhsrobotics.frc2024.subsystems.drive.commands.LockAprilTag;
import org.jmhsrobotics.frc2024.subsystems.intake.IntakeSubsystem;
import org.jmhsrobotics.frc2024.subsystems.vision.VisionSubsystem;
Expand All @@ -26,7 +27,6 @@
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import monologue.Logged;

Expand All @@ -47,13 +47,14 @@ public RobotContainer() {

this.driveSubsystem.setDefaultCommand(new DriveCommand(this.driveSubsystem, this.control));
this.ledSubsystem.setDefaultCommand(new RainbowLEDCommand(this.ledSubsystem));
SmartDashboard.putData("Schedular", CommandScheduler.getInstance());
SmartDashboard.putData("Scheduler", CommandScheduler.getInstance());
SmartDashboard.putData("LockAprilTagCommand", new LockAprilTag(4, this.driveSubsystem, this.visionSubsystem));
configureBindings();

// Named commands must be added before building the chooser.
configurePathPlanner();
autoChooser = AutoBuilder.buildAutoChooser();
autoChooser.setDefaultOption("BaseLineAuto", new DriveTimeCommand(1.535, 0.3, driveSubsystem));
SmartDashboard.putData("Auto Chooser", autoChooser);
}

Expand All @@ -80,7 +81,8 @@ private void configureBindings() {
public Command getAutonomousCommand() {
Command picked = autoChooser.getSelected();
if (picked == null) {
return Commands.print("No autonomous command configured");
DriverStation.reportError("WARNING: No auto command detected, defaulting to baseline auto.", false);
return new DriveTimeCommand(1.535, 0.3, driveSubsystem);
} else {
return picked;
}
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
package org.jmhsrobotics.frc2024.subsystems.drive.commands.auto;

import org.jmhsrobotics.frc2024.subsystems.drive.DriveSubsystem;

import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;

public class DriveTimeCommand extends Command {

private DriveSubsystem drive;

private double driveSeconds;
private double drivePower;

private Timer timer = new Timer();

public DriveTimeCommand(double seconds, double power, DriveSubsystem subsystem) {

driveSeconds = seconds;
drivePower = power;

drive = subsystem;

}

public void initialize() {

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

}

@Override
public void execute() {

this.drive.drive(drivePower, 0, 0, false, false);

}

@Override
public boolean isFinished() {

return timer.get() >= driveSeconds;

}

public void end() {
this.drive.drive(0, 0, 0, false, false);

}

}
Loading