fchg
This commit is contained in:
parent
0f6021bcd6
commit
6c9a52775b
@ -101,8 +101,7 @@ String avancerautoString = "gauche";
|
|||||||
|
|
||||||
public Command getAutonomousCommand() {
|
public Command getAutonomousCommand() {
|
||||||
chooser.getSelected();
|
chooser.getSelected();
|
||||||
return new SequentialCommandGroup(new ParallelCommandGroup(new LanceurAuto(lanceur).withTimeout(6)
|
return new ParallelCommandGroup( Commands.waitSeconds(6),
|
||||||
,new AccAuto(accumulateur).withTimeout(6)), Commands.waitSeconds(6),
|
|
||||||
Commands.select(Map.ofEntries(
|
Commands.select(Map.ofEntries(
|
||||||
Map.entry(avancerautoString,avancer),
|
Map.entry(avancerautoString,avancer),
|
||||||
Map.entry(avancergaucheString, avancerGauche)
|
Map.entry(avancergaucheString, avancerGauche)
|
||||||
|
@ -39,7 +39,7 @@ public class Drive extends SubsystemBase {
|
|||||||
final CanAndCoderSwerve arrieregaucheangle = new CanAndCoderSwerve(Constants.arrieregaucheAngle);
|
final CanAndCoderSwerve arrieregaucheangle = new CanAndCoderSwerve(Constants.arrieregaucheAngle);
|
||||||
final CanAndCoderSwerve arrieredroitangle = new CanAndCoderSwerve(Constants.arrieredroitAngle); */
|
final CanAndCoderSwerve arrieredroitangle = new CanAndCoderSwerve(Constants.arrieredroitAngle); */
|
||||||
public void drive(double x, double y, double zRotation){
|
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);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
x
Reference in New Issue
Block a user