lanceur
This commit is contained in:
@@ -7,9 +7,7 @@ package frc.robot.commands;
|
||||
import edu.wpi.first.math.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystems.Balayeuse;
|
||||
import frc.robot.subsystems.Lanceur;
|
||||
import frc.robot.subsystems.Led;
|
||||
import frc.robot.subsystems.LimeLight3;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
|
||||
@@ -19,28 +17,24 @@ public class LancerBaseVitesse extends Command {
|
||||
private PIDController pidController;
|
||||
private Limelight3G limeLight3G;
|
||||
private Timer timer;
|
||||
private Balayeuse balayeuse;
|
||||
private Led led;
|
||||
private double temp;
|
||||
/** Creates a new Lancer. */
|
||||
public LancerBaseVitesse(Lanceur lanceur, LimeLight3 limeLight3, Balayeuse balayeuse,Led led) {
|
||||
public LancerBaseVitesse(Lanceur lanceur, LimeLight3 limeLight3) {
|
||||
this.lanceur = lanceur;
|
||||
this.balayeuse = balayeuse;
|
||||
this.led = led;
|
||||
this.timer = new Timer();
|
||||
// this.timer = new Timer();
|
||||
this.limeLight3G = new Limelight3G();
|
||||
addRequirements(lanceur, balayeuse, led, limeLight3G);
|
||||
this.temp = 0;
|
||||
addRequirements(lanceur, limeLight3G);
|
||||
//this.temp = 0;
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
pidController = new PIDController(1, 0,0, 0);
|
||||
timer.reset();
|
||||
timer.start();
|
||||
temp = lanceur.Amp();
|
||||
pidController = new PIDController(0.0007, 0,0, 0.001);
|
||||
//timer.reset();
|
||||
//timer.start();
|
||||
//temp = lanceur.Amp();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@@ -65,10 +59,10 @@ public class LancerBaseVitesse extends Command {
|
||||
// led.Jaune2();
|
||||
// }
|
||||
// else{
|
||||
double vitesse = 0.4;
|
||||
double vitesse = lanceur.vitesseDemander();
|
||||
double output = pidController.calculate(lanceur.Vitesse(),vitesse);
|
||||
lanceur.Lancer(output);
|
||||
if(lanceur.Vitesse() >= vitesse){
|
||||
if(lanceur.Vitesse() >= 1200){
|
||||
lanceur.Demeler(0.5);
|
||||
}
|
||||
// }
|
||||
@@ -80,7 +74,6 @@ public class LancerBaseVitesse extends Command {
|
||||
public void end(boolean interrupted) {
|
||||
lanceur.Demeler(0);
|
||||
lanceur.Lancer(0);
|
||||
balayeuse.Pivoter(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
|
||||
Reference in New Issue
Block a user