revenu a la normal
This commit is contained in:
parent
84f4f4ad46
commit
b46109fe0b
@ -79,7 +79,7 @@ public class RobotContainer {
|
|||||||
NamedCommands.registerCommand("piston", new PistonFerme(grimpeur));
|
NamedCommands.registerCommand("piston", new PistonFerme(grimpeur));
|
||||||
autoChooser = AutoBuilder.buildAutoChooser();
|
autoChooser = AutoBuilder.buildAutoChooser();
|
||||||
|
|
||||||
/*manette.a().whileTrue(new GuiderBas(guideur));
|
manette.a().whileTrue(new GuiderBas(guideur));
|
||||||
dashboard.addCamera("USB Camera 0", "USB Camera 0","http://roborio-5618-frc.local:1181/?action=stream")
|
dashboard.addCamera("USB Camera 0", "USB Camera 0","http://roborio-5618-frc.local:1181/?action=stream")
|
||||||
.withSize(4, 4)
|
.withSize(4, 4)
|
||||||
.withPosition(3, 0);
|
.withPosition(3, 0);
|
||||||
@ -92,11 +92,11 @@ public class RobotContainer {
|
|||||||
joystick.button(1).whileTrue(new LancerNote(lanceur, accumulateur));
|
joystick.button(1).whileTrue(new LancerNote(lanceur, accumulateur));
|
||||||
joystick.button(5).whileTrue(new LancerAmp(lanceur, accumulateur));
|
joystick.button(5).whileTrue(new LancerAmp(lanceur, accumulateur));
|
||||||
joystick.button(4).whileTrue(new ParallelCommandGroup(new Lancer(lanceur,limelight),new Limelight_tracker(limelight,drive)));
|
joystick.button(4).whileTrue(new ParallelCommandGroup(new Lancer(lanceur,limelight),new Limelight_tracker(limelight,drive)));
|
||||||
joystick.button(2).whileTrue(new ParallelCommandGroup(new Lancerampli(lanceur,limelight),new Limelight_tracker(limelight,drive),new GuiderHaut(guideur)));*/
|
joystick.button(2).whileTrue(new ParallelCommandGroup(new Lancerampli(lanceur,limelight),new Limelight_tracker(limelight,drive),new GuiderHaut(guideur)));
|
||||||
|
|
||||||
// deplacement
|
// deplacement
|
||||||
configureBindings();
|
configureBindings();
|
||||||
/* drive.setDefaultCommand(new RunCommand(()->{
|
drive.setDefaultCommand(new RunCommand(()->{
|
||||||
drive.drive(MathUtil.applyDeadband(joystick.getY(),0.2), MathUtil.applyDeadband(joystick.getX(),0.2), MathUtil.applyDeadband(joystick.getZ(), 0.2));
|
drive.drive(MathUtil.applyDeadband(joystick.getY(),0.2), MathUtil.applyDeadband(joystick.getX(),0.2), MathUtil.applyDeadband(joystick.getZ(), 0.2));
|
||||||
},drive));
|
},drive));
|
||||||
|
|
||||||
@ -109,23 +109,8 @@ public class RobotContainer {
|
|||||||
LED.setDefaultCommand(allumeLED);
|
LED.setDefaultCommand(allumeLED);
|
||||||
dashboard.add("autochooser",autoChooser)
|
dashboard.add("autochooser",autoChooser)
|
||||||
.withSize(2,1)
|
.withSize(2,1)
|
||||||
.withPosition(1,1);*/
|
.withPosition(1,1);
|
||||||
manette
|
|
||||||
.a()
|
|
||||||
.and(manette.rightBumper())
|
|
||||||
.whileTrue(lanceur.sysIdQuasistatic(SysIdRoutine.Direction.kForward));
|
|
||||||
manette
|
|
||||||
.b()
|
|
||||||
.and(manette.rightBumper())
|
|
||||||
.whileTrue(lanceur.sysIdQuasistatic(SysIdRoutine.Direction.kReverse));
|
|
||||||
manette
|
|
||||||
.x()
|
|
||||||
.and(manette.rightBumper())
|
|
||||||
.whileTrue(lanceur.sysIdDynamic(SysIdRoutine.Direction.kForward));
|
|
||||||
manette
|
|
||||||
.y()
|
|
||||||
.and(manette.rightBumper())
|
|
||||||
.whileTrue(lanceur.sysIdDynamic(SysIdRoutine.Direction.kReverse));
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -69,7 +69,7 @@ public class Lanceur extends SubsystemBase {
|
|||||||
new SysIdRoutine.Mechanism(
|
new SysIdRoutine.Mechanism(
|
||||||
// Tell SysId how to plumb the driving voltage to the motor(s).
|
// Tell SysId how to plumb the driving voltage to the motor(s).
|
||||||
(Measure<Voltage> volts) -> {
|
(Measure<Voltage> volts) -> {
|
||||||
lanceur1.setVoltage(volts.in(Volts));
|
lanceur4.setVoltage(volts.in(Volts));
|
||||||
},
|
},
|
||||||
// Tell SysId how to record a frame of data for each motor on the mechanism being
|
// Tell SysId how to record a frame of data for each motor on the mechanism being
|
||||||
// characterized.
|
// characterized.
|
||||||
@ -78,10 +78,10 @@ public class Lanceur extends SubsystemBase {
|
|||||||
log.motor("shooter-wheel")
|
log.motor("shooter-wheel")
|
||||||
.voltage(
|
.voltage(
|
||||||
appliedVoltage.mut_replace(
|
appliedVoltage.mut_replace(
|
||||||
lanceur1.get() * RobotController.getBatteryVoltage(), Volts))
|
lanceur4.get() * RobotController.getBatteryVoltage(), Volts))
|
||||||
.angularPosition(angle.mut_replace(lanceur1.getEncoder().getPosition(), Rotations))
|
.angularPosition(angle.mut_replace(lanceur4.getEncoder().getPosition(), Rotations))
|
||||||
.angularVelocity(
|
.angularVelocity(
|
||||||
velocity.mut_replace(lanceur1.getEncoder().getVelocity(), RotationsPerSecond));
|
velocity.mut_replace(lanceur4.getEncoder().getVelocity(), RotationsPerSecond));
|
||||||
},
|
},
|
||||||
// Tell SysId to make generated commands require this subsystem, suffix test state in
|
// Tell SysId to make generated commands require this subsystem, suffix test state in
|
||||||
// WPILog with this subsystem's name ("shooter")
|
// WPILog with this subsystem's name ("shooter")
|
||||||
|
Loading…
x
Reference in New Issue
Block a user