mode auto
This commit is contained in:
parent
0d63654df8
commit
004890fd7b
@ -60,10 +60,10 @@ import frc.robot.commands.Elevateur.balonL3;
|
||||
public class RobotContainer {
|
||||
ShuffleboardLayout layoutauto = Shuffleboard.getTab("teb").getLayout("auto", BuiltInLayouts.kList)
|
||||
.withSize(2, 2).withProperties(Map.of("Label position", "LEFT"));
|
||||
GenericEntry L1 = layoutauto.add("choix L1",true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
GenericEntry sortirAngle = layoutauto.add("Cote?",true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
GenericEntry Reculer = layoutauto.add("Reculer",true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
GenericEntry L4 = layoutauto.add("L4",true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
GenericEntry L1 = layoutauto.add("choix L1",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
GenericEntry sortirAngle = layoutauto.add("Cote?",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
GenericEntry Reculer = layoutauto.add("Reculer",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
GenericEntry L4 = layoutauto.add("L4",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); // kSpeedAt12Volts desired top speed
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); // 3/4 of a rotation per second max angular velocity
|
||||
|
||||
@ -160,11 +160,11 @@ public class RobotContainer {
|
||||
drivetrain.applyRequest(()->
|
||||
drive.withVelocityX(-0.1*MaxSpeed)
|
||||
.withVelocityY(0)
|
||||
.withRotationalRate(0)).unless(()->!Reculer.getBoolean(true)).withTimeout(2),
|
||||
.withRotationalRate(0)).unless(()->!Reculer.getBoolean(true)).withTimeout(3),
|
||||
drivetrain.applyRequest(()->
|
||||
drive.withVelocityX(0.5*MaxSpeed)
|
||||
.withVelocityY(0)
|
||||
.withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(2),
|
||||
.withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(3),
|
||||
drivetrain.applyRequest(()->
|
||||
drive.withVelocityX(-0.5*MaxSpeed)
|
||||
.withVelocityY(0)
|
||||
|
Loading…
x
Reference in New Issue
Block a user