Merge branch 'main' of https://git.demerso.net/pls5618/2024/robot
This commit is contained in:
commit
f6153cbb15
@ -48,5 +48,5 @@ public class Constants {
|
||||
public static int photocellacc = 2;
|
||||
|
||||
//piston
|
||||
public static int pistondroiteouvre= 6;
|
||||
public static int pistondroiteouvre= 7;
|
||||
}
|
||||
|
@ -81,6 +81,7 @@ public class RobotContainer {
|
||||
manette.a().whileTrue(new GuiderBas(guideur));
|
||||
manette.b().whileTrue(new GuiderHaut(guideur));
|
||||
manette.x().whileTrue(new PistonFerme(grimpeur));
|
||||
|
||||
joystick.button(3).whileTrue(balayer);
|
||||
joystick.button(1).whileTrue(new LancerNote(lanceur, accumulateur));
|
||||
joystick.button(5).whileTrue(new LancerAmp(lanceur, accumulateur));
|
||||
@ -95,8 +96,8 @@ public class RobotContainer {
|
||||
|
||||
// grimpeur manuel
|
||||
grimpeur.setDefaultCommand(new RunCommand(()->{
|
||||
grimpeur.droit(manette.getLeftY());
|
||||
grimpeur.gauche(manette.getRightY());}
|
||||
grimpeur.droit(MathUtil.applyDeadband(manette.getLeftY(), 0.2));
|
||||
grimpeur.gauche(MathUtil.applyDeadband(manette.getRightY(),0.2 ));}
|
||||
,grimpeur));
|
||||
|
||||
LED.setDefaultCommand(allumeLED);
|
||||
|
@ -24,16 +24,14 @@ public class GrimpeurDroit extends Command {
|
||||
@Override
|
||||
public void initialize() {
|
||||
grimpeur.resetencodeurd();
|
||||
grimpeur.pistonferme();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
grimpeur.droit(doubleSupplier.getAsDouble());
|
||||
if(grimpeur.encoderd()>78){
|
||||
grimpeur.droit(0);
|
||||
|
||||
if(grimpeur.encoderd()<73){
|
||||
grimpeur.droit(doubleSupplier.getAsDouble());
|
||||
}
|
||||
else if(grimpeur.getpitch()<-15){
|
||||
grimpeur.droit(-doubleSupplier.getAsDouble());
|
||||
|
@ -23,17 +23,17 @@ public class GrimpeurGauche extends Command {
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
grimpeur.resetencodeurd();
|
||||
grimpeur.resetencodeurg();
|
||||
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
grimpeur.gauche(doubleSupplier.getAsDouble());
|
||||
if(grimpeur.encoderg()>73){
|
||||
grimpeur.gauche(0);
|
||||
}
|
||||
if(grimpeur.encoderg()<78){
|
||||
grimpeur.gauche(doubleSupplier.getAsDouble());
|
||||
}
|
||||
else if(grimpeur.getpitch()<-15){
|
||||
grimpeur.gauche(doubleSupplier.getAsDouble());
|
||||
}
|
||||
@ -43,10 +43,12 @@ public class GrimpeurGauche extends Command {
|
||||
else{
|
||||
grimpeur.gauche(0);
|
||||
}
|
||||
if(grimpeur.encoderd()>0){
|
||||
if(grimpeur.encoderg()<0){
|
||||
grimpeur.gauche(doubleSupplier.getAsDouble());
|
||||
}
|
||||
else{
|
||||
grimpeur.resetencodeurg();
|
||||
grimpeur.gauche(0);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -19,7 +19,7 @@ public class PistonFerme extends Command {
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
grimpeur.pistonferme();
|
||||
grimpeur.pistonouvre();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@ -28,7 +28,9 @@ public class PistonFerme extends Command {
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {}
|
||||
public void end(boolean interrupted) {
|
||||
grimpeur.pistonferme();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
|
@ -28,7 +28,7 @@ public class Grimpeur extends SubsystemBase {
|
||||
final CANSparkMax grimpeurd = new CANSparkMax(Constants.grimpeurd,MotorType.kBrushless);
|
||||
final CANSparkMax grimpeurg = new CANSparkMax(Constants.grimpeurg,MotorType.kBrushless);
|
||||
// limit switch
|
||||
final Solenoid pistondroite= new Solenoid(PneumaticsModuleType.CTREPCM, Constants.pistondroiteouvre);
|
||||
final Solenoid pistondroite= new Solenoid(PneumaticsModuleType.REVPH, Constants.pistondroiteouvre);
|
||||
//fonction
|
||||
public Grimpeur() {
|
||||
pistonouvre();
|
||||
|
Loading…
x
Reference in New Issue
Block a user