Merge branch 'main' of https://git.demerso.net/pls5618/2024/robot
This commit is contained in:
commit
6e867c5c99
@ -74,21 +74,19 @@ public class RobotContainer {
|
|||||||
AllumeLED allumeLED = new AllumeLED(LED, accumulateur);
|
AllumeLED allumeLED = new AllumeLED(LED, accumulateur);
|
||||||
Pistongrimpeur pistongrimpeur = new Pistongrimpeur(grimpeur, LED);
|
Pistongrimpeur pistongrimpeur = new Pistongrimpeur(grimpeur, LED);
|
||||||
public RobotContainer() {
|
public RobotContainer() {
|
||||||
|
|
||||||
dashboard.addCamera("limelight", "limelight","limelight.local:5800")
|
dashboard.addCamera("limelight", "limelight","limelight.local:5800")
|
||||||
.withSize(3,4)
|
.withSize(3,4)
|
||||||
.withPosition(7,0);
|
.withPosition(7,0);
|
||||||
|
|
||||||
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);
|
||||||
|
|
||||||
NamedCommands.registerCommand("balayer",new Balayer(balayeuse, accumulateur));
|
NamedCommands.registerCommand("balayer",new Balayer(balayeuse, accumulateur));
|
||||||
NamedCommands.registerCommand("lancer", new LancerNote(lanceur, accumulateur));
|
NamedCommands.registerCommand("lancer", new LancerNote(lanceur, accumulateur));
|
||||||
NamedCommands.registerCommand("piston", new PistonFerme(grimpeur));
|
NamedCommands.registerCommand("piston", new PistonFerme(grimpeur));
|
||||||
autoChooser = AutoBuilder.buildAutoChooser();
|
autoChooser = AutoBuilder.buildAutoChooser();
|
||||||
|
|
||||||
manette.a().whileTrue(new GuiderBas(guideur));
|
|
||||||
dashboard.addCamera("USB Camera 0", "USB Camera 0","http://roborio-5618-frc.local:1181/?action=stream")
|
|
||||||
.withSize(4, 4)
|
|
||||||
.withPosition(3, 0);
|
|
||||||
|
|
||||||
manette.a().whileTrue(new GuiderBas(guideur));
|
manette.a().whileTrue(new GuiderBas(guideur));
|
||||||
manette.b().whileTrue(new GuiderHaut(guideur));
|
manette.b().whileTrue(new GuiderHaut(guideur));
|
||||||
@ -110,7 +108,7 @@ public class RobotContainer {
|
|||||||
grimpeur.setDefaultCommand(new RunCommand(()->{
|
grimpeur.setDefaultCommand(new RunCommand(()->{
|
||||||
grimpeur.droit(MathUtil.applyDeadband(-manette.getLeftY(), 0.2));
|
grimpeur.droit(MathUtil.applyDeadband(-manette.getLeftY(), 0.2));
|
||||||
grimpeur.gauche(MathUtil.applyDeadband(-manette.getRightY(),0.2 ));}
|
grimpeur.gauche(MathUtil.applyDeadband(-manette.getRightY(),0.2 ));}
|
||||||
,grimpeur));
|
,grimpeur));
|
||||||
|
|
||||||
LED.setDefaultCommand(allumeLED);
|
LED.setDefaultCommand(allumeLED);
|
||||||
|
|
||||||
|
@ -25,7 +25,7 @@ public class LancerAmp extends Command {
|
|||||||
// Called every time the scheduler runs while the command is scheduled.
|
// Called every time the scheduler runs while the command is scheduled.
|
||||||
@Override
|
@Override
|
||||||
public void execute() {
|
public void execute() {
|
||||||
double vitesse = 0.1;
|
double vitesse = 0.15;
|
||||||
lancer.lanceramp();
|
lancer.lanceramp();
|
||||||
if(lancer.vitesse(vitesse)>vitesse){
|
if(lancer.vitesse(vitesse)>vitesse){
|
||||||
accumulateur.Accumuler();
|
accumulateur.Accumuler();
|
||||||
|
@ -21,9 +21,9 @@ import swervelib.parser.SwerveParser;
|
|||||||
public class Drive extends SubsystemBase {
|
public class Drive extends SubsystemBase {
|
||||||
/** Creates a new Drive. */
|
/** Creates a new Drive. */
|
||||||
|
|
||||||
public static final boolean kFrontLeftDriveMotorReversed = false;
|
public static final boolean kFrontLeftDriveMotorReversed = true;
|
||||||
public static final boolean kBackLeftDriveMotorReversed = false;
|
public static final boolean kBackLeftDriveMotorReversed = true;
|
||||||
public static final boolean kFrontRightDriveMotorReversed = true;
|
public static final boolean kFrontRightDriveMotorReversed = false;
|
||||||
public static final boolean kBackRightDriveMotorReversed = true;
|
public static final boolean kBackRightDriveMotorReversed = true;
|
||||||
|
|
||||||
SwerveDrive swerveDrive;
|
SwerveDrive swerveDrive;
|
||||||
|
Loading…
x
Reference in New Issue
Block a user