10 Commits

Author SHA1 Message Date
172d3c92ab led 2025-04-07 12:06:05 -04:00
80e1f22ea3 plus structurer 2025-03-19 12:08:35 -04:00
792d780d89 mode auto unutile 2025-03-19 12:03:48 -04:00
398ea4ac82 elevateur va mieux 2025-03-12 17:23:59 -04:00
59a44ada9a mode auto L4 2025-03-07 10:04:39 -05:00
0878a276dd mode auto L4 2025-03-07 10:00:15 -05:00
bb9870732c Merge branch 'main' of https://git.demerso.net/PLS5618/Reefscape-2025 2025-03-07 09:06:40 -05:00
c4704210b9 derniere modif de compe 2025-03-07 09:06:10 -05:00
63313b3b7a Merge branch 'main' of https://git.demerso.net/PLS5618/Reefscape-2025 2025-03-06 15:47:09 -05:00
7de77db146 mode auto 2025-03-06 15:47:04 -05:00
6 changed files with 39 additions and 31 deletions

View File

@ -63,13 +63,14 @@ public class RobotContainer {
.withSize(2, 2).withProperties(Map.of("Label position", "LEFT"));
GenericEntry L1 = layoutauto.add("choix L1",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
GenericEntry sortirAngle = layoutauto.add("Cote?",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
GenericEntry Reculer = layoutauto.add("Reculer",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
GenericEntry ReculerB = layoutauto.add("ReculerB",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
GenericEntry ReculerR = layoutauto.add("ReculerR",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
GenericEntry L4 = layoutauto.add("L4",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); // kSpeedAt12Volts desired top speed
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); // 3/4 of a rotation per second max angular velocity
/* Setting up bindings for necessary control of the swerve drive platform */
private final SwerveRequest.RobotCentric drive = new SwerveRequest.RobotCentric()
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband
.withDriveRequestType(DriveRequestType.OpenLoopVoltage
); // Use open-loop control for drive motors
@ -141,14 +142,14 @@ public class RobotContainer {
manette2.a().whileTrue(new Forme3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY));
manette2.b().whileTrue(new AprilTag3(limelight3, drivetrain, manette1::getLeftX, manette1::getLeftY));
//Pince manuel
pince.setDefaultCommand(new RunCommand(()->{
pince.pivote(MathUtil.applyDeadband((manette2.getRightY()*manette2.getRightY()*manette2.getRightY())/3, 0.05));
//Pince manuel
pince.setDefaultCommand(new RunCommand(()->{
pince.pivote(MathUtil.applyDeadband((manette2.getRightY()*manette2.getRightY()*manette2.getRightY())/3, 0.05));
}, pince));
//Elevateur manuel
elevateur.setDefaultCommand(new RunCommand(()->{
elevateur.vitesse(MathUtil.applyDeadband(manette2.getLeftY()*manette2.getLeftY()*manette2.getLeftY(), 0.05));
elevateur.vitesse(MathUtil.applyDeadband(manette2.getLeftY()*manette2.getLeftY()*manette2.getLeftY(), 0.05));
}, elevateur));
//Reset encodeur
@ -158,31 +159,30 @@ public class RobotContainer {
public Command getAutonomousCommand() {
return new SequentialCommandGroup(
drivetrain.applyRequest(()->
drive.withVelocityX(-0.1*MaxSpeed)
drive.withVelocityX(0.1*MaxSpeed)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!Reculer.getBoolean(true)).withTimeout(3.5),
.withRotationalRate(0)).unless(()->!ReculerR.getBoolean(true)).withTimeout(3.5),
drivetrain.applyRequest(()->
drive.withVelocityX(-0.1*MaxSpeed)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!ReculerB.getBoolean(true)).withTimeout(3.5),
drivetrain.applyRequest(()->
drive.withVelocityX(0.1*MaxSpeed)
drive.withVelocityX(-0.1*MaxSpeed)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(3.5),
.withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(2.35),
drivetrain.applyRequest(()->
drive.withVelocityX(-0.1*MaxSpeed)
drive.withVelocityX(0.1*MaxSpeed)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!sortirAngle.getBoolean(true)).withTimeout(3),
.withRotationalRate(0)).unless(()->!sortirAngle.getBoolean(true)|| !ReculerR.getBoolean(true)).withTimeout(3),
drivetrain.applyRequest(()->
drive.withVelocityX(-0.1*MaxSpeed)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!sortirAngle.getBoolean(true)|| !ReculerB.getBoolean(true)).withTimeout(3),
drivetrain.applyRequest(()->
drive.withVelocityX(0)
.withVelocityY(0)
.withRotationalRate(0)).withTimeout(0.1),
new L4(elevateur, pince).unless(()->!L4.getBoolean(true)).withTimeout(4),
drivetrain.applyRequest(()->
drive.withVelocityX(0.1*MaxSpeed)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(0.25),
drivetrain.applyRequest(()->
drive.withVelocityX(0*MaxSpeed)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(2),
new CoralExpire(pince, bougie).unless(()->!L4.getBoolean(true)).withTimeout(2),
new L1Requin(requin, bougie).unless(()-> !L1.getBoolean(true)).withTimeout(2),
new ExpireCorail(requin, bougie).unless(()->!L1.getBoolean(true)).withTimeout(2),
new RainBow(bougie));

View File

@ -78,7 +78,7 @@ public class TunerConstants {
// Theoretical free speed (m/s) at 12 V applied output;
// This needs to be tuned to your individual robot
public static final LinearVelocity kSpeedAt12Volts = MetersPerSecond.of(5.21);
public static final LinearVelocity kSpeedAt12Volts = MetersPerSecond.of(6);
// Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns;
// This may need to be tuned to your individual robot

View File

@ -38,13 +38,13 @@ public class StationPince extends Command {
if(pince.emperagecoral() >= 18){
pince.x = true;
}
if(elevateur.position()<=-0.1 && elevateur.position()>= -0.2){
if(elevateur.position()<=-0.4 && elevateur.position()>= -0.5){
elevateur.vitesse(0);
}
else if(elevateur.position()>=-0.1){
else if(elevateur.position()>=-0.4){
elevateur.vitesse(-0.7);
}
else{
else{
elevateur.vitesse(0.25);
}
if(pince.x){
@ -55,7 +55,7 @@ public class StationPince extends Command {
pince.pivote(0);
}
}
else{
else{
pince.aspirecoral(0.25);
}

View File

@ -28,12 +28,12 @@ public class ExpireCorail extends Command {
@Override
public void execute() {
if(requin.amp()> 60){
requin.balaye(-0.2);
requin.balaye(-0.1);
}
else
{
bougie.Rouge();
requin.balaye(-0.2);
requin.balaye(-0.1);
}
}

View File

@ -31,11 +31,11 @@ public class exspire extends Command {
public void execute() {
if(requin.amp()> 15)
{
requin.balaye(0.4);
requin.balaye(0.2);
}
else{
bougie.Rouge();
requin.balaye(0.4);
requin.balaye(0.2);
}
}

View File

@ -6,14 +6,22 @@ package frc.robot.subsystems;
import com.ctre.phoenix.led.CANdle;
import com.ctre.phoenix.led.CANdleConfiguration;
import com.ctre.phoenix.led.FireAnimation;
import com.ctre.phoenix.led.LarsonAnimation;
import com.ctre.phoenix.led.RainbowAnimation;
import com.ctre.phoenix.led.TwinkleAnimation;
import com.ctre.phoenix.led.TwinkleOffAnimation;
import com.ctre.phoenix.led.TwinkleOffAnimation.TwinkleOffPercent;
import com.ctre.phoenix.led.LarsonAnimation.BounceMode;
import com.ctre.phoenix.led.TwinkleAnimation.TwinklePercent;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
public class Bougie extends SubsystemBase {
CANdle candle = new CANdle(23);
CANdleConfiguration config = new CANdleConfiguration();
RainbowAnimation rainbowAnim = new RainbowAnimation(1, 0.5, 68);
LarsonAnimation rainbowAnim = new LarsonAnimation(256,0,0,0,0.1,68,BounceMode.Front,10,8);
//TwinkleOffAnimation rainbowAnim = new TwinkleOffAnimation(256, 0, 0,0,0.5,68,TwinkleOffPercent.Percent88,8);
/** Creates a new Bougie. */
public Bougie() {
config.brightnessScalar = 0.5;