This commit is contained in:
Antoine PerreaultE
2026-03-28 13:21:35 -04:00
8 changed files with 332 additions and 304 deletions

View File

@@ -3,12 +3,12 @@
"waypoints": [ "waypoints": [
{ {
"anchor": { "anchor": {
"x": 3.5473894436519258, "x": 3.602,
"y": 4.015592011412268 "y": 4.015592011412268
}, },
"prevControl": null, "prevControl": null,
"nextControl": { "nextControl": {
"x": 2.494897544356074, "x": 2.549508100704148,
"y": 4.011425161481168 "y": 4.011425161481168
}, },
"isLocked": false, "isLocked": false,
@@ -16,12 +16,12 @@
}, },
{ {
"anchor": { "anchor": {
"x": 1.7359771754636228, "x": 1.643730569948188,
"y": 4.015592011412268 "y": 4.015592011412268
}, },
"prevControl": { "prevControl": {
"x": 2.627549770741877, "x": 2.5679620034542325,
"y": 4.02839075681212 "y": 4.011502590673576
}, },
"nextControl": null, "nextControl": null,
"isLocked": false, "isLocked": false,

View File

@@ -16,12 +16,12 @@
"robotMass": 51.673, "robotMass": 51.673,
"robotMOI": 6.883, "robotMOI": 6.883,
"robotTrackwidth": 0.546, "robotTrackwidth": 0.546,
"driveWheelRadius": 0.099, "driveWheelRadius": 0.051,
"driveGearing": 6.2, "driveGearing": 6.2,
"maxDriveSpeed": 9.82, "maxDriveSpeed": 9.82,
"driveMotorType": "krakenX60", "driveMotorType": "krakenX60",
"driveCurrentLimit": 120.0, "driveCurrentLimit": 120.0,
"wheelCOF": 1.1, "wheelCOF": 1.2,
"flModuleX": 0.288925, "flModuleX": 0.288925,
"flModuleY": 0.269875, "flModuleY": 0.269875,
"frModuleX": 0.288925, "frModuleX": 0.288925,

View File

@@ -33,6 +33,7 @@ import frc.robot.commands.ModeAuto.AspirerAuto;
import frc.robot.commands.ModeAuto.GrimperMur; import frc.robot.commands.ModeAuto.GrimperMur;
import frc.robot.commands.ModeAuto.GrimperReservoir; import frc.robot.commands.ModeAuto.GrimperReservoir;
import frc.robot.commands.ModeAuto.LancerAuto; import frc.robot.commands.ModeAuto.LancerAuto;
import frc.robot.commands.ModeAuto.LimelighterAuto;
import frc.robot.commands.ModeAuto.RetourMilieuDroite; import frc.robot.commands.ModeAuto.RetourMilieuDroite;
import frc.robot.commands.ModeAuto.RetourMilieuGauche; import frc.robot.commands.ModeAuto.RetourMilieuGauche;
import frc.robot.commands.ModeAuto.TournerVersMur; import frc.robot.commands.ModeAuto.TournerVersMur;
@@ -77,7 +78,7 @@ public class RobotContainer {
NamedCommands.registerCommand("Lancer", new LancerAuto(lanceur, limeLight3G)); NamedCommands.registerCommand("Lancer", new LancerAuto(lanceur, limeLight3G));
NamedCommands.registerCommand("RetourMilieuDroite", new RetourMilieuDroite(drivetrain,limeLight3G)); NamedCommands.registerCommand("RetourMilieuDroite", new RetourMilieuDroite(drivetrain,limeLight3G));
NamedCommands.registerCommand("RetourMilieuGauche", new RetourMilieuGauche(drivetrain, limeLight3G)); NamedCommands.registerCommand("RetourMilieuGauche", new RetourMilieuGauche(drivetrain, limeLight3G));
NamedCommands.registerCommand("Limelighter", new Limelighter(limeLight3G,drivetrain)); NamedCommands.registerCommand("Limelighter", new LimelighterAuto(limeLight3G,drivetrain));
NamedCommands.registerCommand("DescendreBalayeuse", new DescendreBalyeuse(balayeuse)); NamedCommands.registerCommand("DescendreBalayeuse", new DescendreBalyeuse(balayeuse));
NamedCommands.registerCommand("Aspirer", new AspirerAuto(balayeuse)); NamedCommands.registerCommand("Aspirer", new AspirerAuto(balayeuse));
NamedCommands.registerCommand("TournerA180", new TournerVersReservoir(drivetrain)); NamedCommands.registerCommand("TournerA180", new TournerVersReservoir(drivetrain));

View File

@@ -4,7 +4,11 @@
package frc.robot.commands; package frc.robot.commands;
import java.util.Optional;
import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Lanceur; import frc.robot.subsystems.Lanceur;
@@ -16,6 +20,11 @@ public class Lancer extends Command {
private PIDController pidController; private PIDController pidController;
private Limelight3G limeLight3G; private Limelight3G limeLight3G;
private Timer timer; private Timer timer;
double vitesse = 0.5;
double botx = 0;
double boty = 0;
Optional<Alliance> alliance = DriverStation.getAlliance();
/** Creates a new Lancer. */ /** Creates a new Lancer. */
public Lancer(Lanceur lanceur, Limelight3G limeLight3G) { public Lancer(Lanceur lanceur, Limelight3G limeLight3G) {
this.lanceur = lanceur; this.lanceur = lanceur;
@@ -28,6 +37,7 @@ public class Lancer extends Command {
// Called when the command is initially scheduled. // Called when the command is initially scheduled.
@Override @Override
public void initialize() { public void initialize() {
if(limeLight3G.getV()){vitesse = 410.57 * ((Math.sqrt(Math.pow(Math.abs(4.625594-botx), 2) + Math.pow(Math.abs(4.034536-boty), 2)))) + 2250;}
pidController = new PIDController(0.0007, 0,0, 0.001); pidController = new PIDController(0.0007, 0,0, 0.001);
timer.reset(); timer.reset();
} }
@@ -35,17 +45,19 @@ public class Lancer extends Command {
// Called every time the scheduler runs while the command is scheduled. // Called every time the scheduler runs while the command is scheduled.
@Override @Override
public void execute() { public void execute() {
double botx = 0;
double boty = 0;
double[] BotPose = new double[6]; double[] BotPose = new double[6];
if(limeLight3G.getV()){ if(limeLight3G.getV()){
BotPose = limeLight3G.getBotPoseBlue();
if(alliance.get() == Alliance.Blue){
BotPose = limeLight3G.getBotPoseBlue();
}
else{
BotPose = limeLight3G.getBotPoseRed();
}
botx = BotPose[0]; botx = BotPose[0];
boty = BotPose[1]; boty = BotPose[1];
} }
double vitesse = 0.5;
if(limeLight3G.getV()){ if(limeLight3G.getV()){
vitesse = 410.57 * ((Math.sqrt(Math.pow(Math.abs(4.625594-botx), 2) + Math.pow(Math.abs(4.034536-boty), 2)))) + 2250;
System.out.println(vitesse); System.out.println(vitesse);
double output = pidController.calculate(lanceur.Vitesse(),vitesse); double output = pidController.calculate(lanceur.Vitesse(),vitesse);

View File

@@ -4,7 +4,11 @@
package frc.robot.commands.ModeAuto; package frc.robot.commands.ModeAuto;
import java.util.Optional;
import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Lanceur; import frc.robot.subsystems.Lanceur;
@@ -18,6 +22,7 @@ public class LancerAuto extends Command {
Limelight3G limelight3g; Limelight3G limelight3g;
double botx = 0; double botx = 0;
double boty = 0; double boty = 0;
Optional<Alliance> alliance = DriverStation.getAlliance();
/** Creates a new LancerAuto. */ /** Creates a new LancerAuto. */
public LancerAuto(Lanceur lanceur, Limelight3G limelight3g) { public LancerAuto(Lanceur lanceur, Limelight3G limelight3g) {
this.lanceur = lanceur; this.lanceur = lanceur;
@@ -38,13 +43,19 @@ public class LancerAuto extends Command {
public void execute() { public void execute() {
double[] BotPose = new double[6]; double[] BotPose = new double[6];
if(limelight3g.getV()){ if(limelight3g.getV()){
BotPose = limelight3g.getBotPoseBlue();
if(alliance.get() == Alliance.Blue){
BotPose = limelight3g.getBotPoseBlue();
}
else{
BotPose = limelight3g.getBotPoseRed();
}
botx = BotPose[0]; botx = BotPose[0];
boty = BotPose[1]; boty = BotPose[1];
} }
double vitesse = 0.5; double vitesse = 0.5;
if(limelight3g.getV()){ if(limelight3g.getV()){
vitesse = 410.57 * ((Math.sqrt(Math.pow(Math.abs(4.625594-botx), 2) + Math.pow(Math.abs(4.034536-boty), 2)))) + 2250; vitesse = 410.57 * ((Math.sqrt(Math.pow(Math.abs(4.625594-botx), 2) + Math.pow(Math.abs(4.034536-boty), 2)))) + 2250;
System.out.println(vitesse); System.out.println(vitesse);
double output = pidController.calculate(lanceur.Vitesse(),vitesse); double output = pidController.calculate(lanceur.Vitesse(),vitesse);

View File

@@ -13,7 +13,10 @@ import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.generated.TunerConstants; import frc.robot.generated.TunerConstants;
import frc.robot.subsystems.CommandSwerveDrivetrain; import frc.robot.subsystems.CommandSwerveDrivetrain;
import frc.robot.subsystems.Limelight3G; import frc.robot.subsystems.Limelight3G;
import static edu.wpi.first.units.Units.*;
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.RadiansPerSecond;
import static edu.wpi.first.units.Units.RotationsPerSecond;
import java.util.Optional; import java.util.Optional;

View File

@@ -82,7 +82,8 @@ public class TunerConstants {
private static final double kDriveGearRatio = 6.122448979591837; private static final double kDriveGearRatio = 6.122448979591837;
private static final double kSteerGearRatio = 21.428571428571427; private static final double kSteerGearRatio = 21.428571428571427;
private static final Distance kWheelRadius = Inches.of(3.895); // private static final Distance kWheelRadius = Inches.of(3.895);
private static final Distance kWheelRadius = Inches.of(2);
private static final boolean kInvertLeftSide = false; private static final boolean kInvertLeftSide = false;
private static final boolean kInvertRightSide = true; private static final boolean kInvertRightSide = true;

View File

@@ -36,7 +36,7 @@ public class Grimpeur extends SubsystemBase {
return limit.get(); return limit.get();
} }
public double PositionFinal(){ public double PositionFinal(){
return EncodeurGrimpeur.getDouble(105); return EncodeurGrimpeur.getDouble(101);
} }
/** Creates a new Grimpeur. */ /** Creates a new Grimpeur. */
public Grimpeur() { public Grimpeur() {