robot-2024/src/main/java/frc/robot/RobotContainer.java
samuel desharnais 723d918410
2024-02-05 18:44:03 -05:00

83 lines
2.9 KiB
Java

// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot;
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;
import com.pathplanner.lib.commands.PathPlannerAuto;
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.RunCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
// Manette
// Manettes
import edu.wpi.first.wpilibj2.command.button.CommandJoystick;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
// Commands
import frc.robot.command.Balayer;
import frc.robot.command.GrimpeurDroit;
import frc.robot.command.GrimpeurGauche;
import frc.robot.command.GuiderBas;
import frc.robot.command.GuiderHaut;
import frc.robot.command.Lancer;
import frc.robot.command.LancerNote;
import frc.robot.command.Lancerampli;
// Subsystems
import frc.robot.subsystem.Accumulateur;
import frc.robot.subsystem.Balayeuse;
import frc.robot.subsystem.Drive;
import frc.robot.subsystem.Grimpeur;
import frc.robot.subsystem.Guideur;
import frc.robot.subsystem.Lanceur;
public class RobotContainer {
private final SendableChooser<Command> autoChooser;
Drive drive = new Drive();
Accumulateur accumulateur = new Accumulateur();
Balayeuse balayeuse = new Balayeuse();
Grimpeur grimpeur = new Grimpeur();
Guideur guideur = new Guideur();
Lanceur lanceur = new Lanceur();
Balayer balayer = new Balayer(balayeuse, accumulateur);
GuiderHaut guiderHaut = new GuiderHaut(guideur);
GuiderBas guiderBas = new GuiderBas(guideur);
LancerNote lancernote = new LancerNote(lanceur, accumulateur);
Lancerampli lancerampli = new Lancerampli(lanceur);
CommandJoystick joystick = new CommandJoystick(0);
CommandXboxController manette = new CommandXboxController(1);
GrimpeurDroit grimpeurDroit = new GrimpeurDroit(grimpeur,null);
GrimpeurGauche grimpeurGauche = new GrimpeurGauche(grimpeur, null);
public RobotContainer() {
NamedCommands.registerCommand("balayer",new Balayer(balayeuse, accumulateur));
NamedCommands.registerCommand("lancer", new LancerNote(lanceur, accumulateur));
autoChooser = AutoBuilder.buildAutoChooser();
CameraServer.startAutomaticCapture();
manette.a().onTrue(guiderBas);
manette.b().onTrue(guiderHaut);
configureBindings();
drive.setDefaultCommand(new RunCommand(()->{
drive.drive(-MathUtil.applyDeadband(joystick.getY(),0.2), MathUtil.applyDeadband(-joystick.getX(),0.2), MathUtil.applyDeadband(-joystick.getZ(), 0.2));
},drive));
}
private void configureBindings() {
joystick.button(3).toggleOnTrue(balayer);
}
public Command getAutonomousCommand(){
return autoChooser.getSelected();
}
}