Compare commits
	
		
			58 Commits
		
	
	
		
			Limelight
			...
			42fb45d2de
		
	
	| Author | SHA1 | Date | |
|---|---|---|---|
|  | 42fb45d2de | ||
|  | 37ea658138 | ||
|  | 0adbe7b4e2 | ||
|  | 5700ea70d9 | ||
|  | e58cdf0b5b | ||
|  | 6c6abb58e1 | ||
|  | 5b754ff824 | ||
|  | 606c4e98f3 | ||
|  | b6d9ccddb8 | ||
|  | 3660bb9c4a | ||
|  | f60f129410 | ||
|  | a11f31a2a8 | ||
|  | 94aae66eed | ||
|  | 9f83b61c46 | ||
|  | 5d84d83f7d | ||
|  | 87c3abcb65 | ||
|  | 93e5bb0b46 | ||
|  | 7be5f8c2fc | ||
|  | 26d32e3707 | ||
|  | 1f4111ef6d | ||
|  | bb9d5a5550 | ||
|  | 69ef6b6982 | ||
|  | 0be9356fa9 | ||
|  | 1627770572 | ||
|  | c1bdf0aab7 | ||
|  | 8bc8f0390f | ||
|  | 0e04704942 | ||
|  | 53adcf5701 | ||
|  | 319c370c6e | ||
|  | 451d3c6e20 | ||
|  | 2260580c81 | ||
|  | 9cd08cf07c | ||
|  | 8aca411a23 | ||
|  | 44f6030e99 | ||
|  | 6f75b9cc42 | ||
|  | 210d219793 | ||
|  | 06abfa4dbb | ||
|  | 26a4b9f9a3 | ||
|  | b384585224 | ||
|  | ee2c9ff4b2 | ||
|  | 20c95efe93 | ||
|  | 4869632d6d | ||
|  | afaec61f6d | ||
|  | 126058e9d4 | ||
|  | 1f17aaf4de | ||
|  | eece0f47fa | ||
|  | c81f118058 | ||
|  | 7848c4aaf2 | ||
|  | 1d1d6e962d | ||
|  | d6420659e9 | ||
|  | aafb2a62b5 | ||
|  | 0fdfa4269d | ||
|  | 017f168b3c | ||
|  | 5ffa28596c | ||
|  | e7b4b47928 | ||
|  | 0577ce368a | ||
|  | 7521c0d94e | ||
|  | b16d11b70a | 
| @@ -1,4 +1,9 @@ | ||||
| { | ||||
|   "Joysticks": { | ||||
|     "window": { | ||||
|       "visible": false | ||||
|     } | ||||
|   }, | ||||
|   "System Joysticks": { | ||||
|     "window": { | ||||
|       "enabled": false | ||||
|   | ||||
| @@ -20,85 +20,140 @@ 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.Commands; | ||||
| import edu.wpi.first.wpilibj2.command.RunCommand; | ||||
| import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; | ||||
| import edu.wpi.first.wpilibj2.command.button.CommandXboxController; | ||||
| import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; | ||||
| import frc.robot.TunerConstants.TunerConstants; | ||||
| import frc.robot.commands.Algue1Test; | ||||
| import frc.robot.commands.Algue2Test; | ||||
| import frc.robot.commands.AlgueExpire; | ||||
| import frc.robot.commands.Algue_inspire; | ||||
| import frc.robot.commands.AprilTag3; | ||||
| import frc.robot.commands.AprilTag3G; | ||||
| import frc.robot.commands.CorailAspir; | ||||
| import frc.robot.commands.CorailTest; | ||||
| import frc.robot.commands.CoralAlgueInspire; | ||||
| import frc.robot.commands.CoralExpire; | ||||
| import frc.robot.commands.Depart; | ||||
| import frc.robot.commands.ElevateurManuel; | ||||
| import frc.robot.commands.Forme3; | ||||
| import frc.robot.commands.L2; | ||||
| import frc.robot.commands.L3; | ||||
| import frc.robot.commands.L4; | ||||
| import frc.robot.commands.PinceManuel; | ||||
| import frc.robot.commands.PinceManuel2; | ||||
| import frc.robot.commands.RainBow; | ||||
| import frc.robot.commands.StationPince; | ||||
| import frc.robot.commands.reset; | ||||
| import frc.robot.subsystems.Bougie; | ||||
| import frc.robot.subsystems.CommandSwerveDrivetrain; | ||||
| import frc.robot.subsystems.Elevateur; | ||||
| import frc.robot.subsystems.Limelight3; | ||||
| import frc.robot.subsystems.Limelight3G; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| public class RobotContainer { | ||||
|     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 | ||||
|   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 | ||||
|  | ||||
|     /* 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 | ||||
|             .withDriveRequestType(DriveRequestType.OpenLoopVoltage); // Use open-loop control for drive motors | ||||
|   /* 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 | ||||
|     .withDriveRequestType(DriveRequestType.OpenLoopVoltage | ||||
|     ); // Use open-loop control for drive motors | ||||
|  | ||||
|     private final Telemetry logger = new Telemetry(MaxSpeed); | ||||
|   private final Telemetry logger = new Telemetry(MaxSpeed); | ||||
|   private final CommandXboxController manette1 = new CommandXboxController(0); | ||||
|   private final CommandXboxController manette2 = new CommandXboxController(1); | ||||
|   private final Pigeon2 gyro = new Pigeon2(13); // ID du Pigeon 2 | ||||
|   public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain(); | ||||
|   private final SendableChooser<Command> autoChooser; | ||||
|   public double getAngle() { | ||||
|     return gyro.getYaw().getValueAsDouble(); // Retourne l'angle actuel du robot | ||||
|   } | ||||
|    | ||||
|   Elevateur elevateur = new Elevateur(); | ||||
|   Pince pince = new Pince(); | ||||
|   ElevateurManuel elevateurManuel = new ElevateurManuel(elevateur, manette2::getLeftY); | ||||
|   PinceManuel pinceManuel = new PinceManuel(pince,manette2::getRightY); | ||||
|   PinceManuel2 pinceManuel2 = new PinceManuel2(pince); | ||||
|   Bougie bougie = new Bougie(); | ||||
|   Limelight3G limelight3g = new Limelight3G(); | ||||
|   Limelight3 limelight3 = new Limelight3(); | ||||
|   Pose2d pose = new Pose2d(); | ||||
|    | ||||
|  | ||||
|     private final CommandXboxController manette1 = new CommandXboxController(0); | ||||
|     private final CommandXboxController manette2 = new CommandXboxController(1); | ||||
|     | ||||
|     public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain(); | ||||
|  | ||||
|   public RobotContainer() { | ||||
|     autoChooser = AutoBuilder.buildAutoChooser("New Auto"); | ||||
|     SmartDashboard.putData("Auto Mode", autoChooser); | ||||
|     configureBindings(); | ||||
|     NamedCommands.registerCommand("AprilTag", new AprilTag3G(limelight3g, drivetrain, null, null)); | ||||
|     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)); | ||||
|     } | ||||
|   private void configureBindings() { | ||||
|      | ||||
|     private final SendableChooser<Command> autoChooser; | ||||
|     Bougie bougie = new Bougie(); | ||||
|     Limelight3G limelight3g = new Limelight3G(); | ||||
|     Limelight3 limelight3 = new Limelight3(); | ||||
|     Pose2d pose = new Pose2d(); | ||||
|     private final Pigeon2 gyro = new Pigeon2(13); // ID du Pigeon 2 | ||||
|     public double getAngle() { | ||||
|         return gyro.getYaw().getValueAsDouble(); // Retourne l'angle actuel du robot | ||||
|     } | ||||
|         public RobotContainer() { | ||||
|         autoChooser = AutoBuilder.buildAutoChooser("New Auto"); | ||||
|         SmartDashboard.putData("Auto Mode", autoChooser); | ||||
|         configureBindings(); | ||||
|         NamedCommands.registerCommand("AprilTag", new AprilTag3G(limelight3g, drivetrain, null, null)); | ||||
|     } | ||||
|  drivetrain.setDefaultCommand( | ||||
|           // Drivetrain will execute this command periodically | ||||
|           drivetrain.applyRequest(() -> | ||||
|             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) | ||||
|         ) | ||||
|       ); | ||||
|     // Elevateur manuel | ||||
|     drivetrain.registerTelemetry(logger::telemeterize); | ||||
|     elevateur.setDefaultCommand(new RunCommand(()->{ | ||||
|       elevateur.vitesse(MathUtil.applyDeadband(manette2.getLeftY()*manette2.getLeftY(), 0.1)); | ||||
|     }, elevateur)); | ||||
|  | ||||
|     private void configureBindings() { | ||||
|         // Note that X is defined as forward according to WPILib convention, | ||||
|         // and Y is defined as to the left according to WPILib convention. | ||||
|         drivetrain.setDefaultCommand( | ||||
|             // Drivetrain will execute this command periodically | ||||
|             drivetrain.applyRequest(() -> | ||||
|                 drive.withVelocityX(MathUtil.applyDeadband(-manette1.getLeftY()*MaxSpeed, 0.2)) // Drive forward with negative Y (forward) | ||||
|                     .withVelocityY(MathUtil.applyDeadband(-manette1.getLeftX()*MaxSpeed, 0.2)) // Drive left with negative X (left) | ||||
|                     .withRotationalRate(MathUtil.applyDeadband(-manette1.getRightX()*MaxAngularRate, 0.15)) // Drive counterclockwise with negative X (left) | ||||
|             ) | ||||
|         ); | ||||
|     //Pince manuel | ||||
|     pince.setDefaultCommand(new RunCommand(()->{ | ||||
|       pince.pivote(MathUtil.applyDeadband(manette2.getRightY()*manette2.getRightY(), 0.1)); | ||||
|     }, pince)); | ||||
|       | ||||
|      | ||||
|     // manette1 | ||||
|     // reset the field-centric heading on left bumper press | ||||
|     manette1.start().onTrue(drivetrain.runOnce(() -> drivetrain.seedFieldCentric())); | ||||
|     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)); | ||||
|     manette1.leftTrigger().whileTrue(new CoralExpire(pince, bougie)); | ||||
|     //manette2 | ||||
|     manette2.leftTrigger().whileTrue(new AlgueExpire(pince, bougie)); | ||||
|     manette2.a().whileTrue(new CorailAspir(pince)); | ||||
|     manette2.start().whileTrue(new reset(elevateur)); | ||||
|     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)); | ||||
|   } | ||||
|    | ||||
|  | ||||
|         // reset the field-centric heading on left bumper press | ||||
|         manette1.y().whileTrue(drivetrain.sysIdQuasistatic(SysIdRoutine.Direction.kForward)); | ||||
|         manette1.a().whileTrue(drivetrain.sysIdQuasistatic(SysIdRoutine.Direction.kReverse)); | ||||
|         manette1.b().whileTrue(drivetrain.sysIdDynamic(SysIdRoutine.Direction.kForward)); | ||||
|         manette1.x().whileTrue(drivetrain.sysIdDynamic(SysIdRoutine.Direction.kReverse)); | ||||
|         manette1.start().onTrue(drivetrain.runOnce(() -> drivetrain.seedFieldCentric())); | ||||
|         manette1.leftTrigger().whileTrue(new AprilTag3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY)); | ||||
|         manette1.rightTrigger().whileTrue(new Forme3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY)); | ||||
|         manette2.leftTrigger().whileTrue(new AprilTag3G(limelight3g,drivetrain,manette1::getLeftX,manette1::getLeftY)); | ||||
|         drivetrain.registerTelemetry(logger::telemeterize); | ||||
|     } | ||||
|  | ||||
|  | ||||
|       // Note that X is defined as forward according to WPILib convention, | ||||
|       // and Y is defined as to the left according to WPILib convention. | ||||
|    | ||||
|      | ||||
|     // manette2.leftTrigger().whileTrue(new AprilTag3G(limelight3g,drivetrain,manette1::getLeftX,manette1::getLeftY)); | ||||
|      | ||||
|     public Command getAutonomousCommand() { | ||||
|         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)); | ||||
|     } | ||||
|               | ||||
|       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)); | ||||
|     }     | ||||
| } | ||||
							
								
								
									
										41
									
								
								src/main/java/frc/robot/commands/Algue1Test.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										41
									
								
								src/main/java/frc/robot/commands/Algue1Test.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,41 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class Algue1Test extends Command { | ||||
|   private Pince pince; | ||||
|   /** Creates a new AlgueTest. */ | ||||
|   public Algue1Test(Pince pince) { | ||||
|     this.pince = pince; | ||||
|     addRequirements(pince); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     pince.algue1Test(0.2); | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     pince.algue1Test(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										41
									
								
								src/main/java/frc/robot/commands/Algue2Test.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										41
									
								
								src/main/java/frc/robot/commands/Algue2Test.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,41 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class Algue2Test extends Command { | ||||
|   private Pince pince; | ||||
|   /** Creates a new AlgueTest. */ | ||||
|   public Algue2Test(Pince pince) { | ||||
|     this.pince = pince; | ||||
|     addRequirements(pince); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     pince.algue2Test(0.2); | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     pince.algue2Test(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										51
									
								
								src/main/java/frc/robot/commands/AlgueExpire.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										51
									
								
								src/main/java/frc/robot/commands/AlgueExpire.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,51 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Bougie; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class AlgueExpire extends Command { | ||||
|   private Pince pince; | ||||
|   private Bougie bougie; | ||||
|   /** Creates a new CoralAlgue. */ | ||||
|   public AlgueExpire(Pince pince,Bougie bougie) { | ||||
|     this.pince = pince; | ||||
|     this.bougie = bougie; | ||||
|     addRequirements(pince,bougie); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     if(pince.emperagealgue()>60){ | ||||
|       pince.aspirealgue(-0.5); | ||||
|     } | ||||
|     else{ | ||||
|       pince.aspirealgue(-0.5); | ||||
|       bougie.Jaune(); | ||||
|     } | ||||
|      | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     pince.aspirealgue(0);  | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										44
									
								
								src/main/java/frc/robot/commands/Algue_inspire.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										44
									
								
								src/main/java/frc/robot/commands/Algue_inspire.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,44 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class Algue_inspire extends Command { | ||||
|   /** Creates a new Algue_inspire. */ | ||||
|   private Pince pince; | ||||
|   public Algue_inspire(Pince pince) { | ||||
|     this.pince = pince; | ||||
|     addRequirements(pince); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|  | ||||
|   //ajouter l'amperage pour arreter les moteurs | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     pince.aspirealgue(0.5); | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     pince.aspirealgue(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										42
									
								
								src/main/java/frc/robot/commands/CorailAspir.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										42
									
								
								src/main/java/frc/robot/commands/CorailAspir.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,42 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class CorailAspir extends Command { | ||||
|   /** Creates a new CorailAspir. */ | ||||
|   private Pince pince; | ||||
|   public CorailAspir(Pince pince) { | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|     this.pince = pince; | ||||
|     addRequirements(pince); | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|  | ||||
|     pince.aspirecoral(0.5); | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     pince.aspirecoral(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										41
									
								
								src/main/java/frc/robot/commands/CorailTest.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										41
									
								
								src/main/java/frc/robot/commands/CorailTest.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,41 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class CorailTest extends Command { | ||||
|   private Pince pince; | ||||
|   /** Creates a new AlgueTest. */ | ||||
|   public CorailTest(Pince pince) { | ||||
|     this.pince = pince; | ||||
|     addRequirements(pince); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     pince.aspirecoral(0.2); | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     pince.aspirecoral(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										53
									
								
								src/main/java/frc/robot/commands/CoralAlgueInspire.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										53
									
								
								src/main/java/frc/robot/commands/CoralAlgueInspire.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,53 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Bougie; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class CoralAlgueInspire extends Command { | ||||
|   private Pince pince; | ||||
|   private Bougie bougie; | ||||
|   /** Creates a new CoralAlgue. */ | ||||
|   public CoralAlgueInspire(Pince pince, Bougie bougie) { | ||||
|     this.pince = pince; | ||||
|     this.bougie = bougie; | ||||
|     addRequirements(pince,bougie); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     pince.aspirecoral(-.5); | ||||
|     if(pince.emperagealgue()>60){ | ||||
|       pince.aspirealgue(0); | ||||
|       bougie.Bleu(); | ||||
|      }  | ||||
|      else{ | ||||
|       pince.aspirealgue(0.5); | ||||
|       } | ||||
|      | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     pince.aspirecoral(0); | ||||
|     pince.aspirealgue(0);  | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										49
									
								
								src/main/java/frc/robot/commands/CoralExpire.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										49
									
								
								src/main/java/frc/robot/commands/CoralExpire.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,49 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Pince; | ||||
| import frc.robot.subsystems.Bougie; | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class CoralExpire extends Command { | ||||
|   private Pince pince; | ||||
|   Bougie bougie; | ||||
|   /** Creates a new CoralAlgue. */ | ||||
|   public CoralExpire(Pince pince, Bougie bougie) { | ||||
|     this.pince = pince; | ||||
|     this.bougie = bougie; | ||||
|     addRequirements(pince,bougie); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     //if(pince.emperagecoral() > 60){ | ||||
|     //  pince.aspirecoral(0); | ||||
|    //} | ||||
|    //else{ | ||||
|     pince.aspirecoral(-.5); | ||||
|     //bougie.Jaune(); | ||||
|    // } | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     pince.aspirecoral(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										52
									
								
								src/main/java/frc/robot/commands/Depart.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										52
									
								
								src/main/java/frc/robot/commands/Depart.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,52 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Elevateur; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class Depart extends Command { | ||||
|   private Elevateur elevateur; | ||||
|   private Pince pince; | ||||
|   /** Creates a new L2. */ | ||||
|   public Depart(Elevateur elevateur, Pince pince) { | ||||
|     this.pince = pince; | ||||
|     this.elevateur = elevateur; | ||||
|     addRequirements(elevateur,pince); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     if(elevateur.limit2()==true){ | ||||
|       elevateur.vitesse(0); | ||||
|       elevateur.reset(); | ||||
|     } | ||||
|     else{ | ||||
|       elevateur.vitesse(.5); | ||||
|     } | ||||
|      | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     elevateur.vitesse(0); | ||||
|     pince.pivote(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return elevateur.limit2()==true; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										47
									
								
								src/main/java/frc/robot/commands/DepartPince.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										47
									
								
								src/main/java/frc/robot/commands/DepartPince.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,47 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class DepartPince extends Command { | ||||
|   private Pince pince; | ||||
|   /** Creates a new DepartPince. */ | ||||
|   public DepartPince(Pince pince) { | ||||
|     this.pince = pince; | ||||
|     addRequirements(pince); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     if(pince.position()==true){ | ||||
|       pince.pivote(0); | ||||
|       pince.reset(); | ||||
|     } | ||||
|     else{ | ||||
|       pince.pivote(.2); | ||||
|     } | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     pince.pivote(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										48
									
								
								src/main/java/frc/robot/commands/ElevateurManuel.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										48
									
								
								src/main/java/frc/robot/commands/ElevateurManuel.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,48 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import java.util.function.DoubleSupplier; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Elevateur; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class ElevateurManuel extends Command { | ||||
|   private DoubleSupplier doubleSupplier; | ||||
|   private Elevateur elevateur; | ||||
|   /** Creates a new ElevateurManuel. */ | ||||
|   public ElevateurManuel(Elevateur elevateur,DoubleSupplier doubleSupplier) { | ||||
|     this.doubleSupplier = doubleSupplier; | ||||
|     this.elevateur = elevateur; | ||||
|     addRequirements(elevateur); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     if(elevateur.limit2()==true){ | ||||
|       elevateur.vitesse(0); | ||||
|     } | ||||
|     elevateur.vitesse(doubleSupplier.getAsDouble()/3.5); | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     elevateur.vitesse(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										65
									
								
								src/main/java/frc/robot/commands/L2.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										65
									
								
								src/main/java/frc/robot/commands/L2.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,65 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
|  | ||||
| import frc.robot.subsystems.Elevateur; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class L2 extends Command { | ||||
|   private Elevateur elevateur; | ||||
|   private Pince pince; | ||||
|   /** Creates a new L2. */ | ||||
|   public L2(Elevateur elevateur,Pince pince) { | ||||
|     this.elevateur = elevateur; | ||||
|     this.pince = pince; | ||||
|     addRequirements(elevateur,pince); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     if(elevateur.position()<=-1 && elevateur.position()>=-0.9){ | ||||
|       elevateur.vitesse(0); | ||||
|     } | ||||
|     else if(elevateur.position()>=-1){ | ||||
|       elevateur.vitesse(-0.2); | ||||
|     } | ||||
|     else{ | ||||
|       elevateur.vitesse(.2); | ||||
|     // } | ||||
|     // if(pince.encodeurpivot()>=500 && pince.encodeurpivot()<=510){ | ||||
|     //   pince.pivote(0); | ||||
|       | ||||
|     // } | ||||
|     // else if(pince.encodeurpivot()>=510){ | ||||
|     //   pince.pivote(0.2); | ||||
|     // } | ||||
|     // else{ | ||||
|     //   pince.pivote(-0.2); | ||||
|      } | ||||
|  | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     elevateur.vitesse(0); | ||||
|     pince.pivote(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										63
									
								
								src/main/java/frc/robot/commands/L3.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										63
									
								
								src/main/java/frc/robot/commands/L3.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,63 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
|  | ||||
| import frc.robot.subsystems.Elevateur; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class L3 extends Command { | ||||
|   private Elevateur elevateur; | ||||
|   private Pince pince; | ||||
|   /** Creates a new L2. */ | ||||
|   public L3(Elevateur elevateur,Pince pince) { | ||||
|     this.elevateur = elevateur; | ||||
|     this.pince = pince;   | ||||
|     addRequirements(elevateur,pince); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     if(elevateur.position()<=-2.9 && elevateur.position()>=-3){ | ||||
|       elevateur.vitesse(0); | ||||
|     } | ||||
|     else if(elevateur.position()>=-2.9){ | ||||
|       elevateur.vitesse(-0.2); | ||||
|     } | ||||
|     else{ | ||||
|       elevateur.vitesse(.2); | ||||
|     } | ||||
|     // if(pince.encodeurpivot()>=700 && pince.encodeurpivot()<=710){ | ||||
|     //   pince.pivote(0); | ||||
|     // } | ||||
|     // else if(pince.encodeurpivot()>=710){ | ||||
|     //   pince.pivote(0.2); | ||||
|     // } | ||||
|     // else{ | ||||
|     //   pince.pivote(-0.2); | ||||
|     // } | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     elevateur.vitesse(0); | ||||
|     pince.pivote(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										63
									
								
								src/main/java/frc/robot/commands/L4.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										63
									
								
								src/main/java/frc/robot/commands/L4.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,63 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
|  | ||||
| import frc.robot.subsystems.Elevateur; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class L4 extends Command { | ||||
|   private Elevateur elevateur; | ||||
|   private Pince pince; | ||||
|   /** Creates a new L2. */ | ||||
|   public L4(Elevateur elevateur,Pince pince) { | ||||
|     this.elevateur = elevateur; | ||||
|     this.pince = pince; | ||||
|     addRequirements(elevateur,pince); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     if(elevateur.position()<=-6.5 && elevateur.position()>=-6.4){ | ||||
|       elevateur.vitesse(0); | ||||
|     } | ||||
|     else if(elevateur.position()>=-6.5){ | ||||
|       elevateur.vitesse(-0.2); | ||||
|     } | ||||
|     else{ | ||||
|       elevateur.vitesse(.2); | ||||
|     } | ||||
|     // if(pince.encodeurpivot()>=800 && pince.encodeurpivot()<=809){ | ||||
|     //   pince.pivote(0); | ||||
|     // } | ||||
|     // else if(pince.encodeurpivot()>=810){ | ||||
|     //   pince.pivote(0.2); | ||||
|     // } | ||||
|     // else{ | ||||
|     //   pince.pivote(-0.2); | ||||
|     // } | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     elevateur.vitesse(0); | ||||
|     pince.pivote(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										50
									
								
								src/main/java/frc/robot/commands/PinceManuel.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										50
									
								
								src/main/java/frc/robot/commands/PinceManuel.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,50 @@ | ||||
| // 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.commands; | ||||
| import java.util.function.DoubleSupplier; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class PinceManuel extends Command { | ||||
|   private Pince pince; | ||||
|   private DoubleSupplier x; | ||||
|   /** Creates a new PinceManuel. */ | ||||
|   public PinceManuel(Pince pince, DoubleSupplier x) { | ||||
|     this.pince = pince; | ||||
|     this.x = x; | ||||
|     //this.doubleSupplier = doubleSupplier; | ||||
|     addRequirements(pince); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|      if(pince.position()){ | ||||
|        pince.pivote(0); | ||||
|      } | ||||
|      else{ | ||||
|       pince.pivote(x.getAsDouble()/3.5); | ||||
|      } | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     pince.pivote(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										47
									
								
								src/main/java/frc/robot/commands/PinceManuel2.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										47
									
								
								src/main/java/frc/robot/commands/PinceManuel2.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,47 @@ | ||||
| // 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.commands; | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class PinceManuel2 extends Command { | ||||
|   private Pince pince; | ||||
|   //private DoubleSupplier doubleSupplier; | ||||
|   /** Creates a new PinceManuel. */ | ||||
|   public PinceManuel2(Pince pince | ||||
|     | ||||
|   //,DoubleSupplier doubleSupplier | ||||
|   ) { | ||||
|     this.pince = pince; | ||||
|    // this.doubleSupplier = doubleSupplier; | ||||
|     addRequirements(pince); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|  | ||||
|       pince.pivote(-0.2); | ||||
|  | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     pince.pivote(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										64
									
								
								src/main/java/frc/robot/commands/StationPince.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										64
									
								
								src/main/java/frc/robot/commands/StationPince.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,64 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Elevateur; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class StationPince extends Command { | ||||
|    | ||||
|   private Pince pince; | ||||
|   private Elevateur elevateur; | ||||
|   /** Creates a new L2Pince. */ | ||||
|   public StationPince(Pince pince,Elevateur elevateur) { | ||||
|     this.elevateur = elevateur; | ||||
|     this.pince = pince; | ||||
|     addRequirements(pince,elevateur); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     pince.aspirecoral(0.5); | ||||
|     if(pince.encodeurpivot()>=900 && pince.encodeurpivot()<=910){ | ||||
|       pince.pivote(0); | ||||
|     } | ||||
|     else if(pince.encodeurpivot()>=910){ | ||||
|       pince.pivote(0.2); | ||||
|     } | ||||
|     else{ | ||||
|       pince.pivote(-0.2); | ||||
|     } | ||||
|     if(elevateur.position()>=400 && elevateur.position()<=410){ | ||||
|       elevateur.vitesse(0); | ||||
|     } | ||||
|     else if(elevateur.position()>=410){ | ||||
|       elevateur.vitesse(0.3); | ||||
|     } | ||||
|     else{ | ||||
|       elevateur.vitesse(-.3); | ||||
|     } | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) { | ||||
|     pince.pivote(0); | ||||
|     pince.aspirecoral(0); | ||||
|   } | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
							
								
								
									
										45
									
								
								src/main/java/frc/robot/commands/reset.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										45
									
								
								src/main/java/frc/robot/commands/reset.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,45 @@ | ||||
| // 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.commands; | ||||
|  | ||||
| import edu.wpi.first.wpilibj2.command.Command; | ||||
| import frc.robot.subsystems.Elevateur; | ||||
| import frc.robot.subsystems.Pince; | ||||
|  | ||||
|  | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class reset extends Command { | ||||
|   /** Creates a new reset. */ | ||||
|   private Elevateur elevateur; | ||||
|   private Pince pince; | ||||
|   public reset(Elevateur elevateur) { | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|     this.elevateur = elevateur; | ||||
|     this.pince = pince; | ||||
|     addRequirements(elevateur,pince); | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|     elevateur.reset(); | ||||
|     pince.reset(); | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) {} | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
| @@ -11,7 +11,7 @@ import com.ctre.phoenix.led.RainbowAnimation; | ||||
| import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||||
|  | ||||
| public class Bougie extends SubsystemBase { | ||||
|   CANdle candle = new CANdle(5); | ||||
|   CANdle candle = new CANdle(23); | ||||
|   CANdleConfiguration config = new CANdleConfiguration(); | ||||
|   RainbowAnimation rainbowAnim = new RainbowAnimation(1, 0.5, 64); | ||||
|   /** Creates a new Bougie. */ | ||||
| @@ -20,14 +20,29 @@ public class Bougie extends SubsystemBase { | ||||
|     candle.configAllSettings(config); | ||||
|   } | ||||
|   public void Rouge() { | ||||
|    candle.setLEDs(255, 0, 0); | ||||
|    candle.setLEDs(255, 0, 0,0,8,8); | ||||
|    candle.setLEDs(255, 0, 0,0,24,8); | ||||
|    candle.setLEDs(255, 0, 0,0,40,8); | ||||
|    candle.setLEDs(255, 0, 0,0,56,8); | ||||
|   } | ||||
|   public void Vert() { | ||||
|    candle.setLEDs(0, 255, 0); | ||||
|    candle.setLEDs(0, 255, 0,0,8,8); | ||||
|    candle.setLEDs(0, 255, 0,0,24,8); | ||||
|    candle.setLEDs(0, 255, 0,0,40,8); | ||||
|    candle.setLEDs(0, 255, 0,0,56,8); | ||||
|   } | ||||
|   public void Bleu() { | ||||
|    candle.setLEDs(0, 0, 255); | ||||
|     candle.setLEDs(0, 0, 255,0,16,8); | ||||
|     candle.setLEDs(0, 0, 255,0,32,8); | ||||
|     candle.setLEDs(0, 0, 255,0,48,8); | ||||
|     candle.setLEDs(0, 0, 255,0,64,8); | ||||
|   } | ||||
|    public void Jaune() { | ||||
|    candle.setLEDs(255, 215, 0,0,16,8); | ||||
|    candle.setLEDs(255, 215, 0,0,32,8); | ||||
|    candle.setLEDs(255, 215, 0,0,48,8); | ||||
|    candle.setLEDs(255, 215, 0,0,64,8); | ||||
|    } | ||||
|   public void RainBow(){candle.animate(rainbowAnim);} | ||||
|   public void RainBowStop(){candle.animate(null);} | ||||
|   @Override | ||||
| @@ -35,4 +50,3 @@ public class Bougie extends SubsystemBase { | ||||
|     // This method will be called once per scheduler run | ||||
|   } | ||||
| } | ||||
|  | ||||
|   | ||||
							
								
								
									
										40
									
								
								src/main/java/frc/robot/subsystems/Elevateur.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										40
									
								
								src/main/java/frc/robot/subsystems/Elevateur.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,40 @@ | ||||
| // 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.subsystems; | ||||
|  | ||||
| import edu.wpi.first.networktables.GenericEntry; | ||||
| import edu.wpi.first.wpilibj.DigitalInput; | ||||
| import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; | ||||
| import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; | ||||
| import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||||
| import com.revrobotics.spark.SparkMax; | ||||
| import com.revrobotics.spark.SparkLowLevel.MotorType; | ||||
| public class Elevateur extends SubsystemBase { | ||||
|   ShuffleboardTab teb = Shuffleboard.getTab("teb"); | ||||
|   /** Creates a new Elevateur. */ | ||||
|   public Elevateur() { | ||||
|     teb.addDouble("encodeur elevateur",this::position); | ||||
|     teb.addBoolean("limit elevateur", this::limit2); | ||||
|   } | ||||
|   final SparkMax  monte = new SparkMax(22, MotorType.kBrushless); | ||||
|   final DigitalInput limit2 = new DigitalInput(0); | ||||
|    | ||||
|   public double position(){ | ||||
|     return monte.getEncoder().getPosition(); | ||||
|   } | ||||
|   public void vitesse(double vitesse){ | ||||
|     monte.set(vitesse); | ||||
|   } | ||||
|   public boolean limit2(){ | ||||
|     return limit2.get(); | ||||
|   }  | ||||
|   public void reset(){ | ||||
|     monte.getEncoder().setPosition(0); | ||||
|   } | ||||
|   @Override | ||||
|   public void periodic() { | ||||
|     // This method will be called once per scheduler run | ||||
|   } | ||||
| } | ||||
| @@ -1,26 +0,0 @@ | ||||
| // 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.subsystems; | ||||
|  | ||||
| import edu.wpi.first.wpilibj.DigitalInput; | ||||
| import edu.wpi.first.wpilibj.motorcontrol.Spark; | ||||
| import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||||
|  | ||||
| public class Grimpeur extends SubsystemBase { | ||||
|   /** Creates a new Grimpeur. */ | ||||
|   public Grimpeur() {} | ||||
|   final Spark grimpeur = new Spark(0); | ||||
|   final DigitalInput limit1 = new DigitalInput(0); | ||||
|   public void grimpe(double vitesse){ | ||||
|     grimpeur.set(vitesse); | ||||
|   } | ||||
|   final void stop(){ | ||||
|     limit1.get(); | ||||
|   } | ||||
|   @Override | ||||
|   public void periodic() { | ||||
|     // This method will be called once per scheduler run | ||||
|   } | ||||
| } | ||||
							
								
								
									
										65
									
								
								src/main/java/frc/robot/subsystems/Pince.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										65
									
								
								src/main/java/frc/robot/subsystems/Pince.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,65 @@ | ||||
| // 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.subsystems; | ||||
|  | ||||
| import com.revrobotics.spark.SparkLowLevel.MotorType; | ||||
| import com.revrobotics.spark.SparkMax; | ||||
|  | ||||
| import edu.wpi.first.networktables.GenericEntry; | ||||
| import edu.wpi.first.wpilibj.DigitalInput; | ||||
| import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; | ||||
| import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; | ||||
| import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||||
|  | ||||
| public class Pince extends SubsystemBase { | ||||
|   /** Creates a new Pince. */ | ||||
|   ShuffleboardTab teb = Shuffleboard.getTab("teb"); | ||||
|   public Pince() { | ||||
|     teb.addBoolean("limit pince",this::position); | ||||
|     teb.addDouble("encodeur pince", this::encodeurpivot); | ||||
|   } | ||||
|   final SparkMax coral = new SparkMax(20, MotorType.kBrushless); | ||||
|   final SparkMax pivoti = new SparkMax(14, MotorType.kBrushless); | ||||
|   final SparkMax algue1 = new SparkMax(16, MotorType.kBrushless); | ||||
|   final SparkMax algue2 = new SparkMax(19, MotorType.kBrushless); | ||||
|   final DigitalInput limit6 = new DigitalInput(9); | ||||
|    | ||||
|   | ||||
|   public void aspirecoral(double vitesse){ | ||||
|     coral.set(vitesse); | ||||
|   } | ||||
| public void pivote(double vitesse){ | ||||
|   pivoti.set(vitesse); | ||||
| } | ||||
| public void aspirealgue(double vitesse){ | ||||
|   algue2.set(-vitesse); | ||||
|   algue1.set(-vitesse); | ||||
| } | ||||
| public double encodeurpivot(){ | ||||
|   return pivoti.getEncoder().getPosition(); | ||||
| } | ||||
| public boolean position(){ | ||||
|  return limit6.get(); | ||||
| } | ||||
| public void reset(){ | ||||
|   pivoti.getEncoder().setPosition(0); | ||||
| } | ||||
| public double emperagecoral(){ | ||||
|   return coral.getOutputCurrent(); | ||||
| } | ||||
| public double emperagealgue(){ | ||||
|   return algue1.getOutputCurrent(); | ||||
| } | ||||
| public void algue1Test(double vitesse){ | ||||
|   algue1.set(vitesse); | ||||
| } | ||||
| public void algue2Test(double vitesse){ | ||||
|   algue2.set(vitesse); | ||||
| } | ||||
|   @Override | ||||
|   public void periodic() { | ||||
|     // This method will be called once per scheduler run | ||||
|   } | ||||
| } | ||||
		Reference in New Issue
	
	Block a user