This commit is contained in:
Olivier Dubois 2024-02-22 18:03:31 -05:00
commit 04b26ba146
5 changed files with 66 additions and 9 deletions

View File

@ -16,12 +16,12 @@
}, },
{ {
"anchor": { "anchor": {
"x": 2.7, "x": 2.7155331803541096,
"y": 7.0 "y": 6.958021893251764
}, },
"prevControl": { "prevControl": {
"x": 2.6949379619996434, "x": 2.727570849247609,
"y": 7.0 "y": 6.978871747379996
}, },
"nextControl": null, "nextControl": null,
"isLocked": false, "isLocked": false,
@ -39,7 +39,7 @@
}, },
"goalEndState": { "goalEndState": {
"velocity": 0, "velocity": 0,
"rotation": -88.31533329176997, "rotation": 56.65929265352304,
"rotateFast": false "rotateFast": false
}, },
"reversed": false, "reversed": false,

View File

@ -20,8 +20,8 @@
"y": 4.1 "y": 4.1
}, },
"prevControl": { "prevControl": {
"x": 13.990250241783144, "x": 14.011940966373402,
"y": 4.090250241783143 "y": 4.093105879849931
}, },
"nextControl": null, "nextControl": null,
"isLocked": false, "isLocked": false,
@ -39,7 +39,7 @@
}, },
"goalEndState": { "goalEndState": {
"velocity": 0, "velocity": 0,
"rotation": -88.30255667497883, "rotation": -155.07456608690077,
"rotateFast": false "rotateFast": false
}, },
"reversed": false, "reversed": false,

View File

@ -28,6 +28,7 @@ import frc.robot.command.GuiderHaut;
import frc.robot.command.Lancer; import frc.robot.command.Lancer;
import frc.robot.command.LancerAmp; import frc.robot.command.LancerAmp;
import frc.robot.command.LancerNote; import frc.robot.command.LancerNote;
import frc.robot.command.LancerTrape;
import frc.robot.command.Lancerampli; import frc.robot.command.Lancerampli;
import frc.robot.command.Limelight_tracker; import frc.robot.command.Limelight_tracker;
import frc.robot.command.PistonFerme; import frc.robot.command.PistonFerme;
@ -93,7 +94,7 @@ public class RobotContainer {
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))); joystick.button(2).whileTrue(new ParallelCommandGroup(new Lancerampli(lanceur,limelight),new Limelight_tracker(limelight,drive)));
joystick.button(6).whileTrue(new LancerTrape(lanceur, accumulateur));
// deplacement // deplacement
configureBindings(); configureBindings();
drive.setDefaultCommand(new RunCommand(()->{ drive.setDefaultCommand(new RunCommand(()->{

View File

@ -0,0 +1,53 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot.command;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystem.Accumulateur;
import frc.robot.subsystem.Lanceur;
public class LancerTrape extends Command {
private Lanceur lancer;
private Accumulateur accumulateur;
/** Creates a new LancerNote. */
public LancerTrape(Lanceur lancer, Accumulateur accumulateur) {
this.lancer = lancer;
this.accumulateur = accumulateur;
addRequirements(lancer);
// Use addRequirements() here to declare subsystem dependencies.
}
// Called when the command is initially scheduled.
@Override
public void initialize() {
lancer.pid();
}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
double vitesse = 0.8;
lancer.Lancertrape();
if(lancer.vitesse(vitesse)>vitesse){
accumulateur.Accumuler();
}
else{
accumulateur.Accumuler(0);
}
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
lancer.lancer(0);
accumulateur.Accumuler(0);
}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}

View File

@ -86,6 +86,9 @@ public class Lanceur extends SubsystemBase {
} }
public void lancerspeaker(){ public void lancerspeaker(){
lancer(vitesse.getDouble(0.8)); lancer(vitesse.getDouble(0.8));
}
public void Lancertrape(){
lancer(vitesse.getDouble(0.8));
} }
public void lanceramp(){ public void lanceramp(){
lancer(vitesseamp.getDouble(0.1)); lancer(vitesseamp.getDouble(0.1));