changement encodeur l3, pince algue
This commit is contained in:
parent
606c4e98f3
commit
5b754ff824
@ -24,6 +24,9 @@ import edu.wpi.first.wpilibj2.command.RunCommand;
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||
import frc.robot.TunerConstants.TunerConstants;
|
||||
import frc.robot.commands.Algue1Test;
|
||||
import frc.robot.commands.Algue2Test;
|
||||
import frc.robot.commands.Algue_inspire;
|
||||
import frc.robot.commands.AprilTag3;
|
||||
import frc.robot.commands.AprilTag3G;
|
||||
import frc.robot.commands.ElevateurManuel;
|
||||
@ -108,6 +111,11 @@ public class RobotContainer {
|
||||
manette1.rightTrigger().whileTrue(new Forme3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY));
|
||||
manette1.a().whileTrue(new reset(elevateur,pince));
|
||||
manette1.b().whileTrue(new L2(elevateur, pince));
|
||||
|
||||
manette2.a().whileTrue(new Algue_inspire(pince));
|
||||
|
||||
manette2.b().whileTrue(new Algue1Test(pince));
|
||||
manette2.x().whileTrue(new Algue2Test(pince));
|
||||
|
||||
// manette2.leftTrigger().whileTrue(new AprilTag3G(limelight3g,drivetrain,manette1::getLeftX,manette1::getLeftY));
|
||||
}
|
||||
|
44
src/main/java/frc/robot/commands/Algue_inspire.java
Normal file
44
src/main/java/frc/robot/commands/Algue_inspire.java
Normal file
@ -0,0 +1,44 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystems.Pince;
|
||||
|
||||
/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
|
||||
public class Algue_inspire extends Command {
|
||||
/** Creates a new Algue_inspire. */
|
||||
private Pince pince;
|
||||
public Algue_inspire(Pince pince) {
|
||||
this.pince = pince;
|
||||
addRequirements(pince);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {}
|
||||
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
|
||||
//ajouter l'amperage pour arreter les moteurs
|
||||
@Override
|
||||
public void execute() {
|
||||
pince.aspirealgue(0.5);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
pince.aspirealgue(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
@ -28,24 +28,24 @@ public class L3 extends Command {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(elevateur.position()>=700 && elevateur.position()<=710){
|
||||
if(elevateur.position()<=-4 && elevateur.position()>=-4.7){
|
||||
elevateur.vitesse(0);
|
||||
}
|
||||
else if(elevateur.position()>=510){
|
||||
else if(elevateur.position()>=-4.7){
|
||||
elevateur.vitesse(0.5);
|
||||
}
|
||||
else{
|
||||
elevateur.vitesse(-.5);
|
||||
}
|
||||
if(pince.encodeurpivot()>=700 && pince.encodeurpivot()<=710){
|
||||
pince.pivote(0);
|
||||
}
|
||||
else if(pince.encodeurpivot()>=710){
|
||||
pince.pivote(0.2);
|
||||
}
|
||||
else{
|
||||
pince.pivote(-0.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.
|
||||
|
@ -34,7 +34,7 @@ public void pivote(double vitesse){
|
||||
pivoti.set(vitesse);
|
||||
}
|
||||
public void aspirealgue(double vitesse){
|
||||
algue2.set(vitesse);
|
||||
algue2.set(-vitesse);
|
||||
algue1.set(-vitesse);
|
||||
}
|
||||
public double encodeurpivot(){
|
||||
|
Loading…
x
Reference in New Issue
Block a user