mettre en 2026
This commit is contained in:
@@ -8,7 +8,6 @@ import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
|
||||
public class Robot extends TimedRobot {
|
||||
private Command m_autonomousCommand;
|
||||
|
||||
@@ -17,7 +17,6 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
|
||||
import frc.robot.commands.Aspirer;
|
||||
import frc.robot.commands.DescendreBalyeuse;
|
||||
import frc.robot.commands.DescendreGrimpeur;
|
||||
@@ -122,7 +121,7 @@ public class RobotContainer {
|
||||
//manette 2
|
||||
manette1.rightTrigger().whileTrue(new Aspirer(balayeuse));
|
||||
manette1.rightBumper().whileTrue(new MonterBalyeuse(balayeuse));
|
||||
manette1.leftTrigger().whileTrue(new LancerBaseVitesse(lanceur, limeLight3G));
|
||||
manette1.leftTrigger().whileTrue(new LancerBaseVitesse(lanceur));
|
||||
manette1.leftBumper().whileTrue(new DescendreBalyeuse(balayeuse));
|
||||
manette1.x().whileTrue(new LancerAspirer(lanceur, balayeuse, limeLight3G));
|
||||
manette1.b().whileTrue(new ModeOposer(lanceur));
|
||||
|
||||
@@ -4,10 +4,8 @@
|
||||
|
||||
package frc.robot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystems.Balayeuse;
|
||||
import frc.robot.subsystems.Led;
|
||||
|
||||
/* 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 Aspirer extends Command {
|
||||
|
||||
@@ -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.Limelight3G;
|
||||
|
||||
/* 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 */
|
||||
@@ -18,15 +16,12 @@ public class Lancer extends Command {
|
||||
private PIDController pidController;
|
||||
private Limelight3G limeLight3G;
|
||||
private Timer timer;
|
||||
private double temp;
|
||||
/** Creates a new Lancer. */
|
||||
public Lancer(Lanceur lanceur, Limelight3G limeLight3G) {
|
||||
this.lanceur = lanceur;
|
||||
this.timer = new Timer();
|
||||
this.limeLight3G = new Limelight3G();
|
||||
addRequirements(lanceur, limeLight3G);
|
||||
|
||||
this.temp = 0;
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
@@ -34,8 +29,7 @@ public class Lancer extends Command {
|
||||
@Override
|
||||
public void initialize() {
|
||||
pidController = new PIDController(0.0007, 0,0, 0.001);
|
||||
timer.reset();
|
||||
temp = lanceur.Amp();
|
||||
timer.reset();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
|
||||
@@ -7,8 +7,6 @@ package frc.robot.commands;
|
||||
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
|
||||
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;
|
||||
|
||||
|
||||
|
||||
@@ -5,25 +5,22 @@
|
||||
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;
|
||||
import frc.robot.subsystems.LimeLight3;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
|
||||
/* 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 Limelight3G limeLight3G;
|
||||
private Timer timer;
|
||||
private double temp;
|
||||
double tempsDebut = 0;
|
||||
/** Creates a new Lancer. */
|
||||
public LancerBaseVitesse(Lanceur lanceur, Limelight3G limeLight3G) {
|
||||
public LancerBaseVitesse(Lanceur lanceur) {
|
||||
this.lanceur = lanceur;
|
||||
this.timer = new Timer();
|
||||
this.limeLight3G = new Limelight3G();
|
||||
addRequirements(lanceur, limeLight3G);
|
||||
addRequirements(lanceur);
|
||||
//this.temp = 0;
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
@@ -34,38 +31,18 @@ public class LancerBaseVitesse extends Command {
|
||||
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.
|
||||
@Override
|
||||
public void execute() {
|
||||
// int nbFois = 0;
|
||||
|
||||
// double moyenneAmp = 0;
|
||||
// if(timer.get() < 3){
|
||||
// nbFois++;
|
||||
// moyenneAmp += balayeuse.Amp() / nbFois;
|
||||
// }
|
||||
// else{
|
||||
// nbFois++;
|
||||
// moyenneAmp -= temp;
|
||||
// moyenneAmp += balayeuse.Amp() / nbFois;
|
||||
// temp = balayeuse.Amp();
|
||||
// }
|
||||
// if(moyenneAmp > 30 && nbFois > 10){
|
||||
// timer.reset();
|
||||
// balayeuse.Balayer(0.5);
|
||||
// led.Jaune2();
|
||||
// }
|
||||
// else{
|
||||
System.out.println(DriverStation.getMatchTime());
|
||||
double vitesse = lanceur.vitesseDemander();
|
||||
double output = pidController.calculate(lanceur.Vitesse(),vitesse);
|
||||
lanceur.Lancer(output);
|
||||
if(timer.get() >1){
|
||||
if(timer.get() > 1){
|
||||
lanceur.Demeler(1);
|
||||
}
|
||||
// }
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -7,7 +7,6 @@ package frc.robot.commands;
|
||||
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
@@ -16,7 +15,6 @@ import static edu.wpi.first.units.Units.*;
|
||||
|
||||
/* 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 Limelighter extends Command {
|
||||
Timer timer;
|
||||
Limelight3G limelight3g;
|
||||
CommandSwerveDrivetrain drivetrain;
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
@@ -34,20 +32,18 @@ public class Limelighter extends Command {
|
||||
this.limelight3g = limelight3g;
|
||||
this.drivetrain = drivetrain;
|
||||
addRequirements(drivetrain, limelight3g);
|
||||
timer = new Timer();
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
timer.reset();
|
||||
}
|
||||
public void initialize() {}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
double[] BotPose = new double[6];
|
||||
System.out.println("e");
|
||||
if (limelight3g.getV()) {
|
||||
BotPose = limelight3g.getBotPoseBlue();
|
||||
botx = BotPose[1];
|
||||
@@ -61,12 +57,6 @@ public class Limelighter extends Command {
|
||||
drive.withVelocityX(0).withVelocityY(0).withRotationalRate(calcul));
|
||||
System.out.println(calcul);
|
||||
if (calcul < 0.2 && calcul > -0.2) {
|
||||
// timer.start();
|
||||
// } else {
|
||||
// timer.reset();
|
||||
// }
|
||||
// } else {
|
||||
// timer.stop();
|
||||
drivetrain.setControl(drive.withRotationalRate(0));
|
||||
}
|
||||
}
|
||||
@@ -80,7 +70,6 @@ public class Limelighter extends Command {
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
drivetrain.setControl(drive.withRotationalRate(0));
|
||||
timer.stop();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
|
||||
@@ -50,18 +50,12 @@ public class RetourMilieuDroite extends Command {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
double[] BotPose = new double[6];
|
||||
BotPose = limelight3g.getBotPoseBlue();
|
||||
botx = BotPose[0];
|
||||
boty = BotPose[1];
|
||||
|
||||
if(alliance.get() == Alliance.Blue){
|
||||
angle = 0;
|
||||
}
|
||||
else{
|
||||
angle = 180;
|
||||
}
|
||||
if(pigeon2.getYaw().getValueAsDouble() <355 || pigeon2.getYaw().getValueAsDouble() > 5){
|
||||
if(pigeon2.getYaw().getValueAsDouble() >0 && pigeon2.getYaw().getValueAsDouble() <180){
|
||||
drivetrain.setControl(drive.withRotationalRate(0.5));
|
||||
}
|
||||
@@ -69,9 +63,6 @@ public class RetourMilieuDroite extends Command {
|
||||
drivetrain.setControl(drive.withRotationalRate(-0.5));
|
||||
}
|
||||
}
|
||||
else{
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
|
||||
@@ -6,7 +6,6 @@ package frc.robot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.subsystems.Balayeuse;
|
||||
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 ModeOposerBalayeuse extends Command {
|
||||
private Balayeuse balayeuse;
|
||||
|
||||
@@ -248,12 +248,12 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
if(pigeon2.getYaw().getValueAsDouble() > 360){
|
||||
pigeon2.setYaw(pigeon2.getYaw().getValueAsDouble()-360);
|
||||
}
|
||||
else if(pigeon2.getYaw().getValueAsDouble() < 0){
|
||||
pigeon2.setYaw(pigeon2.getYaw().getValueAsDouble()+360);
|
||||
}
|
||||
// if(getPigeon2().getYaw().getValueAsDouble() > 360){
|
||||
// getPigeon2().setYaw(getPigeon2().getYaw().getValueAsDouble()-360);
|
||||
// }
|
||||
// else if(getPigeon2().getYaw().getValueAsDouble() < 0){
|
||||
// getPigeon2().setYaw(getPigeon2().getYaw().getValueAsDouble()+360);
|
||||
// }
|
||||
|
||||
/*
|
||||
* Periodically try to apply the operator perspective.
|
||||
|
||||
@@ -4,14 +4,11 @@
|
||||
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import java.util.Optional;
|
||||
|
||||
import com.ctre.phoenix.led.CANdle;
|
||||
import com.ctre.phoenix.led.RainbowAnimation;
|
||||
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
@@ -21,67 +18,76 @@ public class Led extends SubsystemBase {
|
||||
ShuffleboardTab teb = Shuffleboard.getTab("teb");
|
||||
private GenericEntry equipe =
|
||||
teb.add("equipe commence (bleu = ouvert, rouge = fermé)", true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
|
||||
@SuppressWarnings("removal")
|
||||
CANdle CANDle = new CANdle(17);
|
||||
@SuppressWarnings("removal")
|
||||
RainbowAnimation rainbowAnim = new RainbowAnimation();
|
||||
@SuppressWarnings("removal")
|
||||
public void bleu(){
|
||||
CANDle.setLEDs(0, 0, 255,0,0,8);
|
||||
CANDle.setLEDs(0, 0, 255,0,16,8);
|
||||
CANDle.setLEDs(0, 0, 255,0,32,8);
|
||||
CANDle.setLEDs(0, 0, 255,0,56,8);
|
||||
CANDle.setLEDs(0, 0, 255,0,72,8);
|
||||
CANDle.setLEDs(0, 0, 255,0,88,8);
|
||||
CANDle.setLEDs(0, 0, 255,0,104,8);
|
||||
CANDle.setLEDs(0, 0, 255,0,120,8);
|
||||
CANDle.setLEDs(0, 0, 255,0,136,8);
|
||||
// CANDle.setLEDs(0, 0, 255,0,56,8);
|
||||
// CANDle.setLEDs(0, 0, 255,0,72,8);
|
||||
// CANDle.setLEDs(0, 0, 255,0,88,8);
|
||||
// CANDle.setLEDs(0, 0, 255,0,104,8);
|
||||
// CANDle.setLEDs(0, 0, 255,0,120,8);
|
||||
// CANDle.setLEDs(0, 0, 255,0,136,8);
|
||||
|
||||
}
|
||||
@SuppressWarnings("removal")
|
||||
public void Vert1(){
|
||||
CANDle.setLEDs(0, 255, 0,0,0,8);
|
||||
CANDle.setLEDs(0, 255, 0,0,16,8);
|
||||
CANDle.setLEDs(0, 255, 0,0,32,8);
|
||||
CANDle.setLEDs(0, 255, 0,0,56,8);
|
||||
CANDle.setLEDs(0, 255, 0,0,72,8);
|
||||
CANDle.setLEDs(0, 255, 0,0,88,8);
|
||||
CANDle.setLEDs(0, 255, 0,0,104,8);
|
||||
CANDle.setLEDs(0, 255, 0,0,120,8);
|
||||
CANDle.setLEDs(0, 255, 0,0,136,8);
|
||||
// CANDle.setLEDs(0, 255, 0,0,56,8);
|
||||
// CANDle.setLEDs(0, 255, 0,0,72,8);
|
||||
// CANDle.setLEDs(0, 255, 0,0,88,8);
|
||||
// CANDle.setLEDs(0, 255, 0,0,104,8);
|
||||
// CANDle.setLEDs(0, 255, 0,0,120,8);
|
||||
// CANDle.setLEDs(0, 255, 0,0,136,8);
|
||||
}
|
||||
@SuppressWarnings("removal")
|
||||
public void Rouge(){
|
||||
CANDle.setLEDs(255, 0, 0,0,0,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,16,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,32,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,48,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,64,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,80,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,96,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,112,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,128,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,48,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,64,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,80,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,96,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,112,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,128,8);
|
||||
}
|
||||
@SuppressWarnings("removal")
|
||||
public void Jaune2(){
|
||||
CANDle.setLEDs(255, 255, 0,0,8,8);
|
||||
CANDle.setLEDs(255, 255, 0,0,24,8);
|
||||
CANDle.setLEDs(255, 255, 0,0,40,8);
|
||||
CANDle.setLEDs(255, 255, 0,0,56,8);
|
||||
CANDle.setLEDs(255, 255, 0,0,72,8);
|
||||
CANDle.setLEDs(255, 255, 0,0,88,8);
|
||||
CANDle.setLEDs(255, 255, 0,0,104,8);
|
||||
CANDle.setLEDs(255, 255, 0,0,120,8);
|
||||
CANDle.setLEDs(255, 255, 0,0,136,8);
|
||||
// CANDle.setLEDs(255, 255, 0,0,56,8);
|
||||
// CANDle.setLEDs(255, 255, 0,0,72,8);
|
||||
// CANDle.setLEDs(255, 255, 0,0,88,8);
|
||||
// CANDle.setLEDs(255, 255, 0,0,104,8);
|
||||
// CANDle.setLEDs(255, 255, 0,0,120,8);
|
||||
// CANDle.setLEDs(255, 255, 0,0,136,8);
|
||||
}
|
||||
@SuppressWarnings("removal")
|
||||
public void Rouge2(){
|
||||
CANDle.setLEDs(255, 0, 0,0,8,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,24,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,40,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,56,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,72,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,88,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,104,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,120,8);
|
||||
CANDle.setLEDs(255, 0, 0,0,136,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,56,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,72,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,88,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,104,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,120,8);
|
||||
// CANDle.setLEDs(255, 0, 0,0,136,8);
|
||||
}
|
||||
@SuppressWarnings("removal")
|
||||
public void RainBow(){
|
||||
CANDle.animate(rainbowAnim);
|
||||
}
|
||||
@SuppressWarnings("removal")
|
||||
public void RainBowStop(){
|
||||
CANDle.animate(null);
|
||||
}
|
||||
@@ -93,6 +99,7 @@ public class Led extends SubsystemBase {
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
|
||||
double temps = DriverStation.getMatchTime();
|
||||
if(temps > 20 && temps < 30){
|
||||
Vert1();
|
||||
@@ -132,5 +139,7 @@ public class Led extends SubsystemBase {
|
||||
}
|
||||
}
|
||||
// This method will be called once per scheduler run
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user