Compare commits

...

2 Commits

Author SHA1 Message Date
EdwardFaucher
75c59ddbe5 Merge branch 'main' of https://git.demerso.net/PLS5618/pratique-2025 2024-11-13 19:13:35 -05:00
EdwardFaucher
a7a4c4ef31 2024-11-13 19:13:32 -05:00
2 changed files with 22 additions and 5 deletions

View File

@ -4,14 +4,18 @@
package frc.robot.Commands;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.Subsystems.Accumulateur;
import frc.robot.Subsystems.Lanceur;
public class Lancer extends Command {
private Lanceur lanceur;
private Accumulateur accumulateur;
/** Creates a new Lancer. */
public Lancer(Lanceur lanceur) {
public Lancer(Lanceur lanceur,Accumulateur accumulateur) {
this.lanceur = lanceur;
addRequirements(lanceur);
this.accumulateur = accumulateur;
addRequirements(lanceur, accumulateur);
// Use addRequirements() here to declare subsystem dependencies.
}
// Called when the command is initially scheduled.
@ -22,7 +26,10 @@ public class Lancer extends Command {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
lanceur.lance(0.5);
lanceur.lance();
accumulateur.desaccumule(0.2);
}
// Called once the command ends or is interrupted.
@Override

View File

@ -13,10 +13,12 @@ import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkLowLevel.MotorType;
import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
public class Lanceur extends SubsystemBase {
/** Creates a new Lanceur. */
public Lanceur() {dashboard.add("rottourel", 0.2)
@ -27,7 +29,8 @@ public class Lanceur extends SubsystemBase {
final WPI_TalonSRX lanceur1 = new WPI_TalonSRX(0);
final WPI_TalonSRX lanceur2 = new WPI_TalonSRX(1);
final CANSparkMax tourelle = new CANSparkMax(2, MotorType.kBrushed);
final
final DigitalInput limitswitch1 = new DigitalInput(0);
final DigitalInput limitswitch2 = new DigitalInput(1);
private GenericEntry vitesse =
dashboard.add("vitesselanceur", 0.2)
.withSize(0,0)
@ -39,12 +42,13 @@ public class Lanceur extends SubsystemBase {
lanceur2.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative);
lanceur1.setStatusFramePeriod(StatusFrameEnhanced.Status_2_Feedback0, 1);
}
public void masterslave(){
lanceur2.follow(lanceur1);
lanceur2.setInverted(true);
}
public void lance(double vitesse){
lanceur1.set(vitesse);lanceur2.set(vitesse);
lanceur1.set(vitesse);
}
public void lance(){
lance(vitesse.getDouble(0.2));
@ -64,6 +68,12 @@ public class Lanceur extends SubsystemBase {
lanceur1.config_kI(0, i);
lanceur1.config_kD(0, d);
}
public boolean limitswitch1(){
return limitswitch1.get();
}
public boolean limitswitch2(){
return limitswitch2.get();
}
@Override
public void periodic() {
// This method will be called oncehttps://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2024-latest.json per scheduler run