drivetrain + autoBuilder/chooser + tournerAZero/180
This commit is contained in:
@@ -8,9 +8,12 @@ import static edu.wpi.first.units.Units.*;
|
||||
|
||||
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
import com.pathplanner.lib.auto.AutoBuilder;
|
||||
import com.pathplanner.lib.auto.NamedCommands;
|
||||
|
||||
import edu.wpi.first.cameraserver.CameraServer;
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||
@@ -41,6 +44,7 @@ import frc.robot.subsystems.LimeLight3;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
|
||||
public class RobotContainer {
|
||||
private final SendableChooser<Command> autoChooser;
|
||||
Balayeuse balayeuse = new Balayeuse();
|
||||
Grimpeur grimpeur = new Grimpeur();
|
||||
Lanceur lanceur = new Lanceur();
|
||||
@@ -60,12 +64,11 @@ public class RobotContainer {
|
||||
|
||||
private final Telemetry logger = new Telemetry(MaxSpeed);
|
||||
|
||||
private final CommandXboxController joystick = new CommandXboxController(0);
|
||||
|
||||
public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain();
|
||||
|
||||
|
||||
public RobotContainer() {
|
||||
autoChooser = AutoBuilder.buildAutoChooser();
|
||||
CameraServer.startAutomaticCapture();
|
||||
configureBindings();
|
||||
NamedCommands.registerCommand("GrimperMur", new GrimperMur());
|
||||
@@ -76,13 +79,20 @@ public class RobotContainer {
|
||||
NamedCommands.registerCommand("Limelighter", new Limelighter());
|
||||
NamedCommands.registerCommand("DescendreBalayeuse", new DescendreBalyeuse(balayeuse));
|
||||
NamedCommands.registerCommand("Aspirer", new AspirerAuto(balayeuse));
|
||||
NamedCommands.registerCommand("TournerAZero", new TournerAZero());
|
||||
NamedCommands.registerCommand("TournerA180", new TournerA180());
|
||||
NamedCommands.registerCommand("TournerAZero", new TournerAZero(drivetrain));
|
||||
NamedCommands.registerCommand("TournerA180", new TournerA180(drivetrain));
|
||||
NamedCommands.registerCommand("MonterGrimpeur", new MonterGrimpeur(grimpeur));
|
||||
NamedCommands.registerCommand("DescendreGrimpeur", new DescendreGrimpeur(grimpeur));
|
||||
}
|
||||
|
||||
private void configureBindings() {
|
||||
drivetrain.setDefaultCommand(
|
||||
drivetrain.applyRequest(() ->
|
||||
drive.withVelocityY(MathUtil.applyDeadband(-manette.getLeftX()*Math.abs(-manette.getLeftX())*MaxSpeed, 0.05))
|
||||
.withVelocityX(MathUtil.applyDeadband(-manette.getLeftY()*Math.abs(-manette.getLeftY())*MaxSpeed, 0.05))
|
||||
.withRotationalRate(MathUtil.applyDeadband(-manette.getRightX()*Math.abs(-manette.getRightX())*MaxAngularRate, 0.05))
|
||||
)
|
||||
);
|
||||
manette.a().whileTrue(new Lancer(lanceur,limeLight3G,balayeuse,led));
|
||||
manette.y().whileTrue(new ModeOposer(lanceur, balayeuse));
|
||||
manette.x().whileTrue(new LancerBaseVitesse(lanceur, limeLight3, balayeuse, led));
|
||||
@@ -94,6 +104,6 @@ public class RobotContainer {
|
||||
}
|
||||
|
||||
public Command getAutonomousCommand() {
|
||||
return Commands.print("No autonomous command configured");
|
||||
return autoChooser.getSelected();
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user