From 6c9a52775b86dedc95f297cdc58118153ef00b85 Mon Sep 17 00:00:00 2001 From: samuel desharnais Date: Wed, 10 Jan 2024 20:01:12 -0500 Subject: [PATCH] fchg --- src/main/java/frc/robot/RobotContainer.java | 3 +-- src/main/java/frc/robot/subsystems/Drive.java | 2 +- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 6725911..5876ed1 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -101,8 +101,7 @@ String avancerautoString = "gauche"; public Command getAutonomousCommand() { chooser.getSelected(); - return new SequentialCommandGroup(new ParallelCommandGroup(new LanceurAuto(lanceur).withTimeout(6) - ,new AccAuto(accumulateur).withTimeout(6)), Commands.waitSeconds(6), + return new ParallelCommandGroup( Commands.waitSeconds(6), Commands.select(Map.ofEntries( Map.entry(avancerautoString,avancer), Map.entry(avancergaucheString, avancerGauche) diff --git a/src/main/java/frc/robot/subsystems/Drive.java b/src/main/java/frc/robot/subsystems/Drive.java index 5c90906..d5b0fa9 100644 --- a/src/main/java/frc/robot/subsystems/Drive.java +++ b/src/main/java/frc/robot/subsystems/Drive.java @@ -39,7 +39,7 @@ public class Drive extends SubsystemBase { final CanAndCoderSwerve arrieregaucheangle = new CanAndCoderSwerve(Constants.arrieregaucheAngle); final CanAndCoderSwerve arrieredroitangle = new CanAndCoderSwerve(Constants.arrieredroitAngle); */ public void drive(double x, double y, double zRotation){ - swerveDrive.drive(new Translation2d(x*4, y*4), zRotation, true, false); + swerveDrive.drive(new Translation2d(x*2, y*2), zRotation, true, false); }