Files
Rebuilt-2026/src/main/java/frc/robot/commands/LancerBaseVitesse.java
samuel desharnais 0492c9a2c6 mettre en 2026
2026-03-26 17:45:25 -04:00

64 lines
1.9 KiB
Java

// 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.commands;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Lanceur;
/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
public class LancerBaseVitesse extends Command {
private Lanceur lanceur;
private PIDController pidController;
private Timer timer;
double tempsDebut = 0;
/** Creates a new Lancer. */
public LancerBaseVitesse(Lanceur lanceur) {
this.lanceur = lanceur;
this.timer = new Timer();
addRequirements(lanceur);
//this.temp = 0;
// Use addRequirements() here to declare subsystem dependencies.
}
// Called when the command is initially scheduled.
@Override
public void initialize() {
pidController = new PIDController(0.0007, 0,0, 0.001);
timer.reset();
timer.start();
}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
System.out.println(DriverStation.getMatchTime());
double vitesse = lanceur.vitesseDemander();
double output = pidController.calculate(lanceur.Vitesse(),vitesse);
lanceur.Lancer(output);
if(timer.get() > 1){
lanceur.Demeler(1);
}
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
lanceur.Demeler(0);
lanceur.Lancer(0);
timer.reset();
timer.stop();
}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}