Compare commits
	
		
			130 Commits
		
	
	
		
			Limelight
			...
			105447c4ad
		
	
	| Author | SHA1 | Date | |
|---|---|---|---|
|  | 105447c4ad | ||
|  | b676cf353f | ||
|  | b7eecbaea9 | ||
|  | c8e94563ad | ||
|  | 04ba179373 | ||
|  | 7c101a6eed | ||
|  | de25aa5730 | ||
|  | b50c5be7de | ||
|  | b31ac996ea | ||
|  | 30cc85d34e | ||
|  | 9248eed724 | ||
|  | 6535047346 | ||
|  | a5f9a28c6f | ||
|  | 6c389731f4 | ||
|  | 079fa4e0a7 | ||
|  | ff6d88d9df | ||
|  | b947c93ab7 | ||
|  | 16edaa6bcc | ||
|  | 63e476c64e | ||
|  | 42fb45d2de | ||
|  | abb6d113d0 | ||
|  | 37ea658138 | ||
|  | 0adbe7b4e2 | ||
|  | 5700ea70d9 | ||
|  | e58cdf0b5b | ||
|  | 9b86a0b975 | ||
|  | df31291697 | ||
|  | 77240d255e | ||
|  | 7ffeb78c35 | ||
|  | 5b80c53963 | ||
|  | 476df088ea | ||
|  | cfc6ba9479 | ||
|  | 3b372104e4 | ||
|  | 36c9f0048b | ||
|  | 6c6abb58e1 | ||
|  | 5b754ff824 | ||
|  | 606c4e98f3 | ||
|  | b6d9ccddb8 | ||
|  | cdd304f9e9 | ||
|  | 1157bdf76a | ||
|  | 17f3f697b9 | ||
|  | 88aa6db075 | ||
|  | 3660bb9c4a | ||
|  | f60f129410 | ||
|  | a11f31a2a8 | ||
|  | 94aae66eed | ||
|  | 9f83b61c46 | ||
|  | 5d84d83f7d | ||
|  | d538b368a7 | ||
|  | 87c3abcb65 | ||
|  | 93e5bb0b46 | ||
|  | b6d2ffd931 | ||
|  | f9d09106a4 | ||
|  | 7be5f8c2fc | ||
|  | 26d32e3707 | ||
|  | 583413ec5f | ||
|  | 1f4111ef6d | ||
|  | bb9d5a5550 | ||
|  | 0524ec6355 | ||
|  | 69ef6b6982 | ||
|  | 0be9356fa9 | ||
|  | a09fbcefce | ||
|  | 7fd7c666f1 | ||
|  | 1627770572 | ||
|  | 29227dd2f6 | ||
|  | dc36eea320 | ||
|  | eb141ac2ba | ||
|  | c1bdf0aab7 | ||
|  | eaa14fb1b1 | ||
|  | 8bc8f0390f | ||
|  | 3458203225 | ||
|  | 0e04704942 | ||
|  | 53adcf5701 | ||
|  | 319c370c6e | ||
|  | 451d3c6e20 | ||
|  | 3669e079bd | ||
|  | 6683613c7f | ||
|  | 2ac9cfe8ff | ||
|  | 56704c3e68 | ||
|  | 0f81dd39e9 | ||
|  | a984625e17 | ||
|  | a54ebb16e9 | ||
|  | 2260580c81 | ||
|  | 6437b9f152 | ||
|  | 9cd08cf07c | ||
|  | 7be1b69ece | ||
|  | d44aea512d | ||
|  | 8aca411a23 | ||
|  | 8a7f10ec64 | ||
|  | 345eb83d39 | ||
|  | f01f327c81 | ||
|  | 0c7cfc9d4c | ||
|  | 44f6030e99 | ||
|  | 6f75b9cc42 | ||
|  | 210d219793 | ||
|  | 06abfa4dbb | ||
|  | 26a4b9f9a3 | ||
|  | b384585224 | ||
|  | 831b9fec75 | ||
|  | 4c49ad4e51 | ||
|  | afe25cf046 | ||
|  | ee2c9ff4b2 | ||
|  | 20c95efe93 | ||
|  | 4869632d6d | ||
|  | afaec61f6d | ||
|  | 126058e9d4 | ||
|  | 1f17aaf4de | ||
|  | eece0f47fa | ||
|  | c81f118058 | ||
|  | 7848c4aaf2 | ||
|  | eec4eee2ff | ||
|  | 982db16833 | ||
|  | 1d1d6e962d | ||
|  | d6420659e9 | ||
|  | aafb2a62b5 | ||
|  | 0fdfa4269d | ||
|  | 017f168b3c | ||
|  | 12b5e6954e | ||
|  | 5ffa28596c | ||
|  | 15be1d67ea | ||
|  | e4c7a12606 | ||
|  | 72da7b7d74 | ||
|  | 7e40328af4 | ||
|  | fd8ab8663b | ||
|  | e7b4b47928 | ||
|  | 0577ce368a | ||
|  | 7521c0d94e | ||
|  | 9653ca7205 | ||
|  | b16d11b70a | ||
|  | 1583a95f52 | 
| @@ -20,18 +20,34 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; | |||||||
| import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; | import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; | ||||||
| import edu.wpi.first.wpilibj2.command.Command; | import edu.wpi.first.wpilibj2.command.Command; | ||||||
| import edu.wpi.first.wpilibj2.command.Commands; | 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.SequentialCommandGroup; | ||||||
| import edu.wpi.first.wpilibj2.command.button.CommandXboxController; | import edu.wpi.first.wpilibj2.command.button.CommandXboxController; | ||||||
| import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; |  | ||||||
| import frc.robot.TunerConstants.TunerConstants; | import frc.robot.TunerConstants.TunerConstants; | ||||||
| import frc.robot.commands.AprilTag3; | import frc.robot.commands.AprilTag3; | ||||||
| import frc.robot.commands.AprilTag3G; | import frc.robot.commands.AprilTag3G; | ||||||
|  | import frc.robot.commands.Depart; | ||||||
| import frc.robot.commands.Forme3; | import frc.robot.commands.Forme3; | ||||||
| import frc.robot.commands.RainBow; | import frc.robot.commands.RainBow; | ||||||
|  | import frc.robot.commands.StationPince; | ||||||
|  | import frc.robot.commands.reset; | ||||||
|  | import frc.robot.commands.Elevateur.ElevateurManuel; | ||||||
|  | import frc.robot.commands.Elevateur.L2; | ||||||
|  | import frc.robot.commands.Elevateur.L3; | ||||||
|  | import frc.robot.commands.Elevateur.L4; | ||||||
|  | import frc.robot.commands.Pince.AlgueExpire; | ||||||
|  | import frc.robot.commands.Pince.Algue_inspire; | ||||||
|  | import frc.robot.commands.Pince.CorailAspir; | ||||||
|  | import frc.robot.commands.Pince.CoralAlgueInspire; | ||||||
|  | import frc.robot.commands.Pince.CoralExpire; | ||||||
|  | import frc.robot.commands.Pince.PinceManuel; | ||||||
| import frc.robot.subsystems.Bougie; | import frc.robot.subsystems.Bougie; | ||||||
| import frc.robot.subsystems.CommandSwerveDrivetrain; | import frc.robot.subsystems.CommandSwerveDrivetrain; | ||||||
|  | import frc.robot.subsystems.Elevateur; | ||||||
|  | import frc.robot.subsystems.Grimpeur; | ||||||
| import frc.robot.subsystems.Limelight3; | import frc.robot.subsystems.Limelight3; | ||||||
| import frc.robot.subsystems.Limelight3G; | import frc.robot.subsystems.Limelight3G; | ||||||
|  | import frc.robot.subsystems.Pince; | ||||||
|  |  | ||||||
| public class RobotContainer { | public class RobotContainer { | ||||||
|   private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); // kSpeedAt12Volts desired top speed |   private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); // kSpeedAt12Volts desired top speed | ||||||
| @@ -40,55 +56,94 @@ public class RobotContainer { | |||||||
|   /* Setting up bindings for necessary control of the swerve drive platform */ |   /* Setting up bindings for necessary control of the swerve drive platform */ | ||||||
|   private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric() |   private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric() | ||||||
|     .withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband |     .withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband | ||||||
|             .withDriveRequestType(DriveRequestType.OpenLoopVoltage); // Use open-loop control for drive motors |     .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 manette1 = new CommandXboxController(0); | ||||||
|   private final CommandXboxController manette2 = new CommandXboxController(1); |   private final CommandXboxController manette2 = new CommandXboxController(1); | ||||||
|     |   private final Pigeon2 gyro = new Pigeon2(13); // ID du Pigeon 2 | ||||||
|   public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain(); |   public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain(); | ||||||
|      |  | ||||||
|   private final SendableChooser<Command> autoChooser; |   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); | ||||||
|   Bougie bougie = new Bougie(); |   Bougie bougie = new Bougie(); | ||||||
|   Limelight3G limelight3g = new Limelight3G(); |   Limelight3G limelight3g = new Limelight3G(); | ||||||
|   Limelight3 limelight3 = new Limelight3(); |   Limelight3 limelight3 = new Limelight3(); | ||||||
|   Pose2d pose = new Pose2d(); |   Pose2d pose = new Pose2d(); | ||||||
|     private final Pigeon2 gyro = new Pigeon2(13); // ID du Pigeon 2 |   Grimpeur Grimpeur = new Grimpeur(); | ||||||
|     public double getAngle() { |    | ||||||
|         return gyro.getYaw().getValueAsDouble(); // Retourne l'angle actuel du robot |  | ||||||
|     } |  | ||||||
|   public RobotContainer() { |   public RobotContainer() { | ||||||
|     autoChooser = AutoBuilder.buildAutoChooser("New Auto"); |     autoChooser = AutoBuilder.buildAutoChooser("New Auto"); | ||||||
|     SmartDashboard.putData("Auto Mode", autoChooser); |     SmartDashboard.putData("Auto Mode", autoChooser); | ||||||
|     configureBindings(); |     configureBindings(); | ||||||
|     NamedCommands.registerCommand("AprilTag", new AprilTag3G(limelight3g, drivetrain, null, null)); |     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 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.setDefaultCommand( | ||||||
|           // Drivetrain will execute this command periodically |           // Drivetrain will execute this command periodically | ||||||
|           drivetrain.applyRequest(() -> |           drivetrain.applyRequest(() -> | ||||||
|                 drive.withVelocityX(MathUtil.applyDeadband(-manette1.getLeftY()*MaxSpeed, 0.2)) // Drive forward with negative Y (forward) |             drive.withVelocityX(MathUtil.applyDeadband(Math.pow(-manette1.getLeftX(), 2)*MaxSpeed, 0.1)) // Drive forward with negative Y (forward) | ||||||
|                     .withVelocityY(MathUtil.applyDeadband(-manette1.getLeftX()*MaxSpeed, 0.2)) // Drive left with negative X (left) |               .withVelocityY(MathUtil.applyDeadband(Math.pow(-manette1.getLeftY(), 2)*MaxSpeed, 0.10000)) // Drive left with negative X (left) | ||||||
|                     .withRotationalRate(MathUtil.applyDeadband(-manette1.getRightX()*MaxAngularRate, 0.15)) // Drive counterclockwise with negative X (left) |               .withRotationalRate(MathUtil.applyDeadband(Math.pow(-manette1.getRightX(), 2)*manette1.getRightX()*MaxAngularRate, 0.1)) // Drive counterclockwise with negative X (left) | ||||||
|         ) |         ) | ||||||
|       ); |       ); | ||||||
|  |     // Elevateur manuel | ||||||
|         // 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); |     drivetrain.registerTelemetry(logger::telemeterize); | ||||||
|  |     elevateur.setDefaultCommand(new RunCommand(()->{ | ||||||
|  |       elevateur.vitesse(MathUtil.applyDeadband(manette2.getLeftY(), 0.1)); | ||||||
|  |     }, elevateur)); | ||||||
|  |  | ||||||
|  |     //Pince manuel | ||||||
|  |     pince.setDefaultCommand(new RunCommand(()->{ | ||||||
|  |       pince.pivote(MathUtil.applyDeadband(manette2.getRightY(), 0.1)); | ||||||
|  |     }, pince)); | ||||||
|  |       | ||||||
|  |      | ||||||
|  |     // manette1 | ||||||
|  |  | ||||||
|  |     // reset the field-centric heading on start press | ||||||
|  |     manette1.start().onTrue(drivetrain.runOnce(() -> drivetrain.seedFieldCentric())); | ||||||
|  |  | ||||||
|  |     //elevateur | ||||||
|  |     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)); | ||||||
|  |  | ||||||
|  |     //pince | ||||||
|  |     manette1.rightTrigger().whileTrue(new CoralAlgueInspire(pince, bougie)); | ||||||
|  |     manette1.rightBumper().whileTrue(new StationPince(pince, elevateur)); | ||||||
|  |     manette1.leftTrigger().whileTrue(new CoralExpire(pince, bougie)); | ||||||
|  |  | ||||||
|  |     //manette2 | ||||||
|  |  | ||||||
|  |     //pince | ||||||
|  |     manette2.a().whileTrue(new CorailAspir(pince)); | ||||||
|  |     manette2.start().whileTrue(new reset(elevateur, pince)); | ||||||
|  |     manette2.b().whileTrue(new Algue_inspire(pince)); | ||||||
|  |     manette2.start().whileTrue(new reset(elevateur,pince)); | ||||||
|  |     manette2.leftTrigger().whileTrue(new AlgueExpire(pince, bougie)); | ||||||
|  |  | ||||||
|  |     //limelight | ||||||
|  |     manette2.leftBumper().whileTrue(new AprilTag3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY)); | ||||||
|  |     manette2.rightBumper().whileTrue(new Forme3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY)); | ||||||
|   } |   } | ||||||
|    |    | ||||||
|  |     // manette2.leftTrigger().whileTrue(new AprilTag3G(limelight3g,drivetrain,manette1::getLeftX,manette1::getLeftY)); | ||||||
|  |      | ||||||
|     public Command getAutonomousCommand() { |     public Command getAutonomousCommand() { | ||||||
|       return new SequentialCommandGroup(Commands.runOnce(()->{ |       return new SequentialCommandGroup(Commands.runOnce(()->{ | ||||||
|         boolean flip = DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red; |         boolean flip = DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red; | ||||||
| @@ -100,5 +155,4 @@ public class RobotContainer { | |||||||
|         } |         } | ||||||
|       }),autoChooser.getSelected(), new RainBow(bougie)); |       }),autoChooser.getSelected(), new RainBow(bougie)); | ||||||
|     }     |     }     | ||||||
|               |  | ||||||
| } | } | ||||||
							
								
								
									
										63
									
								
								src/main/java/frc/robot/commands/BalayeuseAlgue.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										63
									
								
								src/main/java/frc/robot/commands/BalayeuseAlgue.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.Bougie; | ||||||
|  | import frc.robot.subsystems.Requin; | ||||||
|  |  | ||||||
|  | /* 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 BalayeuseAlgue extends Command { | ||||||
|  |   private Requin requin; | ||||||
|  |   private Bougie bougie; | ||||||
|  |   /** Creates a new Balayeuse. */ | ||||||
|  |   public BalayeuseAlgue(Requin requin, Bougie bougie) { | ||||||
|  |     this.requin = requin; | ||||||
|  |     this.bougie =bougie; | ||||||
|  |     addRequirements(requin,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(requin.encodeur()>=500 &&  requin.encodeur()<=510) | ||||||
|  |      { | ||||||
|  |        requin.rotationer(0); | ||||||
|  |        if(requin.amp()> 60){ | ||||||
|  |        requin.balaye(0); | ||||||
|  |        bougie.Vert(); | ||||||
|  |      } | ||||||
|  |       else | ||||||
|  |       { | ||||||
|  |            requin.balaye(0.5); | ||||||
|  |       } | ||||||
|  |      } | ||||||
|  |      else if(requin.encodeur()>=510){ | ||||||
|  |      requin.rotationer(0.5); | ||||||
|  |      } | ||||||
|  |      else{ | ||||||
|  |       requin.rotationer(-0.5); | ||||||
|  |      } | ||||||
|  |      | ||||||
|  |    } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     requin.rotationer(0); | ||||||
|  |     requin.balaye(0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										40
									
								
								src/main/java/frc/robot/commands/BalayeuseBas.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										40
									
								
								src/main/java/frc/robot/commands/BalayeuseBas.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.commands; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.wpilibj2.command.Command; | ||||||
|  | import frc.robot.subsystems.Requin; | ||||||
|  |  | ||||||
|  | /* 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 BalayeuseBas extends Command { | ||||||
|  |   private Requin requin; | ||||||
|  |   /** Creates a new Balayeuse. */ | ||||||
|  |   public BalayeuseBas(Requin requin) { | ||||||
|  |     this.requin = requin; | ||||||
|  |     addRequirements(requin); | ||||||
|  |     // 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() { | ||||||
|  |   requin.rotationer(-0.5); | ||||||
|  |   } | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     requin.rotationer(0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										67
									
								
								src/main/java/frc/robot/commands/BalayeuseCoral.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										67
									
								
								src/main/java/frc/robot/commands/BalayeuseCoral.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,67 @@ | |||||||
|  | // 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.Requin; | ||||||
|  |  | ||||||
|  | /* 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 BalayeuseCoral extends Command { | ||||||
|  |   private Requin requin; | ||||||
|  |   private Bougie bougie; | ||||||
|  |   /** Creates a new Balayeuse. */ | ||||||
|  |   public BalayeuseCoral(Requin requin, Bougie bougie) { | ||||||
|  |     this.requin = requin; | ||||||
|  |     this.bougie = bougie; | ||||||
|  |     addRequirements(requin,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(requin.encodeur()>=100 &&  requin.encodeur()<=110){ | ||||||
|  |        requin.rotationer(0); | ||||||
|  |       if(requin.amp()>60){ | ||||||
|  |       requin.balaye(0); | ||||||
|  |        bougie.Vert(); | ||||||
|  |        if(requin.enHaut()){ | ||||||
|  |         requin.rotationer(0); | ||||||
|  |        } | ||||||
|  |         else{ | ||||||
|  |           requin.rotationer(0.5); | ||||||
|  |         } | ||||||
|  |     } | ||||||
|  |      else{ | ||||||
|  |        requin.balaye(0.5); | ||||||
|  |      } | ||||||
|  |      } | ||||||
|  |      else if(requin.encodeur()>=110){ | ||||||
|  |      requin.rotationer(0.5); | ||||||
|  |      } | ||||||
|  |      else{ | ||||||
|  |        requin.rotationer(-0.5); | ||||||
|  |      } | ||||||
|  |      | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     requin.rotationer(0); | ||||||
|  |     requin.balaye(0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										47
									
								
								src/main/java/frc/robot/commands/BalayeuseHaut.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										47
									
								
								src/main/java/frc/robot/commands/BalayeuseHaut.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.Requin; | ||||||
|  |  | ||||||
|  | /* 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 BalayeuseHaut extends Command { | ||||||
|  |   private Requin requin; | ||||||
|  |   /** Creates a new Balayeuse. */ | ||||||
|  |   public BalayeuseHaut(Requin requin) { | ||||||
|  |     this.requin = requin; | ||||||
|  |     addRequirements(requin); | ||||||
|  |     // 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(requin.enHaut()==true){ | ||||||
|  |       requin.rotationer(0); | ||||||
|  |       requin.reset(); | ||||||
|  |     } | ||||||
|  |     else{ | ||||||
|  |       requin.rotationer(-0.5); | ||||||
|  |     } | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     requin.rotationer(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; | ||||||
|  |   } | ||||||
|  | } | ||||||
| @@ -0,0 +1,46 @@ | |||||||
|  | // 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.Elevateur; | ||||||
|  |  | ||||||
|  | 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()) | ||||||
|  |     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; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										78
									
								
								src/main/java/frc/robot/commands/Elevateur/L2.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										78
									
								
								src/main/java/frc/robot/commands/Elevateur/L2.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,78 @@ | |||||||
|  | // 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.Elevateur; | ||||||
|  | import edu.wpi.first.networktables.DoubleSubscriber; | ||||||
|  | import edu.wpi.first.networktables.NetworkTable; | ||||||
|  | import edu.wpi.first.networktables.NetworkTableInstance; | ||||||
|  | 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; | ||||||
|  |  | ||||||
|  |   NetworkTableInstance networktable = NetworkTableInstance.getDefault(); | ||||||
|  |   NetworkTable tabelevateur = networktable.getTable("tabelevateur"); | ||||||
|  |   private DoubleSubscriber encodeur1 = tabelevateur.getDoubleTopic("encodeurelevateurbasL2").subscribe(-1); | ||||||
|  |   private DoubleSubscriber encodeur2 = tabelevateur.getDoubleTopic("encodeurelevateurhautL2").subscribe(-0.9); | ||||||
|  |   private DoubleSubscriber encodeur3 = tabelevateur.getDoubleTopic("encodeurpincebasL2").subscribe(-1); | ||||||
|  |   private DoubleSubscriber encodeur4 = tabelevateur.getDoubleTopic("encodeurpinceautL2").subscribe(-0.9); | ||||||
|  |   /** 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() { | ||||||
|  |     double encodeurbase = encodeur1.get(); | ||||||
|  |     double encodeurhaute = encodeur2.get(); | ||||||
|  |     double encodeurbasp = encodeur3.get(); | ||||||
|  |     double encodeurhautp = encodeur4.get(); | ||||||
|  |     if(elevateur.position()<=encodeurbase && elevateur.position()>=-encodeurhaute){ | ||||||
|  |       elevateur.vitesse(0); | ||||||
|  |     } | ||||||
|  |     else if(elevateur.position()>=encodeurbase){ | ||||||
|  |       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; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										76
									
								
								src/main/java/frc/robot/commands/Elevateur/L3.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										76
									
								
								src/main/java/frc/robot/commands/Elevateur/L3.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,76 @@ | |||||||
|  | // 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.Elevateur; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.networktables.DoubleSubscriber; | ||||||
|  | import edu.wpi.first.networktables.NetworkTable; | ||||||
|  | import edu.wpi.first.networktables.NetworkTableInstance; | ||||||
|  | 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; | ||||||
|  |     NetworkTableInstance networktable = NetworkTableInstance.getDefault(); | ||||||
|  |   NetworkTable tabelevateur = networktable.getTable("tabelevateur"); | ||||||
|  |   private DoubleSubscriber encodeur1 = tabelevateur.getDoubleTopic("encodeurhautL3").subscribe(-2.9); | ||||||
|  |   private DoubleSubscriber encodeur2 = tabelevateur.getDoubleTopic("encodeurbasL3").subscribe(-3); | ||||||
|  |   private DoubleSubscriber encodeur3 = tabelevateur.getDoubleTopic("encodeurpincebasL3").subscribe(-1); | ||||||
|  |   private DoubleSubscriber encodeur4 = tabelevateur.getDoubleTopic("encodeurpincehautL3").subscribe(-0.9); | ||||||
|  |   /** 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() { | ||||||
|  |     double encodeurHaute = encodeur1.get(); | ||||||
|  |     double encodeurBase = encodeur2.get(); | ||||||
|  |     double encodeurbase = encodeur3.get(); | ||||||
|  |     double encodeurhaute = encodeur4.get(); | ||||||
|  |     if(elevateur.position()<=-encodeurHaute && elevateur.position()>=encodeurBase){ | ||||||
|  |       elevateur.vitesse(0); | ||||||
|  |     } | ||||||
|  |     else if(elevateur.position()>=-encodeurHaute){ | ||||||
|  |       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; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										79
									
								
								src/main/java/frc/robot/commands/Elevateur/L4.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										79
									
								
								src/main/java/frc/robot/commands/Elevateur/L4.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,79 @@ | |||||||
|  | // 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.Elevateur; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.networktables.DoubleSubscriber; | ||||||
|  | import edu.wpi.first.networktables.DoubleTopic; | ||||||
|  | import edu.wpi.first.networktables.NetworkTable; | ||||||
|  | import edu.wpi.first.networktables.NetworkTableInstance; | ||||||
|  | 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; | ||||||
|  |   NetworkTableInstance networktable = NetworkTableInstance.getDefault(); | ||||||
|  |   NetworkTable tabelevateur = networktable.getTable("tabelevateur"); | ||||||
|  |   private DoubleTopic encodeur1topic = tabelevateur.getDoubleTopic("encodeurbasL4"); | ||||||
|  |   DoubleSubscriber encodeur1 = encodeur1topic.subscribe(-6.4); | ||||||
|  |   private DoubleSubscriber encodeur2 = tabelevateur.getDoubleTopic("encodeurhautL4").subscribe(-6.5); | ||||||
|  |   private DoubleSubscriber encodeur3 = tabelevateur.getDoubleTopic("encodeurpincebasL4").subscribe(-1); | ||||||
|  |   private DoubleSubscriber encodeur4 = tabelevateur.getDoubleTopic("encodeurpincehautL4").subscribe(-0.9); | ||||||
|  |   /** Creates a new L2. */ | ||||||
|  |   public L4(Elevateur elevateur,Pince pince) { | ||||||
|  |     this.elevateur = elevateur; | ||||||
|  |     this.pince = pince; | ||||||
|  |     encodeur1topic.setPersistent(true); | ||||||
|  |     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() { | ||||||
|  |     double encodeurBase = encodeur1.get(); | ||||||
|  |     double encodeurhaute = encodeur2.get(); | ||||||
|  |     double encodeurbasp = encodeur3.get(); | ||||||
|  |     double encodeurhautp = encodeur4.get(); | ||||||
|  |     if(elevateur.position()<=encodeurhaute && elevateur.position()>=encodeurBase){ | ||||||
|  |       elevateur.vitesse(0); | ||||||
|  |     } | ||||||
|  |     else if(elevateur.position()>=encodeurhaute){ | ||||||
|  |       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; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										41
									
								
								src/main/java/frc/robot/commands/ExpireAlgue.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										41
									
								
								src/main/java/frc/robot/commands/ExpireAlgue.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.Requin; | ||||||
|  |  | ||||||
|  | /* 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 ExpireAlgue extends Command { | ||||||
|  |   private Requin requin; | ||||||
|  |   /** Creates a new ExpireAlgue. */ | ||||||
|  |   public ExpireAlgue(Requin requin) { | ||||||
|  |     this.requin = requin; | ||||||
|  |     addRequirements(requin); | ||||||
|  |     // 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() { | ||||||
|  |     requin.balaye(0.5); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     requin.balaye(0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										65
									
								
								src/main/java/frc/robot/commands/L1Requin.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										65
									
								
								src/main/java/frc/robot/commands/L1Requin.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.Bougie; | ||||||
|  | import frc.robot.subsystems.Requin; | ||||||
|  |  | ||||||
|  | /* 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 L1Requin extends Command { | ||||||
|  |   private Requin requin; | ||||||
|  |   private Bougie bougie; | ||||||
|  |   /** Creates a new Balayeuse. */ | ||||||
|  |   public L1Requin(Requin requin,Bougie bougie) { | ||||||
|  |     this.requin = requin; | ||||||
|  |     this.bougie = bougie; | ||||||
|  |     addRequirements(requin,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(requin.encodeur()>=800 &&  requin.encodeur()<=810){ | ||||||
|  |       requin.rotationer(0); | ||||||
|  |       if(requin.amp()>8){ | ||||||
|  |       requin.balaye(-0.5); | ||||||
|  |     } | ||||||
|  |         else{ | ||||||
|  |           requin.balaye(0);  | ||||||
|  |           bougie.Rouge(); | ||||||
|  |       } | ||||||
|  |     } | ||||||
|  |     else if(requin.encodeur()>=810){ | ||||||
|  |     requin.rotationer(0.5); | ||||||
|  |     } | ||||||
|  |     else{ | ||||||
|  |       requin.rotationer(-0.5); | ||||||
|  |     } | ||||||
|  |      | ||||||
|  |      | ||||||
|  |        | ||||||
|  |      | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     requin.rotationer(0); | ||||||
|  |     requin.balaye(0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										41
									
								
								src/main/java/frc/robot/commands/Pince/Algue1Test.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										41
									
								
								src/main/java/frc/robot/commands/Pince/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.Pince; | ||||||
|  |  | ||||||
|  | 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/Pince/Algue2Test.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										41
									
								
								src/main/java/frc/robot/commands/Pince/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.Pince; | ||||||
|  |  | ||||||
|  | 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/Pince/AlgueExpire.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										51
									
								
								src/main/java/frc/robot/commands/Pince/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.Pince; | ||||||
|  |  | ||||||
|  | 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/Pince/Algue_inspire.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										44
									
								
								src/main/java/frc/robot/commands/Pince/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.Pince; | ||||||
|  |  | ||||||
|  | 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/Pince/CorailAspir.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										42
									
								
								src/main/java/frc/robot/commands/Pince/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.Pince; | ||||||
|  |  | ||||||
|  | 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/Pince/CorailTest.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										41
									
								
								src/main/java/frc/robot/commands/Pince/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.Pince; | ||||||
|  |  | ||||||
|  | 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; | ||||||
|  |   } | ||||||
|  | } | ||||||
| @@ -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.Pince; | ||||||
|  |  | ||||||
|  | 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/Pince/CoralExpire.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										49
									
								
								src/main/java/frc/robot/commands/Pince/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.Pince; | ||||||
|  |  | ||||||
|  | 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; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										47
									
								
								src/main/java/frc/robot/commands/Pince/DepartPince.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										47
									
								
								src/main/java/frc/robot/commands/Pince/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.Pince; | ||||||
|  |  | ||||||
|  | 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; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										50
									
								
								src/main/java/frc/robot/commands/Pince/PinceManuel.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										50
									
								
								src/main/java/frc/robot/commands/Pince/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.Pince; | ||||||
|  | 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; | ||||||
|  |   } | ||||||
|  | } | ||||||
| @@ -9,8 +9,8 @@ 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 */ | /* 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 RainBow extends Command { | public class RainBow extends Command { | ||||||
|   Bougie bougie; |  | ||||||
|   /** Creates a new RainBow. */ |   /** Creates a new RainBow. */ | ||||||
|  |   private Bougie bougie; | ||||||
|   public RainBow(Bougie bougie) { |   public RainBow(Bougie bougie) { | ||||||
|     this.bougie = bougie; |     this.bougie = bougie; | ||||||
|     addRequirements(bougie); |     addRequirements(bougie); | ||||||
|   | |||||||
							
								
								
									
										77
									
								
								src/main/java/frc/robot/commands/StationPince.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										77
									
								
								src/main/java/frc/robot/commands/StationPince.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,77 @@ | |||||||
|  | // 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.networktables.DoubleSubscriber; | ||||||
|  | import edu.wpi.first.networktables.NetworkTable; | ||||||
|  | import edu.wpi.first.networktables.NetworkTableInstance; | ||||||
|  | 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; | ||||||
|  |   NetworkTableInstance networktable = NetworkTableInstance.getDefault(); | ||||||
|  |   NetworkTable tabelevateur = networktable.getTable("tabelevateur"); | ||||||
|  |   private DoubleSubscriber encodeur1 = tabelevateur.getDoubleTopic("encodeur bas Station").subscribe(-0.5); | ||||||
|  |   private DoubleSubscriber encodeur2 = tabelevateur.getDoubleTopic("encodeur haut Station").subscribe(-0.4); | ||||||
|  |   private DoubleSubscriber encodeur3 = tabelevateur.getDoubleTopic("encodeur pince bas Station").subscribe(-1); | ||||||
|  |   private DoubleSubscriber encodeur4 = tabelevateur.getDoubleTopic("encodeur pince haut Station").subscribe(-0.9); | ||||||
|  |   /** 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() { | ||||||
|  |     double encodeurBase = encodeur1.get(); | ||||||
|  |     double encodeurhaute = encodeur2.get(); | ||||||
|  |     double encodeurbasp = encodeur3.get(); | ||||||
|  |     double encodeurhautp = encodeur4.get(); | ||||||
|  |     pince.aspirecoral(0.5); | ||||||
|  |     if(pince.encodeurpivot()<=encodeurBase && pince.encodeurpivot()>=encodeurhaute){ | ||||||
|  |       pince.pivote(0); | ||||||
|  |     } | ||||||
|  |     else if(pince.encodeurpivot()>=encodeurBase){ | ||||||
|  |       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; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										41
									
								
								src/main/java/frc/robot/commands/aspire.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										41
									
								
								src/main/java/frc/robot/commands/aspire.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.Requin; | ||||||
|  |  | ||||||
|  | /* 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 aspire extends Command { | ||||||
|  |   /** Creates a new aspire. */ | ||||||
|  |   private Requin requin; | ||||||
|  |   public aspire(Requin requin) { | ||||||
|  |     // Use addRequirements() here to declare subsystem dependencies. | ||||||
|  |     this.requin = requin; | ||||||
|  |     addRequirements(requin); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // 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() { | ||||||
|  |     requin.balaye(0.3); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     requin.balaye(0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										41
									
								
								src/main/java/frc/robot/commands/exspire.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										41
									
								
								src/main/java/frc/robot/commands/exspire.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.Requin; | ||||||
|  |  | ||||||
|  | /* 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 exspire extends Command { | ||||||
|  |   /** Creates a new aspire. */ | ||||||
|  |   private Requin requin; | ||||||
|  |   public exspire(Requin requin) { | ||||||
|  |     // Use addRequirements() here to declare subsystem dependencies. | ||||||
|  |     this.requin = requin; | ||||||
|  |     addRequirements(requin); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // 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() { | ||||||
|  |     requin.balaye(-0.3); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     requin.balaye(0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										56
									
								
								src/main/java/frc/robot/commands/grimpeur/GrimperHaut.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										56
									
								
								src/main/java/frc/robot/commands/grimpeur/GrimperHaut.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,56 @@ | |||||||
|  | // 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.grimpeur; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.wpilibj2.command.Command; | ||||||
|  | import frc.robot.subsystems.Bougie; | ||||||
|  | import frc.robot.subsystems.Grimpeur; | ||||||
|  |  | ||||||
|  | /* 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 GrimperHaut extends Command { | ||||||
|  |   private Grimpeur grimpeur; | ||||||
|  |   private Bougie bougie; | ||||||
|  |   /** Creates a new Grimper. */ | ||||||
|  |   public GrimperHaut(Grimpeur grimpeur, Bougie bougie) { | ||||||
|  |     this.grimpeur = grimpeur; | ||||||
|  |     this.bougie = bougie; | ||||||
|  |     addRequirements(grimpeur,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(grimpeur.stop()==true){ | ||||||
|  |       grimpeur.grimpe(0); | ||||||
|  |       grimpeur.reset(); | ||||||
|  |       bougie.RainBow(); | ||||||
|  |     } | ||||||
|  |     else{ | ||||||
|  |       grimpeur.grimpe(0.5); | ||||||
|  |       bougie.RainBowStop(); | ||||||
|  |     } | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     grimpeur.grimpe(0); | ||||||
|  |    if(grimpeur.stop()){ | ||||||
|  |     bougie.RainBow(); | ||||||
|  |    } | ||||||
|  |  | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return grimpeur.stop()==true; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										57
									
								
								src/main/java/frc/robot/commands/grimpeur/GrimpeurBas.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										57
									
								
								src/main/java/frc/robot/commands/grimpeur/GrimpeurBas.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,57 @@ | |||||||
|  | // 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.grimpeur; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.networktables.DoubleSubscriber; | ||||||
|  | import edu.wpi.first.networktables.NetworkTable; | ||||||
|  | import edu.wpi.first.networktables.NetworkTableInstance; | ||||||
|  | import edu.wpi.first.wpilibj2.command.Command; | ||||||
|  | import frc.robot.subsystems.Grimpeur; | ||||||
|  |  | ||||||
|  | /* 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 GrimpeurBas extends Command { | ||||||
|  |   private Grimpeur grimpeur; | ||||||
|  |    NetworkTableInstance networktable = NetworkTableInstance.getDefault(); | ||||||
|  |   NetworkTable tabelevateur = networktable.getTable("tabelevateur"); | ||||||
|  |   private DoubleSubscriber encodeur1 = tabelevateur.getDoubleTopic("encodeurgrimpeurbas").subscribe(-39.19); | ||||||
|  |   private DoubleSubscriber encodeur2 = tabelevateur.getDoubleTopic("encodeurgrimpeurhaut ").subscribe(-38.5); | ||||||
|  |   /** Creates a new GrimpeurBas. */ | ||||||
|  |   public GrimpeurBas(Grimpeur grimpeur) { | ||||||
|  |     this.grimpeur = grimpeur; | ||||||
|  |     addRequirements(grimpeur); | ||||||
|  |     // 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() { | ||||||
|  |     double encodeurbas = encodeur1.get(); | ||||||
|  |     double encodeurhaut = encodeur2.get(); | ||||||
|  |     if(grimpeur.encodeur()>=encodeurhaut && grimpeur.encodeur()<=encodeurbas){ | ||||||
|  |       grimpeur.grimpe(0); | ||||||
|  |     } | ||||||
|  |     else if(grimpeur.encodeur()>=encodeurhaut){ | ||||||
|  |       grimpeur.grimpe(-0.5); | ||||||
|  |     } | ||||||
|  |    else{grimpeur.grimpe(0.5); | ||||||
|  |   }  | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     grimpeur.grimpe(0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
| @@ -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.grimpeur; | ||||||
|  |  | ||||||
|  | import java.util.function.DoubleSupplier; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.wpilibj2.command.Command; | ||||||
|  | import frc.robot.subsystems.Grimpeur; | ||||||
|  |  | ||||||
|  | /* 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 GrimpeurManuel extends Command { | ||||||
|  |   private Grimpeur grimpeur; | ||||||
|  |   private DoubleSupplier x; | ||||||
|  |   /** Creates a new GrimpeurManuel. */ | ||||||
|  |   public GrimpeurManuel(Grimpeur grimpeur,DoubleSupplier x) { | ||||||
|  |     this.grimpeur = grimpeur; | ||||||
|  |     this.x = x; | ||||||
|  |     addRequirements(grimpeur); | ||||||
|  |     // 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(grimpeur.stop()){ | ||||||
|  |       grimpeur.grimpe(0); | ||||||
|  |     } | ||||||
|  |     else{ | ||||||
|  |     grimpeur.grimpe(x.getAsDouble());   | ||||||
|  |     } | ||||||
|  |      | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     grimpeur.grimpe(0); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Returns true when the command should end. | ||||||
|  |   @Override | ||||||
|  |   public boolean isFinished() { | ||||||
|  |     return false; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										39
									
								
								src/main/java/frc/robot/commands/grimpeur/ResetGrimpeur.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										39
									
								
								src/main/java/frc/robot/commands/grimpeur/ResetGrimpeur.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,39 @@ | |||||||
|  | // 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.grimpeur; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.wpilibj2.command.Command; | ||||||
|  | import frc.robot.subsystems.Grimpeur; | ||||||
|  |  | ||||||
|  | /* 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 ResetGrimpeur extends Command { | ||||||
|  |   private Grimpeur grimpeur; | ||||||
|  |   /** Creates a new ResetGrimpeur. */ | ||||||
|  |   public ResetGrimpeur(Grimpeur grimpeur) { | ||||||
|  |     this.grimpeur = grimpeur; | ||||||
|  |     addRequirements(grimpeur); | ||||||
|  |     // 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() { | ||||||
|  |     grimpeur.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; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										49
									
								
								src/main/java/frc/robot/commands/requin_manuel.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										49
									
								
								src/main/java/frc/robot/commands/requin_manuel.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 java.util.function.DoubleSupplier; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.wpilibj2.command.Command; | ||||||
|  | import frc.robot.subsystems.Requin; | ||||||
|  |  | ||||||
|  | /* 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 requin_manuel extends Command { | ||||||
|  |   /** Creates a new requin_manuel. */ | ||||||
|  |   private Requin requin; | ||||||
|  |   private DoubleSupplier x; | ||||||
|  |   public requin_manuel(Requin requin) { | ||||||
|  |     // Use addRequirements() here to declare subsystem dependencies. | ||||||
|  |     this.requin = requin; | ||||||
|  |     addRequirements(requin); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // 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(requin.enHaut()){ | ||||||
|  |     requin.rotationer(0);   | ||||||
|  |     } | ||||||
|  |     else{ | ||||||
|  |       requin.rotationer(x.getAsDouble()); | ||||||
|  |     } | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called once the command ends or is interrupted. | ||||||
|  |   @Override | ||||||
|  |   public void end(boolean interrupted) { | ||||||
|  |     requin.rotationer(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, Pince pince) { | ||||||
|  |     // 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; | import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||||||
|  |  | ||||||
| public class Bougie extends SubsystemBase { | public class Bougie extends SubsystemBase { | ||||||
|   CANdle candle = new CANdle(5); |   CANdle candle = new CANdle(23); | ||||||
|   CANdleConfiguration config = new CANdleConfiguration(); |   CANdleConfiguration config = new CANdleConfiguration(); | ||||||
|   RainbowAnimation rainbowAnim = new RainbowAnimation(1, 0.5, 64); |   RainbowAnimation rainbowAnim = new RainbowAnimation(1, 0.5, 64); | ||||||
|   /** Creates a new Bougie. */ |   /** Creates a new Bougie. */ | ||||||
| @@ -20,19 +20,37 @@ public class Bougie extends SubsystemBase { | |||||||
|     candle.configAllSettings(config); |     candle.configAllSettings(config); | ||||||
|   } |   } | ||||||
|   public void Rouge() { |   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() { |   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() { |   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); | ||||||
|   } |   } | ||||||
|   public void RainBow(){candle.animate(rainbowAnim);} |  | ||||||
|   public void RainBowStop(){candle.animate(null);} |  | ||||||
|   @Override |   @Override | ||||||
|   public void periodic() { |   public void periodic() { | ||||||
|     // This method will be called once per scheduler run |     // 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 | ||||||
|  |   } | ||||||
|  | } | ||||||
| @@ -4,20 +4,34 @@ | |||||||
|  |  | ||||||
| package frc.robot.subsystems; | package frc.robot.subsystems; | ||||||
|  |  | ||||||
|  | import com.revrobotics.spark.SparkMax; | ||||||
|  | import com.revrobotics.spark.SparkLowLevel.MotorType; | ||||||
|  |  | ||||||
| import edu.wpi.first.wpilibj.DigitalInput; | import edu.wpi.first.wpilibj.DigitalInput; | ||||||
| import edu.wpi.first.wpilibj.motorcontrol.Spark; | import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; | ||||||
|  | import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; | ||||||
| import edu.wpi.first.wpilibj2.command.SubsystemBase; | import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||||||
|  |  | ||||||
| public class Grimpeur extends SubsystemBase { | public class Grimpeur extends SubsystemBase { | ||||||
|   /** Creates a new Grimpeur. */ |   /** Creates a new Grimpeur. */ | ||||||
|   public Grimpeur() {} |   ShuffleboardTab teb = Shuffleboard.getTab("teb"); | ||||||
|   final Spark grimpeur = new Spark(0); |   public Grimpeur() { | ||||||
|   final DigitalInput limit1 = new DigitalInput(0); |     teb.addBoolean("limit grimpeur", this::stop); | ||||||
|  |     teb.addDouble("encodeur grimpeur", this::encodeur); | ||||||
|  |   } | ||||||
|  |   final SparkMax grimpeur = new SparkMax(21,MotorType.kBrushless); | ||||||
|  |   final DigitalInput limit1 = new DigitalInput(2); | ||||||
|   public void grimpe(double vitesse){ |   public void grimpe(double vitesse){ | ||||||
|     grimpeur.set(vitesse); |     grimpeur.set(vitesse); | ||||||
|   } |   } | ||||||
|   final void stop(){ |   public boolean stop(){ | ||||||
|     limit1.get(); |    return limit1.get(); | ||||||
|  |   } | ||||||
|  |   public double encodeur(){ | ||||||
|  |   return grimpeur.getEncoder().getPosition(); | ||||||
|  |   } | ||||||
|  |   public void reset(){ | ||||||
|  |      grimpeur.getEncoder().setPosition(0); | ||||||
|     } |     } | ||||||
|   @Override |   @Override | ||||||
|   public void periodic() { |   public void periodic() { | ||||||
|   | |||||||
							
								
								
									
										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 | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										48
									
								
								src/main/java/frc/robot/subsystems/Requin.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										48
									
								
								src/main/java/frc/robot/subsystems/Requin.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.subsystems; | ||||||
|  |  | ||||||
|  | import com.revrobotics.spark.SparkFlex; | ||||||
|  | import com.revrobotics.spark.SparkMax; | ||||||
|  | import com.revrobotics.spark.SparkLowLevel.MotorType; | ||||||
|  | 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 Requin extends SubsystemBase { | ||||||
|  |   /** Creates a new Requin. */ | ||||||
|  |   ShuffleboardTab teb = Shuffleboard.getTab("teb"); | ||||||
|  |   public Requin() { | ||||||
|  |     teb.addBoolean("limit requin", this::enHaut); | ||||||
|  |   } | ||||||
|  |     | ||||||
|  |   final SparkFlex balaye = new SparkFlex(15, MotorType.kBrushless); | ||||||
|  |   final SparkMax rotatione = new SparkMax(17, MotorType.kBrushless); | ||||||
|  |   final DigitalInput limit3 = new DigitalInput(1); | ||||||
|  |      | ||||||
|  |   public void balaye(double vitesse){ | ||||||
|  |     balaye.set(vitesse); | ||||||
|  |   } | ||||||
|  |   public void rotationer(double vitesse){ | ||||||
|  |   rotatione.set(vitesse); | ||||||
|  |   } | ||||||
|  |   public boolean enHaut(){ | ||||||
|  |   return limit3.get(); | ||||||
|  |   }  | ||||||
|  |   public double encodeur(){ | ||||||
|  |   return rotatione.getEncoder().getPosition(); | ||||||
|  |   } | ||||||
|  |   public void reset(){ | ||||||
|  |     rotatione.getEncoder().setPosition(0); | ||||||
|  |   } | ||||||
|  |   public double amp(){ | ||||||
|  |     return balaye.getOutputCurrent(); | ||||||
|  |   } | ||||||
|  |   @Override | ||||||
|  |   public void periodic() { | ||||||
|  |     // This method will be called once per scheduler run | ||||||
|  |   } | ||||||
|  | } | ||||||
		Reference in New Issue
	
	Block a user