2025-01-27 18:21:18 -05:00
// 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 ;
2025-01-30 19:18:56 -05:00
import static edu.wpi.first.units.Units.* ;
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType ;
2025-02-17 18:33:49 -05:00
import com.ctre.phoenix6.hardware.Pigeon2 ;
2025-01-30 19:18:56 -05:00
import com.ctre.phoenix6.swerve.SwerveRequest ;
import com.pathplanner.lib.auto.AutoBuilder ;
import com.pathplanner.lib.auto.NamedCommands ;
2025-02-17 19:15:53 -05:00
import com.pathplanner.lib.commands.PathPlannerAuto ;
import com.pathplanner.lib.util.FlippingUtil ;
2025-02-10 18:33:37 -05:00
import edu.wpi.first.math.MathUtil ;
2025-02-17 18:33:49 -05:00
import edu.wpi.first.math.geometry.Pose2d ;
2025-02-17 19:15:53 -05:00
import edu.wpi.first.wpilibj.DriverStation ;
import edu.wpi.first.wpilibj.DriverStation.Alliance ;
2025-01-30 19:18:56 -05:00
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser ;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard ;
2025-01-27 18:21:18 -05:00
import edu.wpi.first.wpilibj2.command.Command ;
import edu.wpi.first.wpilibj2.command.Commands ;
2025-02-25 16:38:35 -05:00
import edu.wpi.first.wpilibj2.command.RunCommand ;
2025-02-17 18:33:49 -05:00
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup ;
2025-01-30 19:18:56 -05:00
import edu.wpi.first.wpilibj2.command.button.CommandXboxController ;
import frc.robot.TunerConstants.TunerConstants ;
2025-02-25 19:38:53 -05:00
import frc.robot.commands.Algue1Test ;
import frc.robot.commands.Algue2Test ;
2025-02-25 20:08:57 -05:00
import frc.robot.commands.AlgueExpire ;
2025-02-25 19:38:53 -05:00
import frc.robot.commands.Algue_inspire ;
2025-02-15 12:38:56 -05:00
import frc.robot.commands.AprilTag3 ;
import frc.robot.commands.AprilTag3G ;
2025-02-24 18:15:32 -05:00
import frc.robot.commands.CorailAspir ;
import frc.robot.commands.CorailTest ;
2025-02-06 17:50:24 -05:00
import frc.robot.commands.CoralAlgueInspire ;
import frc.robot.commands.CoralExpire ;
import frc.robot.commands.Depart ;
2025-02-25 16:38:35 -05:00
import frc.robot.commands.ElevateurManuel ;
2025-02-15 12:38:56 -05:00
import frc.robot.commands.Forme3 ;
2025-02-25 16:38:35 -05:00
import frc.robot.commands.L2 ;
2025-02-25 20:08:57 -05:00
import frc.robot.commands.L3 ;
import frc.robot.commands.L4 ;
2025-02-25 16:38:35 -05:00
import frc.robot.commands.PinceManuel ;
import frc.robot.commands.PinceManuel2 ;
2025-02-10 19:11:48 -05:00
import frc.robot.commands.RainBow ;
2025-02-06 17:50:24 -05:00
import frc.robot.commands.StationPince ;
2025-02-25 16:38:35 -05:00
import frc.robot.commands.reset ;
2025-02-10 19:11:48 -05:00
import frc.robot.subsystems.Bougie ;
2025-01-30 19:18:56 -05:00
import frc.robot.subsystems.CommandSwerveDrivetrain ;
2025-02-25 16:38:35 -05:00
import frc.robot.subsystems.Elevateur ;
2025-02-15 12:38:56 -05:00
import frc.robot.subsystems.Limelight3 ;
import frc.robot.subsystems.Limelight3G ;
2025-02-25 16:38:35 -05:00
import frc.robot.subsystems.Pince ;
2025-01-30 19:18:56 -05:00
2025-01-27 18:21:18 -05:00
public class RobotContainer {
2025-02-25 18:12:27 -05:00
private double MaxSpeed = TunerConstants . kSpeedAt12Volts . in ( MetersPerSecond ) ; // kSpeedAt12Volts desired top speed
private double MaxAngularRate = RotationsPerSecond . of ( 0 . 75 ) . in ( RadiansPerSecond ) ; // 3/4 of a rotation per second max angular velocity
2025-01-30 19:18:56 -05:00
2025-02-25 18:12:27 -05:00
/* Setting up bindings for necessary control of the swerve drive platform */
private final SwerveRequest . FieldCentric drive = new SwerveRequest . FieldCentric ( )
. withDeadband ( MaxSpeed * 0 . 1 ) . withRotationalDeadband ( MaxAngularRate * 0 . 1 ) // Add a 10% deadband
2025-02-25 18:15:52 -05:00
. withDriveRequestType ( DriveRequestType . OpenLoopVoltage
) ; // Use open-loop control for drive motors
2025-01-30 19:18:56 -05:00
2025-02-25 18:12:27 -05:00
private final Telemetry logger = new Telemetry ( MaxSpeed ) ;
private final CommandXboxController manette1 = new CommandXboxController ( 0 ) ;
private final CommandXboxController manette2 = new CommandXboxController ( 1 ) ;
2025-02-25 18:15:52 -05:00
private final Pigeon2 gyro = new Pigeon2 ( 13 ) ; // ID du Pigeon 2
2025-02-25 18:12:27 -05:00
public final CommandSwerveDrivetrain drivetrain = TunerConstants . createDrivetrain ( ) ;
2025-02-25 18:15:52 -05:00
private final SendableChooser < Command > autoChooser ;
public double getAngle ( ) {
return gyro . getYaw ( ) . getValueAsDouble ( ) ; // Retourne l'angle actuel du robot
}
2025-02-25 18:12:27 -05:00
Elevateur elevateur = new Elevateur ( ) ;
Pince pince = new Pince ( ) ;
ElevateurManuel elevateurManuel = new ElevateurManuel ( elevateur , manette2 : : getLeftY ) ;
2025-02-26 17:26:31 -05:00
PinceManuel pinceManuel = new PinceManuel ( pince , manette2 : : getRightY ) ;
2025-02-25 18:12:27 -05:00
PinceManuel2 pinceManuel2 = new PinceManuel2 ( pince ) ;
Bougie bougie = new Bougie ( ) ;
Limelight3G limelight3g = new Limelight3G ( ) ;
Limelight3 limelight3 = new Limelight3 ( ) ;
Pose2d pose = new Pose2d ( ) ;
2025-02-25 18:15:52 -05:00
2025-02-25 17:56:24 -05:00
2025-02-25 18:12:27 -05:00
public RobotContainer ( ) {
2025-02-25 18:15:52 -05:00
autoChooser = AutoBuilder . buildAutoChooser ( " New Auto " ) ;
SmartDashboard . putData ( " Auto Mode " , autoChooser ) ;
configureBindings ( ) ;
NamedCommands . registerCommand ( " AprilTag " , new AprilTag3G ( limelight3g , drivetrain , null , null ) ) ;
2025-02-26 18:02:25 -05:00
NamedCommands . registerCommand ( " Station " , new StationPince ( pince , elevateur ) ) ;
NamedCommands . registerCommand ( " L4 " , new L4 ( elevateur , pince ) ) ;
NamedCommands . registerCommand ( " L3 " , new L3 ( elevateur , pince ) ) ;
NamedCommands . registerCommand ( " CoralExpire " , new CoralExpire ( pince , bougie ) ) ;
NamedCommands . registerCommand ( " CoraletAlgue " , new CoralAlgueInspire ( pince , bougie ) ) ;
2025-02-25 18:15:52 -05:00
}
2025-02-25 18:12:27 -05:00
private void configureBindings ( ) {
2025-02-26 18:49:17 -05:00
2025-02-26 18:02:25 -05:00
drivetrain . setDefaultCommand (
2025-02-25 18:12:27 -05:00
// Drivetrain will execute this command periodically
drivetrain . applyRequest ( ( ) - >
2025-02-26 18:49:17 -05:00
drive . withVelocityX ( MathUtil . applyDeadband ( - manette1 . getLeftY ( ) * manette1 . getLeftY ( ) * MaxSpeed , 0 . 1 ) ) // Drive forward with negative Y (forward)
. withVelocityY ( MathUtil . applyDeadband ( - manette1 . getLeftX ( ) * manette1 . getLeftX ( ) * MaxSpeed , 0 . 10000 ) ) // Drive left with negative X (left)
. withRotationalRate ( MathUtil . applyDeadband ( - manette1 . getRightX ( ) * manette1 . getRightX ( ) * MaxAngularRate , 0 . 1 ) ) // Drive counterclockwise with negative X (left)
2025-02-25 18:12:27 -05:00
)
) ;
2025-02-26 18:49:17 -05:00
// Elevateur manuel
2025-02-25 18:15:52 -05:00
drivetrain . registerTelemetry ( logger : : telemeterize ) ;
2025-01-29 19:19:14 -05:00
elevateur . setDefaultCommand ( new RunCommand ( ( ) - > {
2025-02-26 18:49:17 -05:00
elevateur . vitesse ( MathUtil . applyDeadband ( manette2 . getLeftY ( ) * manette2 . getLeftY ( ) , 0 . 1 ) ) ;
2025-01-29 19:19:14 -05:00
} , elevateur ) ) ;
2025-02-25 16:38:35 -05:00
2025-02-26 18:02:25 -05:00
//Pince manuel
2025-02-20 20:25:59 -05:00
pince . setDefaultCommand ( new RunCommand ( ( ) - > {
2025-02-26 18:49:17 -05:00
pince . pivote ( MathUtil . applyDeadband ( manette2 . getRightY ( ) * manette2 . getRightY ( ) , 0 . 1 ) ) ;
2025-02-20 20:25:59 -05:00
} , pince ) ) ;
2025-02-26 18:02:25 -05:00
2025-02-26 18:49:17 -05:00
2025-02-26 18:04:04 -05:00
// manette1
2025-02-26 18:49:17 -05:00
// reset the field-centric heading on left bumper press
2025-02-25 18:12:27 -05:00
manette1 . start ( ) . onTrue ( drivetrain . runOnce ( ( ) - > drivetrain . seedFieldCentric ( ) ) ) ;
2025-02-22 10:30:20 -05:00
manette1 . a ( ) . whileTrue ( new Depart ( elevateur , pince ) ) ;
manette1 . b ( ) . whileTrue ( new L2 ( elevateur , pince ) ) ;
manette1 . x ( ) . whileTrue ( new L3 ( elevateur , pince ) ) ;
manette1 . y ( ) . whileTrue ( new L4 ( elevateur , pince ) ) ;
manette1 . rightTrigger ( ) . whileTrue ( new CoralAlgueInspire ( pince , bougie ) ) ;
manette1 . rightBumper ( ) . whileTrue ( new StationPince ( pince , elevateur ) ) ;
2025-02-26 18:11:11 -05:00
manette1 . leftTrigger ( ) . whileTrue ( new CoralExpire ( pince , bougie ) ) ;
2025-01-29 19:29:01 -05:00
//manette2
2025-02-22 14:46:41 -05:00
manette2 . leftTrigger ( ) . whileTrue ( new AlgueExpire ( pince , bougie ) ) ;
2025-02-24 18:15:32 -05:00
manette2 . a ( ) . whileTrue ( new CorailAspir ( pince ) ) ;
2025-02-24 19:13:12 -05:00
manette2 . start ( ) . whileTrue ( new reset ( elevateur ) ) ;
2025-02-26 18:11:11 -05:00
manette2 . b ( ) . whileTrue ( new Algue_inspire ( pince ) ) ;
manette2 . leftBumper ( ) . whileTrue ( new AprilTag3 ( limelight3 , drivetrain , manette1 : : getLeftX , manette1 : : getLeftY ) ) ;
manette2 . rightBumper ( ) . whileTrue ( new Forme3 ( limelight3 , drivetrain , manette1 : : getLeftX , manette1 : : getLeftY ) ) ;
2025-01-29 19:01:51 -05:00
}
2025-02-10 19:49:13 -05:00
2025-02-26 18:02:25 -05:00
// Note that X is defined as forward according to WPILib convention,
// and Y is defined as to the left according to WPILib convention.
2025-02-25 18:12:27 -05:00
// manette2.leftTrigger().whileTrue(new AprilTag3G(limelight3g,drivetrain,manette1::getLeftX,manette1::getLeftY));
2025-02-26 18:02:25 -05:00
2025-02-18 18:47:13 -05:00
public Command getAutonomousCommand ( ) {
2025-02-25 18:12:27 -05:00
return new SequentialCommandGroup ( Commands . runOnce ( ( ) - > {
boolean flip = DriverStation . getAlliance ( ) . orElse ( Alliance . Blue ) = = Alliance . Red ;
if ( flip ) {
drivetrain . resetPose ( FlippingUtil . flipFieldPose ( ( ( PathPlannerAuto ) autoChooser . getSelected ( ) ) . getStartingPose ( ) ) ) ;
}
else {
drivetrain . resetPose ( ( ( PathPlannerAuto ) autoChooser . getSelected ( ) ) . getStartingPose ( ) ) ;
}
} ) , autoChooser . getSelected ( ) , new RainBow ( bougie ) ) ;
}
}