This commit is contained in:
Antoine PerreaultE 2025-02-26 19:23:34 -05:00
commit b947c93ab7
3 changed files with 11 additions and 9 deletions

View File

@ -96,27 +96,29 @@ public class RobotContainer {
NamedCommands.registerCommand("CoraletAlgue", new CoralAlgueInspire(pince,bougie));
}
private void configureBindings() {
// Elevateur manuel
drivetrain.setDefaultCommand(
// Drivetrain will execute this command periodically
drivetrain.applyRequest(() ->
drive.withVelocityX(MathUtil.applyDeadband(-manette1.getLeftY()*MaxSpeed, 0.2)) // Drive forward with negative Y (forward)
.withVelocityY(MathUtil.applyDeadband(-manette1.getLeftX()*MaxSpeed, 0.2)) // Drive left with negative X (left)
.withRotationalRate(MathUtil.applyDeadband(-manette1.getRightX()*MaxAngularRate, 0.15)) // Drive counterclockwise with negative X (left)
drive.withVelocityX(MathUtil.applyDeadband(-manette1.getLeftY()*manette1.getLeftY()*MaxSpeed, 0.1)) // Drive forward with negative Y (forward)
.withVelocityY(MathUtil.applyDeadband(-manette1.getLeftX()*manette1.getLeftX()*MaxSpeed, 0.10000)) // Drive left with negative X (left)
.withRotationalRate(MathUtil.applyDeadband(-manette1.getRightX()*manette1.getRightX()*MaxAngularRate, 0.1)) // Drive counterclockwise with negative X (left)
)
);
// Elevateur manuel
drivetrain.registerTelemetry(logger::telemeterize);
elevateur.setDefaultCommand(new RunCommand(()->{
elevateur.vitesse(MathUtil.applyDeadband(manette2.getLeftY(), 0.2));
elevateur.vitesse(MathUtil.applyDeadband(manette2.getLeftY()*manette2.getLeftY(), 0.1));
}, elevateur));
//Pince manuel
pince.setDefaultCommand(new RunCommand(()->{
pince.pivote(MathUtil.applyDeadband(manette2.getRightY()/5, 0.2));
pince.pivote(MathUtil.applyDeadband(manette2.getRightY()*manette2.getRightY(), 0.1));
}, pince));
// reset the field-centric heading on left bumper press
// manette1
// reset the field-centric heading on left bumper press
manette1.start().onTrue(drivetrain.runOnce(() -> drivetrain.seedFieldCentric()));
manette1.a().whileTrue(new Depart(elevateur, pince));
manette1.b().whileTrue(new L2(elevateur,pince));

View File

@ -31,7 +31,7 @@ public class ElevateurManuel extends Command {
if(elevateur.limit2()==true){
elevateur.vitesse(0);
}
elevateur.vitesse(doubleSupplier.getAsDouble()/7);
elevateur.vitesse(doubleSupplier.getAsDouble()/3.5);
}
// Called once the command ends or is interrupted.

View File

@ -32,7 +32,7 @@ public class PinceManuel extends Command {
pince.pivote(0);
}
else{
pince.pivote(x.getAsDouble());
pince.pivote(x.getAsDouble()/3.5);
}
}