pince
This commit is contained in:
		| @@ -20,6 +20,7 @@ import frc.robot.commands.L2; | ||||
| import frc.robot.commands.L3; | ||||
| import frc.robot.commands.L4; | ||||
| import frc.robot.commands.PinceManuel; | ||||
| import frc.robot.commands.PinceManuel2; | ||||
| import frc.robot.commands.StationPince; | ||||
| import frc.robot.subsystems.Elevateur; | ||||
| import frc.robot.subsystems.Pince; | ||||
| @@ -32,14 +33,15 @@ public class RobotContainer { | ||||
|   Pince pince = new Pince(); | ||||
|   Elevateur elevateur = new Elevateur(); | ||||
|   ElevateurManuel elevateurManuel = new ElevateurManuel(elevateur, manette2::getLeftY); | ||||
|   PinceManuel pinceManuel = new PinceManuel(pince, manette2::getRightY); | ||||
|   PinceManuel pinceManuel = new PinceManuel(pince); | ||||
|   PinceManuel2 pinceManuel2 = new PinceManuel2(pince); | ||||
|   public RobotContainer() { | ||||
|     configureBindings(); | ||||
|     elevateur.setDefaultCommand(new RunCommand(()->{ | ||||
|       elevateur.vitesse(MathUtil.applyDeadband(manette2.getLeftY(), 0.2)); | ||||
|     }, elevateur)); | ||||
|     pince.setDefaultCommand(new RunCommand(()->{ | ||||
|       pince.pivote(MathUtil.applyDeadband(manette2.getRightY(), 0.2)); | ||||
|       pince.pivote(MathUtil.applyDeadband(manette2.getRightY()/5, 0.2)); | ||||
|     }, pince)); | ||||
|      NamedCommands.registerCommand("Station",new StationPince(pince, elevateur)); | ||||
|     NamedCommands.registerCommand("L4", new L4(elevateur, pince)); | ||||
| @@ -59,8 +61,9 @@ public class RobotContainer { | ||||
|     manette1.rightTrigger().whileTrue(new CoralAlgueInspire(pince, bougie)); | ||||
|     manette1.rightBumper().whileTrue(new StationPince(pince, elevateur)); | ||||
|     //manette2 | ||||
|     manette2.leftTrigger().toggleOnTrue(new AlgueExpire(pince, bougie)); | ||||
|      | ||||
|     manette2.leftTrigger().whileTrue(new AlgueExpire(pince, bougie)); | ||||
|     manette2.povUp().whileTrue(new PinceManuel(pince)); | ||||
|     manette2.povDown().whileTrue(new PinceManuel2(pince)); | ||||
|   } | ||||
|    | ||||
|   public Command getAutonomousCommand() { | ||||
|   | ||||
| @@ -29,7 +29,7 @@ public class DepartPince extends Command { | ||||
|       pince.reset(); | ||||
|     } | ||||
|     else{ | ||||
|       pince.pivote(.5); | ||||
|       pince.pivote(.2); | ||||
|     } | ||||
|   } | ||||
|  | ||||
|   | ||||
| @@ -42,10 +42,10 @@ public class L2 extends Command { | ||||
|       | ||||
|     } | ||||
|     else if(pince.encodeurpivot()>=510){ | ||||
|       pince.pivote(-0.3); | ||||
|       pince.pivote(-0.2); | ||||
|     } | ||||
|     else{ | ||||
|       pince.pivote(0.3); | ||||
|       pince.pivote(0.2); | ||||
|     } | ||||
|  | ||||
|   } | ||||
|   | ||||
| @@ -41,10 +41,10 @@ public class L3 extends Command { | ||||
|       pince.pivote(0); | ||||
|     } | ||||
|     else if(pince.encodeurpivot()>=710){ | ||||
|       pince.pivote(-0.5); | ||||
|       pince.pivote(-0.2); | ||||
|     } | ||||
|     else{ | ||||
|       pince.pivote(0.5); | ||||
|       pince.pivote(0.2); | ||||
|     } | ||||
|   } | ||||
|  | ||||
|   | ||||
| @@ -41,10 +41,10 @@ public class L4 extends Command { | ||||
|       pince.pivote(0); | ||||
|     } | ||||
|     else if(pince.encodeurpivot()>=810){ | ||||
|       pince.pivote(-0.5); | ||||
|       pince.pivote(-0.2); | ||||
|     } | ||||
|     else{ | ||||
|       pince.pivote(0.5); | ||||
|       pince.pivote(0.2); | ||||
|     } | ||||
|   } | ||||
|  | ||||
|   | ||||
| @@ -14,9 +14,11 @@ public class PinceManuel extends Command { | ||||
|   private Pince pince; | ||||
|   private DoubleSupplier doubleSupplier; | ||||
|   /** Creates a new PinceManuel. */ | ||||
|   public PinceManuel(Pince pince, DoubleSupplier doubleSupplier) { | ||||
|   public PinceManuel(Pince pince | ||||
|   //, DoubleSupplier doubleSupplier | ||||
|   ) { | ||||
|     this.pince = pince; | ||||
|     this.doubleSupplier = doubleSupplier; | ||||
|     //this.doubleSupplier = doubleSupplier; | ||||
|     addRequirements(pince); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
| @@ -32,7 +34,7 @@ public class PinceManuel extends Command { | ||||
|       pince.pivote(0); | ||||
|     } | ||||
|     else{ | ||||
|       pince.pivote(doubleSupplier.getAsDouble()); | ||||
|       pince.pivote(0.2); | ||||
|     } | ||||
|   } | ||||
|  | ||||
|   | ||||
							
								
								
									
										48
									
								
								src/main/java/frc/robot/commands/PinceManuel2.java
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										48
									
								
								src/main/java/frc/robot/commands/PinceManuel2.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.Pince; | ||||
|  | ||||
| /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ | ||||
| public class PinceManuel2 extends Command { | ||||
|   private Pince pince; | ||||
|   //private DoubleSupplier doubleSupplier; | ||||
|   /** Creates a new PinceManuel. */ | ||||
|   public PinceManuel2(Pince pince | ||||
|     | ||||
|   //,DoubleSupplier doubleSupplier | ||||
|   ) { | ||||
|     this.pince = pince; | ||||
|    // this.doubleSupplier = doubleSupplier; | ||||
|     addRequirements(pince); | ||||
|     // Use addRequirements() here to declare subsystem dependencies. | ||||
|   } | ||||
|  | ||||
|   // Called when the command is initially scheduled. | ||||
|   @Override | ||||
|   public void initialize() {} | ||||
|  | ||||
|   // Called every time the scheduler runs while the command is scheduled. | ||||
|   @Override | ||||
|   public void execute() { | ||||
|  | ||||
|       pince.pivote(-0.2); | ||||
|  | ||||
|   } | ||||
|  | ||||
|   // Called once the command ends or is interrupted. | ||||
|   @Override | ||||
|   public void end(boolean interrupted) {} | ||||
|  | ||||
|   // Returns true when the command should end. | ||||
|   @Override | ||||
|   public boolean isFinished() { | ||||
|     return false; | ||||
|   } | ||||
| } | ||||
| @@ -33,10 +33,10 @@ public class StationPince extends Command { | ||||
|       pince.pivote(0); | ||||
|     } | ||||
|     else if(pince.encodeurpivot()>=910){ | ||||
|       pince.pivote(-0.5); | ||||
|       pince.pivote(-0.2); | ||||
|     } | ||||
|     else{ | ||||
|       pince.pivote(0.5); | ||||
|       pince.pivote(0.2); | ||||
|     } | ||||
|     if(elevateur.position()>=400 && elevateur.position()<=410){ | ||||
|       elevateur.vitesse(0); | ||||
|   | ||||
| @@ -11,7 +11,7 @@ import com.revrobotics.spark.SparkLowLevel.MotorType; | ||||
| public class Elevateur extends SubsystemBase { | ||||
|   /** Creates a new Elevateur. */ | ||||
|   public Elevateur() {} | ||||
|   final SparkMax  monte = new SparkMax(3, MotorType.kBrushless); | ||||
|   final SparkMax  monte = new SparkMax(22, MotorType.kBrushless); | ||||
|   final DigitalInput limit2 = new DigitalInput(1); | ||||
|   public double position(){ | ||||
|     return monte.getEncoder().getPosition(); | ||||
|   | ||||
| @@ -17,7 +17,7 @@ public class Pince extends SubsystemBase { | ||||
|   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(2); | ||||
|   final DigitalInput limit6 = new DigitalInput(0); | ||||
|   public void aspirecoral(double vitesse){ | ||||
|     coral.set(vitesse); | ||||
|   } | ||||
|   | ||||
		Reference in New Issue
	
	Block a user