Compare commits
	
		
			6 Commits
		
	
	
		
			elevateur
			...
			7848c4aaf2
		
	
	| Author | SHA1 | Date | |
|---|---|---|---|
|  | 7848c4aaf2 | ||
|  | 1d1d6e962d | ||
|  | d6420659e9 | ||
|  | aafb2a62b5 | ||
|  | 017f168b3c | ||
|  | 5ffa28596c | 
							
								
								
									
										41
									
								
								src/main/java/frc/robot/command/AlgueExpire.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										41
									
								
								src/main/java/frc/robot/command/AlgueExpire.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.command; | ||||||
|  |  | ||||||
|  | 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 AlgueExpire extends Command { | ||||||
|  |   private Pince pince; | ||||||
|  |   /** Creates a new CoralAlgue. */ | ||||||
|  |   public AlgueExpire(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.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; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										49
									
								
								src/main/java/frc/robot/command/CoralAlgueInspire.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										49
									
								
								src/main/java/frc/robot/command/CoralAlgueInspire.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.command; | ||||||
|  |  | ||||||
|  | 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 CoralAlgueInspire extends Command { | ||||||
|  |   private Pince pince; | ||||||
|  |   /** Creates a new CoralAlgue. */ | ||||||
|  |   public CoralAlgueInspire(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(-.5); | ||||||
|  |     if(pince.emperagealgue()>8){ | ||||||
|  |       pince.aspirealgue(0); | ||||||
|  |      }  | ||||||
|  |      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; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										41
									
								
								src/main/java/frc/robot/command/CoralExpire.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										41
									
								
								src/main/java/frc/robot/command/CoralExpire.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.command; | ||||||
|  |  | ||||||
|  | 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 CoralExpire extends Command { | ||||||
|  |   private Pince pince; | ||||||
|  |   /** Creates a new CoralAlgue. */ | ||||||
|  |   public CoralExpire(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(.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; | ||||||
|  |   } | ||||||
|  | } | ||||||
| @@ -2,18 +2,18 @@ | |||||||
| // Open Source Software; you can modify and/or share it under the terms of | // 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. | // the WPILib BSD license file in the root directory of this project. | ||||||
| 
 | 
 | ||||||
| package frc.robot.commands; | package frc.robot.command; | ||||||
| 
 | 
 | ||||||
| import edu.wpi.first.wpilibj2.command.Command; | 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 */ | /* 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 { | public class CoralInspire extends Command { | ||||||
|   private Elevateur elevateur; |   private Pince pince; | ||||||
|   /** Creates a new L2. */ |   /** Creates a new CoralAlgue. */ | ||||||
|   public Depart(Elevateur elevateur) { |   public CoralInspire(Pince pince) { | ||||||
|     this.elevateur = elevateur; |     this.pince = pince; | ||||||
|     addRequirements(elevateur); |     addRequirements(pince); | ||||||
|     // Use addRequirements() here to declare subsystem dependencies. |     // Use addRequirements() here to declare subsystem dependencies. | ||||||
|   } |   } | ||||||
| 
 | 
 | ||||||
| @@ -24,24 +24,23 @@ public class Depart extends Command { | |||||||
|   // Called every time the scheduler runs while the command is scheduled. |   // Called every time the scheduler runs while the command is scheduled. | ||||||
|   @Override |   @Override | ||||||
|   public void execute() { |   public void execute() { | ||||||
|     if(elevateur.limit2()==true){ |     if(pince.emperagecoral()>8){ | ||||||
|       elevateur.vitesse(0); |     pince.aspirecoral(0);   | ||||||
|       elevateur.reset(); |  | ||||||
|     } |     } | ||||||
|     else{ |     else{ | ||||||
|       elevateur.vitesse(-.5); |       pince.aspirecoral(.5); | ||||||
|     } |     } | ||||||
|   } |   } | ||||||
| 
 | 
 | ||||||
|   // Called once the command ends or is interrupted. |   // Called once the command ends or is interrupted. | ||||||
|   @Override |   @Override | ||||||
|   public void end(boolean interrupted) { |   public void end(boolean interrupted) { | ||||||
|     elevateur.vitesse(0); |     pince.aspirecoral(0); | ||||||
|   } |   } | ||||||
| 
 | 
 | ||||||
|   // Returns true when the command should end. |   // Returns true when the command should end. | ||||||
|   @Override |   @Override | ||||||
|   public boolean isFinished() { |   public boolean isFinished() { | ||||||
|     return elevateur.limit2()==true; |     return false; | ||||||
|   } |   } | ||||||
| } | } | ||||||
							
								
								
									
										47
									
								
								src/main/java/frc/robot/command/DepartPince.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										47
									
								
								src/main/java/frc/robot/command/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.command; | ||||||
|  |  | ||||||
|  | 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(.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; | ||||||
|  |   } | ||||||
|  | } | ||||||
| @@ -2,18 +2,18 @@ | |||||||
| // Open Source Software; you can modify and/or share it under the terms of | // 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. | // the WPILib BSD license file in the root directory of this project. | ||||||
| 
 | 
 | ||||||
| package frc.robot.commands; | package frc.robot.command; | ||||||
| 
 | 
 | ||||||
| import edu.wpi.first.wpilibj2.command.Command; | 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 */ | /* 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 { | public class L2Pince extends Command { | ||||||
|   private Elevateur elevateur; |   private Pince pince; | ||||||
|   /** Creates a new L2. */ |   /** Creates a new L2Pince. */ | ||||||
|   public L3(Elevateur elevateur) { |   public L2Pince(Pince pince) { | ||||||
|     this.elevateur = elevateur; |     this.pince = pince; | ||||||
|     addRequirements(elevateur); |     addRequirements(pince); | ||||||
|     // Use addRequirements() here to declare subsystem dependencies. |     // Use addRequirements() here to declare subsystem dependencies. | ||||||
|   } |   } | ||||||
| 
 | 
 | ||||||
| @@ -24,21 +24,21 @@ public class L3 extends Command { | |||||||
|   // Called every time the scheduler runs while the command is scheduled. |   // Called every time the scheduler runs while the command is scheduled. | ||||||
|   @Override |   @Override | ||||||
|   public void execute() { |   public void execute() { | ||||||
|     if(elevateur.position()>=700 && elevateur.position()<=710){ |     if(pince.encodeurpivot()>=500 && pince.encodeurpivot()<=510){ | ||||||
|       elevateur.vitesse(0); |       pince.pivote(0); | ||||||
|     } |     } | ||||||
|     else if(elevateur.position()>=510){ |     else if(pince.encodeurpivot()>=510){ | ||||||
|       elevateur.vitesse(-0.5); |       pince.pivote(-0.3); | ||||||
|     } |     } | ||||||
|     else{ |     else{ | ||||||
|       elevateur.vitesse(.5); |       pince.pivote(0.3); | ||||||
|     } |     } | ||||||
|   } |   } | ||||||
| 
 | 
 | ||||||
|   // Called once the command ends or is interrupted. |   // Called once the command ends or is interrupted. | ||||||
|   @Override |   @Override | ||||||
|   public void end(boolean interrupted) { |   public void end(boolean interrupted) { | ||||||
|     elevateur.vitesse(0); |     pince.pivote(0); | ||||||
|   } |   } | ||||||
| 
 | 
 | ||||||
|   // Returns true when the command should end. |   // Returns true when the command should end. | ||||||
| @@ -2,18 +2,18 @@ | |||||||
| // Open Source Software; you can modify and/or share it under the terms of | // 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. | // the WPILib BSD license file in the root directory of this project. | ||||||
| 
 | 
 | ||||||
| package frc.robot.commands; | package frc.robot.command; | ||||||
| 
 | 
 | ||||||
| import edu.wpi.first.wpilibj2.command.Command; | 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 */ | /* 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 { | public class L3Pince extends Command { | ||||||
|   private Elevateur elevateur; |   private Pince pince; | ||||||
|   /** Creates a new L2. */ |   /** Creates a new L2Pince. */ | ||||||
|   public L2(Elevateur elevateur) { |   public L3Pince(Pince pince) { | ||||||
|     this.elevateur = elevateur; |     this.pince = pince; | ||||||
|     addRequirements(elevateur); |     addRequirements(pince); | ||||||
|     // Use addRequirements() here to declare subsystem dependencies. |     // Use addRequirements() here to declare subsystem dependencies. | ||||||
|   } |   } | ||||||
| 
 | 
 | ||||||
| @@ -24,22 +24,21 @@ public class L2 extends Command { | |||||||
|   // Called every time the scheduler runs while the command is scheduled. |   // Called every time the scheduler runs while the command is scheduled. | ||||||
|   @Override |   @Override | ||||||
|   public void execute() { |   public void execute() { | ||||||
|     if(elevateur.position()>=500 && elevateur.position()<=510){ |     if(pince.encodeurpivot()>=700 && pince.encodeurpivot()<=710){ | ||||||
|       elevateur.vitesse(0); |       pince.pivote(0); | ||||||
|     } |     } | ||||||
|     else if(elevateur.position()>=510){ |     else if(pince.encodeurpivot()>=710){ | ||||||
|       elevateur.vitesse(-0.3); |       pince.pivote(-0.5); | ||||||
|     } |     } | ||||||
|     else{ |     else{ | ||||||
|       elevateur.vitesse(.3); |       pince.pivote(0.5); | ||||||
|     } |     } | ||||||
| 
 |  | ||||||
|   } |   } | ||||||
| 
 | 
 | ||||||
|   // Called once the command ends or is interrupted. |   // Called once the command ends or is interrupted. | ||||||
|   @Override |   @Override | ||||||
|   public void end(boolean interrupted) { |   public void end(boolean interrupted) { | ||||||
|     elevateur.vitesse(0); |     pince.pivote(0); | ||||||
|   } |   } | ||||||
| 
 | 
 | ||||||
|   // Returns true when the command should end. |   // Returns true when the command should end. | ||||||
| @@ -2,18 +2,18 @@ | |||||||
| // Open Source Software; you can modify and/or share it under the terms of | // 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. | // the WPILib BSD license file in the root directory of this project. | ||||||
| 
 | 
 | ||||||
| package frc.robot.commands; | package frc.robot.command; | ||||||
| 
 | 
 | ||||||
| import edu.wpi.first.wpilibj2.command.Command; | 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 */ | /* 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 { | public class L4Pince extends Command { | ||||||
|   private Elevateur elevateur; |   private Pince pince; | ||||||
|   /** Creates a new L2. */ |   /** Creates a new L2Pince. */ | ||||||
|   public L4(Elevateur elevateur) { |   public L4Pince(Pince pince) { | ||||||
|     this.elevateur = elevateur; |     this.pince = pince; | ||||||
|     addRequirements(elevateur); |     addRequirements(pince); | ||||||
|     // Use addRequirements() here to declare subsystem dependencies. |     // Use addRequirements() here to declare subsystem dependencies. | ||||||
|   } |   } | ||||||
| 
 | 
 | ||||||
| @@ -24,26 +24,26 @@ public class L4 extends Command { | |||||||
|   // Called every time the scheduler runs while the command is scheduled. |   // Called every time the scheduler runs while the command is scheduled. | ||||||
|   @Override |   @Override | ||||||
|   public void execute() { |   public void execute() { | ||||||
|     if(elevateur.position()>=800 && elevateur.position()<=810){ |     if(pince.encodeurpivot()>=800 && pince.encodeurpivot()<=810){ | ||||||
|       elevateur.vitesse(0); |       pince.pivote(0); | ||||||
|     } |     } | ||||||
|     else if(elevateur.position()>=810){ |     else if(pince.encodeurpivot()>=810){ | ||||||
|       elevateur.vitesse(-0.5); |       pince.pivote(-0.5); | ||||||
|     } |     } | ||||||
|     else{ |     else{ | ||||||
|       elevateur.vitesse(.5); |       pince.pivote(0.5); | ||||||
|     } |     } | ||||||
|   } |   } | ||||||
| 
 | 
 | ||||||
|   // Called once the command ends or is interrupted. |   // Called once the command ends or is interrupted. | ||||||
|   @Override |   @Override | ||||||
|   public void end(boolean interrupted) { |   public void end(boolean interrupted) { | ||||||
|     elevateur.vitesse(0); |     pince.pivote(0); | ||||||
|   } |   } | ||||||
| 
 | 
 | ||||||
|   // Returns true when the command should end. |   // Returns true when the command should end. | ||||||
|   @Override |   @Override | ||||||
|   public boolean isFinished() { |   public boolean isFinished() { | ||||||
|     return elevateur.position()>=800; |     return false; | ||||||
|   } |   } | ||||||
| } | } | ||||||
							
								
								
									
										49
									
								
								src/main/java/frc/robot/command/StationPince.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										49
									
								
								src/main/java/frc/robot/command/StationPince.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.command; | ||||||
|  |  | ||||||
|  | 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 StationPince extends Command { | ||||||
|  |   private Pince pince; | ||||||
|  |   /** Creates a new L2Pince. */ | ||||||
|  |   public StationPince(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.encodeurpivot()>=900 && pince.encodeurpivot()<=910){ | ||||||
|  |       pince.pivote(0); | ||||||
|  |     } | ||||||
|  |     else if(pince.encodeurpivot()>=910){ | ||||||
|  |       pince.pivote(-0.5); | ||||||
|  |     } | ||||||
|  |     else{ | ||||||
|  |       pince.pivote(0.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; | ||||||
|  |   } | ||||||
|  | } | ||||||
| @@ -1,48 +0,0 @@ | |||||||
| // Copyright (c) FIRST and other WPILib contributors. |  | ||||||
| // Open Source Software; you can modify and/or share it under the terms of |  | ||||||
| // the WPILib BSD license file in the root directory of this project. |  | ||||||
|  |  | ||||||
| package frc.robot.commands; |  | ||||||
|  |  | ||||||
| import java.util.function.DoubleSupplier; |  | ||||||
|  |  | ||||||
| import edu.wpi.first.wpilibj2.command.Command; |  | ||||||
| import frc.robot.subsystems.Elevateur; |  | ||||||
|  |  | ||||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ |  | ||||||
| public class ElevateurManuel extends Command { |  | ||||||
|   private DoubleSupplier doubleSupplier; |  | ||||||
|   private Elevateur elevateur; |  | ||||||
|   /** Creates a new ElevateurManuel. */ |  | ||||||
|   public ElevateurManuel(Elevateur elevateur,DoubleSupplier doubleSupplier) { |  | ||||||
|     this.doubleSupplier = doubleSupplier; |  | ||||||
|     this.elevateur = elevateur; |  | ||||||
|     addRequirements(elevateur); |  | ||||||
|     // Use addRequirements() here to declare subsystem dependencies. |  | ||||||
|   } |  | ||||||
|  |  | ||||||
|   // Called when the command is initially scheduled. |  | ||||||
|   @Override |  | ||||||
|   public void initialize() {} |  | ||||||
|  |  | ||||||
|   // Called every time the scheduler runs while the command is scheduled. |  | ||||||
|   @Override |  | ||||||
|   public void execute() { |  | ||||||
|     if(elevateur.limit2()==true){ |  | ||||||
|       elevateur.vitesse(0); |  | ||||||
|     } |  | ||||||
|     elevateur.vitesse(doubleSupplier.getAsDouble()); |  | ||||||
|   } |  | ||||||
|  |  | ||||||
|   // 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; |  | ||||||
|   } |  | ||||||
| } |  | ||||||
| @@ -1,32 +0,0 @@ | |||||||
| // Copyright (c) FIRST and other WPILib contributors. |  | ||||||
| // Open Source Software; you can modify and/or share it under the terms of |  | ||||||
| // the WPILib BSD license file in the root directory of this project. |  | ||||||
|  |  | ||||||
| package frc.robot.subsystems; |  | ||||||
|  |  | ||||||
| import edu.wpi.first.wpilibj.DigitalInput; |  | ||||||
| import edu.wpi.first.wpilibj2.command.SubsystemBase; |  | ||||||
| import com.revrobotics.spark.SparkMax; |  | ||||||
| import com.revrobotics.spark.SparkLowLevel.MotorType; |  | ||||||
| public class Elevateur extends SubsystemBase { |  | ||||||
|   /** Creates a new Elevateur. */ |  | ||||||
|   public Elevateur() {} |  | ||||||
|   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 |  | ||||||
|   } |  | ||||||
| } |  | ||||||
							
								
								
									
										50
									
								
								src/main/java/frc/robot/subsystems/Pince.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										50
									
								
								src/main/java/frc/robot/subsystems/Pince.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.subsystems; | ||||||
|  |  | ||||||
|  | import com.revrobotics.spark.SparkLowLevel.MotorType; | ||||||
|  | import com.revrobotics.spark.SparkMax; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.wpilibj.DigitalInput; | ||||||
|  | import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||||||
|  |  | ||||||
|  | public class Pince extends SubsystemBase { | ||||||
|  |   /** Creates a new Pince. */ | ||||||
|  |   public Pince() {} | ||||||
|  |   final SparkMax coral = new SparkMax(0, MotorType.kBrushless); | ||||||
|  |   final SparkMax pivoti = new SparkMax(0, MotorType.kBrushless); | ||||||
|  |   final SparkMax algue1 = new SparkMax(0, MotorType.kBrushless); | ||||||
|  |   final SparkMax algue2 = new SparkMax(0, MotorType.kBrushless); | ||||||
|  |   final DigitalInput limit6 = new DigitalInput(0); | ||||||
|  |   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(); | ||||||
|  | } | ||||||
|  |   @Override | ||||||
|  |   public void periodic() { | ||||||
|  |     // This method will be called once per scheduler run | ||||||
|  |   } | ||||||
|  | } | ||||||
		Reference in New Issue
	
	Block a user