Compare commits
	
		
			7 Commits
		
	
	
		
			6fb4e0c1ac
			...
			elevateur
		
	
	| Author | SHA1 | Date | |
|---|---|---|---|
|  | 36456f1fe4 | ||
|  | 0567735a6f | ||
|  | 0fdfa4269d | ||
|  | e7b4b47928 | ||
|  | 0577ce368a | ||
|  | 7521c0d94e | ||
|  | b16d11b70a | 
| @@ -6,29 +6,15 @@ package frc.robot; | |||||||
|  |  | ||||||
| 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.button.CommandXboxController; |  | ||||||
|  |  | ||||||
|  |  | ||||||
| public class RobotContainer { | public class RobotContainer { | ||||||
|  |   public RobotContainer() { | ||||||
|  |     configureBindings(); | ||||||
|  |   } | ||||||
|  |  | ||||||
|     private final CommandXboxController manette1 = new CommandXboxController(0); |   private void configureBindings() {} | ||||||
|     private final CommandXboxController manette2 = new CommandXboxController(0); |  | ||||||
|  |  | ||||||
|     public RobotContainer() { |   public Command getAutonomousCommand() { | ||||||
|  |     return Commands.print("No autonomous command configured"); | ||||||
|         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. |  | ||||||
|  |  | ||||||
|         // Run SysId routines when holding back/start and X/Y. |  | ||||||
|         // Note that each routine should be run exactly once in a single log. |  | ||||||
|    |  | ||||||
|     } |  | ||||||
|  |  | ||||||
|     public Command getAutonomousCommand() { |  | ||||||
|         return Commands.print(""); |  | ||||||
|     } |  | ||||||
| } | } | ||||||
|   | |||||||
							
								
								
									
										47
									
								
								src/main/java/frc/robot/commands/Depart.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										47
									
								
								src/main/java/frc/robot/commands/Depart.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.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 Depart extends Command { | ||||||
|  |   private Elevateur elevateur; | ||||||
|  |   /** Creates a new L2. */ | ||||||
|  |   public Depart(Elevateur elevateur) { | ||||||
|  |     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.reset(); | ||||||
|  |     } | ||||||
|  |     else{ | ||||||
|  |       elevateur.vitesse(-.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 elevateur.limit2()==true; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										48
									
								
								src/main/java/frc/robot/commands/ElevateurManuel.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										48
									
								
								src/main/java/frc/robot/commands/ElevateurManuel.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,48 @@ | |||||||
|  | // Copyright (c) FIRST and other WPILib contributors. | ||||||
|  | // Open Source Software; you can modify and/or share it under the terms of | ||||||
|  | // the WPILib BSD license file in the root directory of this project. | ||||||
|  |  | ||||||
|  | package frc.robot.commands; | ||||||
|  |  | ||||||
|  | import java.util.function.DoubleSupplier; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.wpilibj2.command.Command; | ||||||
|  | import frc.robot.subsystems.Elevateur; | ||||||
|  |  | ||||||
|  | /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||||
|  | public class ElevateurManuel extends Command { | ||||||
|  |   private DoubleSupplier doubleSupplier; | ||||||
|  |   private Elevateur elevateur; | ||||||
|  |   /** Creates a new ElevateurManuel. */ | ||||||
|  |   public ElevateurManuel(Elevateur elevateur,DoubleSupplier doubleSupplier) { | ||||||
|  |     this.doubleSupplier = doubleSupplier; | ||||||
|  |     this.elevateur = elevateur; | ||||||
|  |     addRequirements(elevateur); | ||||||
|  |     // Use addRequirements() here to declare subsystem dependencies. | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Called when the command is initially scheduled. | ||||||
|  |   @Override | ||||||
|  |   public void initialize() {} | ||||||
|  |  | ||||||
|  |   // Called every time the scheduler runs while the command is scheduled. | ||||||
|  |   @Override | ||||||
|  |   public void execute() { | ||||||
|  |     if(elevateur.limit2()==true){ | ||||||
|  |       elevateur.vitesse(0); | ||||||
|  |     } | ||||||
|  |     elevateur.vitesse(doubleSupplier.getAsDouble()); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // 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; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										50
									
								
								src/main/java/frc/robot/commands/L2.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										50
									
								
								src/main/java/frc/robot/commands/L2.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,50 @@ | |||||||
|  | // Copyright (c) FIRST and other WPILib contributors. | ||||||
|  | // Open Source Software; you can modify and/or share it under the terms of | ||||||
|  | // the WPILib BSD license file in the root directory of this project. | ||||||
|  |  | ||||||
|  | package frc.robot.commands; | ||||||
|  |  | ||||||
|  | import 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 L2 extends Command { | ||||||
|  |   private Elevateur elevateur; | ||||||
|  |   /** Creates a new L2. */ | ||||||
|  |   public L2(Elevateur elevateur) { | ||||||
|  |     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.position()>=500 && elevateur.position()<=510){ | ||||||
|  |       elevateur.vitesse(0); | ||||||
|  |     } | ||||||
|  |     else if(elevateur.position()>=510){ | ||||||
|  |       elevateur.vitesse(-0.3); | ||||||
|  |     } | ||||||
|  |     else{ | ||||||
|  |       elevateur.vitesse(.3); | ||||||
|  |     } | ||||||
|  |  | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // 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; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										49
									
								
								src/main/java/frc/robot/commands/L3.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										49
									
								
								src/main/java/frc/robot/commands/L3.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,49 @@ | |||||||
|  | // Copyright (c) FIRST and other WPILib contributors. | ||||||
|  | // Open Source Software; you can modify and/or share it under the terms of | ||||||
|  | // the WPILib BSD license file in the root directory of this project. | ||||||
|  |  | ||||||
|  | package frc.robot.commands; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.wpilibj2.command.Command; | ||||||
|  | import frc.robot.subsystems.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 L3 extends Command { | ||||||
|  |   private Elevateur elevateur; | ||||||
|  |   /** Creates a new L2. */ | ||||||
|  |   public L3(Elevateur elevateur) { | ||||||
|  |     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.position()>=700 && elevateur.position()<=710){ | ||||||
|  |       elevateur.vitesse(0); | ||||||
|  |     } | ||||||
|  |     else if(elevateur.position()>=510){ | ||||||
|  |       elevateur.vitesse(-0.5); | ||||||
|  |     } | ||||||
|  |     else{ | ||||||
|  |       elevateur.vitesse(.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; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										49
									
								
								src/main/java/frc/robot/commands/L4.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										49
									
								
								src/main/java/frc/robot/commands/L4.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,49 @@ | |||||||
|  | // Copyright (c) FIRST and other WPILib contributors. | ||||||
|  | // Open Source Software; you can modify and/or share it under the terms of | ||||||
|  | // the WPILib BSD license file in the root directory of this project. | ||||||
|  |  | ||||||
|  | package frc.robot.commands; | ||||||
|  |  | ||||||
|  | import edu.wpi.first.wpilibj2.command.Command; | ||||||
|  | import frc.robot.subsystems.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 L4 extends Command { | ||||||
|  |   private Elevateur elevateur; | ||||||
|  |   /** Creates a new L2. */ | ||||||
|  |   public L4(Elevateur elevateur) { | ||||||
|  |     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.position()>=800 && elevateur.position()<=810){ | ||||||
|  |       elevateur.vitesse(0); | ||||||
|  |     } | ||||||
|  |     else if(elevateur.position()>=810){ | ||||||
|  |       elevateur.vitesse(-0.5); | ||||||
|  |     } | ||||||
|  |     else{ | ||||||
|  |       elevateur.vitesse(.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 elevateur.position()>=800; | ||||||
|  |   } | ||||||
|  | } | ||||||
							
								
								
									
										32
									
								
								src/main/java/frc/robot/subsystems/Elevateur.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										32
									
								
								src/main/java/frc/robot/subsystems/Elevateur.java
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,32 @@ | |||||||
|  | // 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 | ||||||
|  |   } | ||||||
|  | } | ||||||
		Reference in New Issue
	
	Block a user