Compare commits
4 Commits
d04817a197
...
main
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
873095e865 | ||
|
|
a142290bd5 | ||
|
|
d73da286ed | ||
|
|
e42464b1d6 |
@@ -71,12 +71,12 @@ public class RobotContainer {
|
||||
autoChooser = AutoBuilder.buildAutoChooser();
|
||||
CameraServer.startAutomaticCapture();
|
||||
configureBindings();
|
||||
NamedCommands.registerCommand("GrimperMur", new GrimperMur());
|
||||
NamedCommands.registerCommand("GrimperReservoir", new GrimperReservoir());
|
||||
NamedCommands.registerCommand("GrimperMur", new GrimperMur(limeLight3,drivetrain));
|
||||
NamedCommands.registerCommand("GrimperReservoir", new GrimperReservoir(limeLight3G,drivetrain));
|
||||
NamedCommands.registerCommand("Lancer", new LancerAuto(lanceur));
|
||||
NamedCommands.registerCommand("RetourMilieuDroite", new RetourMilieuDroite());
|
||||
NamedCommands.registerCommand("RetourMilieuGauche", new RetourMilieuGauche());
|
||||
NamedCommands.registerCommand("Limelighter", new Limelighter());
|
||||
NamedCommands.registerCommand("Limelighter", new Limelighter(limeLight3G,drivetrain));
|
||||
NamedCommands.registerCommand("DescendreBalayeuse", new DescendreBalyeuse(balayeuse));
|
||||
NamedCommands.registerCommand("Aspirer", new AspirerAuto(balayeuse));
|
||||
NamedCommands.registerCommand("TournerAZero", new TournerAZero(drivetrain));
|
||||
@@ -93,6 +93,7 @@ public class RobotContainer {
|
||||
.withRotationalRate(MathUtil.applyDeadband(-manette.getRightX()*Math.abs(-manette.getRightX())*MaxAngularRate, 0.05))
|
||||
)
|
||||
);
|
||||
manette.povUp().whileTrue(new LancerAuto(lanceur));
|
||||
manette.a().whileTrue(new Lancer(lanceur,limeLight3G,balayeuse,led));
|
||||
manette.y().whileTrue(new ModeOposer(lanceur, balayeuse));
|
||||
manette.x().whileTrue(new LancerBaseVitesse(lanceur, limeLight3, balayeuse, led));
|
||||
|
||||
@@ -50,7 +50,7 @@ public class Aspirer extends Command {
|
||||
}
|
||||
if(moyenneAmp < balayeuse.AmpMax()){
|
||||
timer.reset();
|
||||
balayeuse.Balayer(0.5);
|
||||
balayeuse.Balayer(-0.5);
|
||||
}
|
||||
else{
|
||||
balayeuse.Balayer(0);
|
||||
|
||||
@@ -24,7 +24,7 @@ public class DescendreGrimpeur extends Command {
|
||||
@Override
|
||||
public void execute() {
|
||||
if(!grimpeur.Limit()){
|
||||
grimpeur.Grimper(-0.2);
|
||||
grimpeur.Grimper(-0.3);
|
||||
}
|
||||
else{
|
||||
grimpeur.Reset();
|
||||
|
||||
@@ -10,7 +10,6 @@ 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;
|
||||
|
||||
/* 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 */
|
||||
@@ -37,7 +36,7 @@ public class Lancer extends Command {
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
pidController = new PIDController(0, 0,0, 0);
|
||||
pidController = new PIDController(1, 0,0, 0);
|
||||
timer.reset();
|
||||
timer.start();
|
||||
temp = lanceur.Amp();
|
||||
@@ -46,10 +45,14 @@ public class Lancer extends Command {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
double botx = 0;
|
||||
double boty = 0;
|
||||
double[] BotPose = new double[6];
|
||||
BotPose = limeLight3G.getBotPoseBlue();
|
||||
double botx = BotPose[0];
|
||||
double boty = BotPose[1];
|
||||
if(limeLight3G.getV()){
|
||||
BotPose = limeLight3G.getBotPoseBlue();
|
||||
botx = BotPose[0];
|
||||
boty = BotPose[1];
|
||||
}
|
||||
int nbFois = 0;
|
||||
|
||||
double moyenneAmp = 0;
|
||||
@@ -63,21 +66,25 @@ public class Lancer extends Command {
|
||||
moyenneAmp += balayeuse.Amp() / nbFois;
|
||||
temp = balayeuse.Amp();
|
||||
}
|
||||
if(moyenneAmp > lanceur.AmpBas() && nbFois > 10){
|
||||
// if(moyenneAmp > lanceur.AmpBas() && nbFois > 10){
|
||||
timer.reset();
|
||||
balayeuse.Balayer(0.5);
|
||||
led.Jaune2();
|
||||
}
|
||||
else{
|
||||
//pythagore |
|
||||
// \/
|
||||
double vitesse = Math.sqrt(Math.pow(Math.abs(4.625594-botx), 2) + Math.pow(Math.abs(4.034536-boty), 2));
|
||||
double output = pidController.calculate(lanceur.Vitesse(),vitesse);
|
||||
balayeuse.Balayer(-0.5);
|
||||
// led.Jaune2();
|
||||
// }
|
||||
// else{
|
||||
|
||||
double vitesse = 0.5;
|
||||
if(limeLight3G.getV()){
|
||||
//pythagore |
|
||||
// \/
|
||||
vitesse = Math.sqrt(Math.pow(Math.abs(4.625594-botx), 2) + Math.pow(Math.abs(4.034536-boty), 2));
|
||||
}
|
||||
double output = vitesse; /*pidController.calculate(lanceur.Vitesse(),vitesse);*/
|
||||
lanceur.Lancer(output);
|
||||
if(lanceur.Vitesse() >= vitesse){
|
||||
lanceur.Demeler(0.5);
|
||||
}
|
||||
}
|
||||
// }
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -37,7 +37,7 @@ public class LancerBaseVitesse extends Command {
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
pidController = new PIDController(0, 0,0, 0);
|
||||
pidController = new PIDController(1, 0,0, 0);
|
||||
timer.reset();
|
||||
timer.start();
|
||||
temp = lanceur.Amp();
|
||||
@@ -46,32 +46,32 @@ public class LancerBaseVitesse extends Command {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
int nbFois = 0;
|
||||
// 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{
|
||||
// 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{
|
||||
double vitesse = 0.4;
|
||||
double output = pidController.calculate(lanceur.Vitesse(),vitesse);
|
||||
lanceur.Lancer(output);
|
||||
if(lanceur.Vitesse() >= vitesse){
|
||||
lanceur.Demeler(0.5);
|
||||
}
|
||||
}
|
||||
// }
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -4,12 +4,34 @@
|
||||
|
||||
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;
|
||||
import frc.robot.subsystems.Limelight3G;
|
||||
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);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
double botx;
|
||||
double boty;
|
||||
double angle;
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage);
|
||||
/** Creates a new Limelighter. */
|
||||
public Limelighter() {
|
||||
public Limelighter(Limelight3G limelight3g,CommandSwerveDrivetrain drivetrain) {
|
||||
this.limelight3g = limelight3g;
|
||||
this.drivetrain = drivetrain;
|
||||
addRequirements(drivetrain,limelight3g);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
@@ -19,15 +41,31 @@ public class Limelighter extends Command {
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {}
|
||||
public void execute() {
|
||||
double[] BotPose = new double[6];
|
||||
BotPose = limelight3g.getBotPoseBlue();
|
||||
botx = BotPose[0];
|
||||
boty = BotPose[1];
|
||||
angle = BotPose[5];
|
||||
drivetrain.setControl(drive.withRotationalRate(limelight3g.Calcule(4.625594, botx, 4.034536, boty, BotPose[5])/90));
|
||||
if(limelight3g.Calcule(4.625594, botx, 4.034536, boty, angle)/90 < 0.1){
|
||||
timer.start();
|
||||
}
|
||||
else{
|
||||
timer.reset();
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {}
|
||||
public void end(boolean interrupted) {
|
||||
drivetrain.setControl(drive.withRotationalRate(0));
|
||||
timer.stop();
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return timer.get() > 1;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -4,12 +4,37 @@
|
||||
|
||||
package frc.robot.commands.ModeAuto;
|
||||
|
||||
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 com.ctre.phoenix6.hardware.Pigeon2;
|
||||
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
import frc.robot.subsystems.LimeLight3;
|
||||
|
||||
/* 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 GrimperMur extends Command {
|
||||
LimeLight3 limeLight3;
|
||||
CommandSwerveDrivetrain drivetrain;
|
||||
double[] BotPose = new double[6];
|
||||
double botx;
|
||||
double boty;
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
Pigeon2 pigeon2;
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage);
|
||||
/** Creates a new GrimperMur. */
|
||||
public GrimperMur() {
|
||||
public GrimperMur(LimeLight3 limeLight3, CommandSwerveDrivetrain drivetrain) {
|
||||
this.drivetrain = drivetrain;
|
||||
this.limeLight3 = limeLight3;
|
||||
addRequirements(limeLight3,drivetrain);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
@@ -19,15 +44,27 @@ public class GrimperMur extends Command {
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {}
|
||||
public void execute() {
|
||||
BotPose = limeLight3.getBotPoseBlue();
|
||||
botx = BotPose[0];
|
||||
boty = BotPose[1];
|
||||
if(180-pigeon2.getYaw().getValueAsDouble() < 10 && 180- pigeon2.getYaw().getValueAsDouble() > -10){
|
||||
drivetrain.setControl(drive.withVelocityX(2.961328-boty).withVelocityY(1.11-botx));
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(drive.withRotationalRate(180-pigeon2.getYaw().getValueAsDouble()/45));
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {}
|
||||
public void end(boolean interrupted) {
|
||||
drivetrain.setControl(drive.withVelocityX(0).withVelocityY(0).withRotationalRate(0));
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return (2.961328-boty < 0.05 || 2.961328-boty >-0.05) && (1.11-botx < 0.05 || 1.11-botx > -0.05);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -4,12 +4,37 @@
|
||||
|
||||
package frc.robot.commands.ModeAuto;
|
||||
|
||||
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 com.ctre.phoenix6.hardware.Pigeon2;
|
||||
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
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 GrimperReservoir extends Command {
|
||||
/** Creates a new GrimperReservoir. */
|
||||
public GrimperReservoir() {
|
||||
Limelight3G limeLight3G;
|
||||
CommandSwerveDrivetrain drivetrain;
|
||||
double[] BotPose = new double[6];
|
||||
double botx;
|
||||
double boty;
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
|
||||
Pigeon2 pigeon2;
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage);
|
||||
/** Creates a new GrimperMur. */
|
||||
public GrimperReservoir(Limelight3G limeLight3G, CommandSwerveDrivetrain drivetrain) {
|
||||
this.drivetrain = drivetrain;
|
||||
this.limeLight3G = limeLight3G;
|
||||
addRequirements(limeLight3G,drivetrain);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
@@ -19,15 +44,27 @@ public class GrimperReservoir extends Command {
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {}
|
||||
public void execute() {
|
||||
BotPose = limeLight3G.getBotPoseBlue();
|
||||
botx = BotPose[0];
|
||||
boty = BotPose[1];
|
||||
if(0-pigeon2.getYaw().getValueAsDouble() < 10 && 0- pigeon2.getYaw().getValueAsDouble() > -10){
|
||||
drivetrain.setControl(drive.withVelocityX(5.081328-boty).withVelocityY(1.11-botx));
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(drive.withRotationalRate(0-pigeon2.getYaw().getValueAsDouble()/45));
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {}
|
||||
public void end(boolean interrupted) {
|
||||
drivetrain.setControl(drive.withVelocityX(0).withVelocityY(0).withRotationalRate(0));
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
return 5.081328-boty < 0.05 || 5.081328-boty >-0.05 && 1.11-botx < 0.05 || 1.11-botx > -0.05;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -15,6 +15,7 @@ public class LancerAuto extends Command {
|
||||
/** Creates a new LancerAuto. */
|
||||
public LancerAuto(Lanceur lanceur) {
|
||||
this.lanceur = lanceur;
|
||||
addRequirements(lanceur);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
@@ -28,12 +29,16 @@ public class LancerAuto extends Command {
|
||||
@Override
|
||||
public void execute() {
|
||||
lanceur.Lancer(0.5);
|
||||
if(timer.get() > 1){
|
||||
lanceur.Demeler(0.5);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
lanceur.Lancer(0);
|
||||
lanceur.Demeler(0);
|
||||
timer.reset();
|
||||
timer.stop();
|
||||
}
|
||||
|
||||
@@ -25,7 +25,7 @@ public class MonterGrimpeur extends Command {
|
||||
public void execute() {
|
||||
|
||||
if(Math.abs(grimpeur.Position()) < grimpeur.PositionFinal()){
|
||||
grimpeur.Grimper(0.2);
|
||||
grimpeur.Grimper(0.3);
|
||||
System.out.println("monte");
|
||||
}
|
||||
else {
|
||||
|
||||
@@ -21,7 +21,7 @@ public class Grimpeur extends SubsystemBase {
|
||||
SparkMaxConfig slaveConfig = new SparkMaxConfig();
|
||||
DigitalInput limit = new DigitalInput(0);
|
||||
private GenericEntry EncodeurGrimpeur =
|
||||
teb.add("Position haut grimpeur", 10).getEntry();
|
||||
teb.add("Position haut grimpeur", 105).getEntry();
|
||||
public void Grimper(double vitesse){
|
||||
grimpeur1.set(vitesse);
|
||||
grimpeur2.set(vitesse);
|
||||
@@ -36,7 +36,7 @@ public class Grimpeur extends SubsystemBase {
|
||||
return limit.get();
|
||||
}
|
||||
public double PositionFinal(){
|
||||
return EncodeurGrimpeur.getDouble(10);
|
||||
return EncodeurGrimpeur.getDouble(105);
|
||||
}
|
||||
/** Creates a new Grimpeur. */
|
||||
public Grimpeur() {
|
||||
|
||||
@@ -18,12 +18,12 @@ public class Lanceur extends SubsystemBase {
|
||||
SparkFlex moteur2 = new SparkFlex(18, MotorType.kBrushless);
|
||||
SparkFlex Demeleur = new SparkFlex(19, MotorType.kBrushless);
|
||||
GenericEntry vitesse =
|
||||
teb.add("vitesse lanceur",100).getEntry();
|
||||
teb.add("vitesse lanceur",0.5).getEntry();
|
||||
GenericEntry AmpLanceur =
|
||||
teb.add("ampérage lanceur",30).getEntry();
|
||||
public void Lancer(double vitesse){
|
||||
moteur1.set(vitesse);
|
||||
moteur2.set(-vitesse);
|
||||
// moteur1.set(-vitesse);
|
||||
moteur2.set(vitesse);
|
||||
}
|
||||
public void Demeler(double vitesse){
|
||||
Demeleur.set(vitesse);
|
||||
@@ -38,7 +38,7 @@ public class Lanceur extends SubsystemBase {
|
||||
return AmpLanceur.getDouble(30);
|
||||
}
|
||||
public double vitesseDemander(){
|
||||
return vitesse.getDouble(100);
|
||||
return vitesse.getDouble(0.5);
|
||||
}
|
||||
/** Creates a new Lanceur. */
|
||||
public Lanceur() {
|
||||
|
||||
Reference in New Issue
Block a user