39 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
c0e7985ab7 mode auto 2025-03-04 17:37:15 -05:00
004890fd7b mode auto 2025-03-04 17:37:01 -05:00
0d63654df8 mode auto 2025-03-04 13:07:57 -05:00
28d5118c1f mode auto 2025-03-04 12:52:13 -05:00
5009a1c928 enlever truc inutil + toggle pour auto 2025-03-04 12:23:57 -05:00
41e7d89919 mode auto fonctionnel 2025-03-04 11:59:17 -05:00
b3c699ccf9 mode auto 2025-03-04 11:44:01 -05:00
8852d0a1b6 mode auto 2025-03-04 11:41:46 -05:00
9ce0d79903 mode auto 2025-03-04 10:23:54 -05:00
a420d3ff2f mode auto 2025-03-04 10:06:12 -05:00
b1124bd3f0 mode auto manuel 2025-03-04 09:34:50 -05:00
9f4142d7aa valeurs encodeurs, sequance, touche, quelque test amperage 2025-03-03 20:32:11 -05:00
263caa4d85 Merge branch 'main' of https://git.demerso.net/PLS5618/Reefscape-2025 2025-03-03 09:43:25 -05:00
e462e83f0e amperage 2025-03-03 09:43:24 -05:00
710e216b91 Merge branch 'main' of https://git.demerso.net/PLS5618/Reefscape-2025 2025-03-03 09:42:24 -05:00
3eb5b75b23 mode automne 2025-03-03 09:42:00 -05:00
264bbd003f touche, amperage, distance 2025-03-03 09:22:48 -05:00
37452f0b05 Merge branch 'main' of https://git.demerso.net/PLS5618/Reefscape-2025 2025-03-01 15:28:12 -05:00
0c701558ec encodeur 2025-03-01 15:27:32 -05:00
b6bd4d9319 bougie dans station pince 2025-03-01 15:10:43 -05:00
94af67a895 jeu L4 2025-03-01 15:05:05 -05:00
8afd6a74a5 Merge branch 'main' of https://git.demerso.net/PLS5618/Reefscape-2025 2025-03-01 15:00:14 -05:00
300c177ae0 touche 2025-03-01 14:53:24 -05:00
0c36717d13 touche 2025-03-01 14:52:56 -05:00
d1f9d55c3a debug 2025-03-01 13:53:13 -05:00
30b0ad39f0 necodeur est mal ecrit 2025-03-01 09:47:30 -05:00
54df3fbd8d Merge branch 'main' of https://git.demerso.net/PLS5618/Reefscape-2025 2025-03-01 09:42:32 -05:00
3999137e3f on utilile pasd ca 2025-03-01 09:42:30 -05:00
5d14c08269 grimpeur manuel 2025-03-01 09:41:31 -05:00
34 changed files with 497 additions and 504 deletions

View File

@ -0,0 +1,63 @@
{
"version": "2025.0",
"command": {
"type": "sequential",
"data": {
"commands": [
{
"type": "path",
"data": {
"pathName": "New Path"
}
},
{
"type": "wait",
"data": {
"waitTime": 2.0
}
},
{
"type": "deadline",
"data": {
"commands": [
{
"type": "wait",
"data": {
"waitTime": 2.0
}
},
{
"type": "named",
"data": {
"name": "baleeuse"
}
}
]
}
},
{
"type": "deadline",
"data": {
"commands": [
{
"type": "wait",
"data": {
"waitTime": 2.0
}
},
{
"type": "named",
"data": {
"name": "baleeuse sort"
}
}
]
}
}
]
}
},
"resetOdom": true,
"folder": null,
"choreoAuto": false
}

File diff suppressed because one or more lines are too long

View File

@ -3,25 +3,25 @@
"waypoints": [
{
"anchor": {
"x": 1.8820696721311476,
"y": 6.0
"x": 7.564241803278687,
"y": 3.899129098360655
},
"prevControl": null,
"nextControl": {
"x": 1.8706512438743716,
"y": 5.690872003047288
"x": 6.506996649367605,
"y": 3.898163120386143
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 1.8820696721311476,
"y": 3.1279999999999997
"x": 6.269569672131147,
"y": 3.899129098360655
},
"prevControl": {
"x": 1.8863317961339294,
"y": 3.3779636659576444
"x": 7.259410179761819,
"y": 3.9002985318003183
},
"nextControl": null,
"isLocked": false,
@ -35,8 +35,8 @@
"globalConstraints": {
"maxVelocity": 3.0,
"maxAcceleration": 3.0,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 720.0,
"maxAngularVelocity": 0.1,
"maxAngularAcceleration": 0.1,
"nominalVoltage": 12.0,
"unlimited": false
},

View File

@ -5,21 +5,21 @@
package frc.robot;
import static edu.wpi.first.units.Units.*;
import java.util.Map;
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
import com.ctre.phoenix6.hardware.Pigeon2;
import com.ctre.phoenix6.swerve.SwerveRequest;
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;
import com.pathplanner.lib.commands.PathPlannerAuto;
import com.pathplanner.lib.util.FlippingUtil;
import edu.wpi.first.cameraserver.CameraServer;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
@ -41,19 +41,31 @@ import frc.robot.commands.Pince.CorailAspir;
import frc.robot.commands.Pince.CoralAlgueInspire;
import frc.robot.commands.Pince.CoralExpire;
import frc.robot.commands.Pince.PinceManuel;
import frc.robot.commands.requin.BalayeuseBas;
import frc.robot.commands.requin.BalayeuseAlgue;
import frc.robot.commands.requin.BalayeuseCoral;
import frc.robot.commands.requin.BalayeuseHaut;
import frc.robot.commands.requin.exspire;
import frc.robot.commands.requin.ExpireCorail;
import frc.robot.commands.requin.L1Requin;
import frc.robot.subsystems.Bougie;
import frc.robot.subsystems.CommandSwerveDrivetrain;
import frc.robot.subsystems.Elevateur;
import frc.robot.subsystems.Grimpeur;
import frc.robot.subsystems.Limelight3;
import frc.robot.subsystems.Limelight3G;
import frc.robot.subsystems.Pince;
import frc.robot.subsystems.Requin;
import frc.robot.commands.requin.exspire;
import frc.robot.commands.Pince.DepartPince;
import frc.robot.commands.Elevateur.balonL2;
import frc.robot.commands.Elevateur.balonL3;
public class RobotContainer {
ShuffleboardLayout layoutauto = Shuffleboard.getTab("teb").getLayout("auto", BuiltInLayouts.kList)
.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 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
@ -68,7 +80,6 @@ public class RobotContainer {
private final CommandXboxController manette2 = new CommandXboxController(1);
private final Pigeon2 gyro = new Pigeon2(13); // ID du Pigeon 2
public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain();
private final SendableChooser<Command> autoChooser;
public double getAngle() {
return gyro.getYaw().getValueAsDouble(); // Retourne l'angle actuel du robot
}
@ -81,60 +92,59 @@ public class RobotContainer {
Limelight3G limelight3g = new Limelight3G();
Limelight3 limelight3 = new Limelight3();
Pose2d pose = new Pose2d();
Grimpeur Grimpeur = new Grimpeur();
Requin requin = new Requin();
CorailAspir corailAspir = new CorailAspir(pince, bougie);
public RobotContainer() {
autoChooser = AutoBuilder.buildAutoChooser("New Auto");
SmartDashboard.putData("Auto Mode", autoChooser);
CameraServer.startAutomaticCapture();
configureBindings();
NamedCommands.registerCommand("AprilTag", new AprilTag3G(limelight3g, drivetrain, null, null));
NamedCommands.registerCommand("Station",new StationPince(pince, elevateur));
NamedCommands.registerCommand("L4", new L4(elevateur, pince));
NamedCommands.registerCommand("L3", new L3(elevateur, pince));
NamedCommands.registerCommand("CoralExpire",new CoralExpire(pince,bougie));
NamedCommands.registerCommand("CoraletAlgue", new CoralAlgueInspire(pince,bougie));
}
private void configureBindings() {
drivetrain.registerTelemetry(logger::telemeterize);
drivetrain.setDefaultCommand(
// Drivetrain will execute this command periodically
drivetrain.applyRequest(() ->
drive.withVelocityX(MathUtil.applyDeadband(-manette1.getLeftX()*manette1.getLeftX()*manette1.getLeftX()*MaxSpeed, 0.05)) // Drive forward with negative Y (forward)
.withVelocityY(MathUtil.applyDeadband(manette1.getLeftY()*manette1.getLeftY()*manette1.getLeftY()*MaxSpeed, 0.05)) // Drive left with negative X (left)
.withRotationalRate(MathUtil.applyDeadband(-manette1.getRightX()*manette1.getRightX()*manette1.getRightX()*MaxAngularRate, 0.05)) // Drive counterclockwise with negative X (left)
drive.withVelocityY(MathUtil.applyDeadband(-manette1.getLeftX()*-manette1.getLeftX()*-manette1.getLeftX()*MaxSpeed, 0.05)) // Drive forward with negative Y (forward)
.withVelocityX(MathUtil.applyDeadband(-manette1.getLeftY()*-manette1.getLeftY()*-manette1.getLeftY()*MaxSpeed, 0.05)) // Drive left with negative X (left)
.withRotationalRate(MathUtil.applyDeadband(-manette1.getRightX()*-manette1.getRightX()*-manette1.getRightX()*MaxAngularRate, 0.05)) // Drive counterclockwise with negative X (left)
)
);
/* Manette 1 */
// reset the field-centric heading on start press
manette1.start().onTrue(drivetrain.runOnce(() -> drivetrain.seedFieldCentric()));
//pince
manette1.rightTrigger().whileTrue(new CoralAlgueInspire(pince, bougie));
manette1.rightBumper().whileTrue(new StationPince(pince, elevateur));
manette1.leftTrigger().whileTrue(new CoralExpire(pince, bougie));
manette1.rightBumper().toggleOnTrue(new StationPince(pince, elevateur,bougie));
manette1.povLeft().whileTrue(new AlgueExpire(pince, bougie));
manette1.leftBumper().whileTrue(new AprilTag3G(limelight3g,drivetrain,manette1::getLeftX,manette1::getLeftY));
manette1.povRight().whileTrue(new CoralExpire(pince, bougie));
manette1.leftTrigger().whileTrue(new DepartPince(pince));
manette1.povDown().whileTrue(new Algue_inspire(pince,bougie));
manette1.leftStick().whileTrue(new CorailAspir(pince, bougie));
//elevateur
manette1.a().whileTrue(new Depart(elevateur, pince));
manette1.b().whileTrue(new L2(elevateur,pince));
manette1.x().whileTrue(new L3(elevateur, pince));
manette1.y().whileTrue(new L4(elevateur, pince));
manette1.a().toggleOnTrue(new Depart(elevateur, pince));
manette1.b().toggleOnTrue(new L2(elevateur,pince));
manette1.x().toggleOnTrue(new L3(elevateur, pince));
manette1.y().toggleOnTrue(new L4(elevateur, pince));
manette1.povUp().toggleOnTrue(new balonL2(elevateur));
manette1.start().toggleOnTrue(new balonL3(elevateur));
/* Manette 2 */
//requin
manette2.a().whileTrue(new CorailAspir(pince,bougie));
manette2.b().whileTrue(new Algue_inspire(pince,bougie));
manette2.y().whileTrue(new BalayeuseHaut(requin));
manette2.x().whileTrue(new BalayeuseBas(requin));
manette2.rightTrigger().whileTrue(new exspire(requin,bougie));
manette2.leftTrigger().whileTrue(new AlgueExpire(pince, bougie));
manette2.rightBumper().whileTrue(new BalayeuseAlgue(requin,bougie));
manette2.leftBumper().whileTrue(new L1Requin(requin, bougie));
manette2.rightTrigger().whileTrue(new BalayeuseHaut(requin));
manette2.leftTrigger().whileTrue(new BalayeuseCoral(requin, bougie));
manette2.y().whileTrue(new exspire(requin, bougie));
manette2.x().whileTrue(new ExpireCorail(requin, bougie));
//limelight
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(), 0.05));
pince.pivote(MathUtil.applyDeadband((manette2.getRightY()*manette2.getRightY()*manette2.getRightY())/3, 0.05));
}, pince));
//Elevateur manuel
@ -142,23 +152,39 @@ public class RobotContainer {
elevateur.vitesse(MathUtil.applyDeadband(manette2.getLeftY()*manette2.getLeftY()*manette2.getLeftY(), 0.05));
}, elevateur));
//limelight
manette2.leftBumper().whileTrue(new AprilTag3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY));
manette2.rightBumper().whileTrue(new Forme3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY));
//Reset encodeur
manette2.start().whileTrue(new reset(elevateur, pince));
manette2.start().whileTrue(new reset(elevateur, pince, requin));
}
public Command getAutonomousCommand() {
return new SequentialCommandGroup(Commands.runOnce(()->{
boolean flip = DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red;
if(flip){
drivetrain.resetPose(FlippingUtil.flipFieldPose(((PathPlannerAuto)autoChooser.getSelected()).getStartingPose()));
}
else{
drivetrain.resetPose(((PathPlannerAuto)autoChooser.getSelected()).getStartingPose());
}
}),autoChooser.getSelected(), new RainBow(bougie));
return new SequentialCommandGroup(
drivetrain.applyRequest(()->
drive.withVelocityX(0.1*MaxSpeed)
.withVelocityY(0)
.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)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(2.35),
drivetrain.applyRequest(()->
drive.withVelocityX(0.1*MaxSpeed)
.withVelocityY(0)
.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),
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

@ -0,0 +1,54 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot.commands;
import static edu.wpi.first.units.Units.*;
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
import com.ctre.phoenix6.swerve.SwerveRequest;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.TunerConstants.TunerConstants;
import frc.robot.subsystems.CommandSwerveDrivetrain;
/* 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 AvancerAuto extends Command {
private CommandSwerveDrivetrain commandSwerveDrivetrain = TunerConstants.createDrivetrain();
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); // kSpeedAt12Volts desired top speed
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); // 3/4 of
private final SwerveRequest.RobotCentric drive = new SwerveRequest.RobotCentric()
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
.withDriveRequestType(DriveRequestType.OpenLoopVoltage);
/** Creates a new AvancerAuto. */
public AvancerAuto(SwerveRequest.RobotCentric drive, CommandSwerveDrivetrain commandSwerveDrivetrain) {
// Use addRequirements() here to declare subsystem dependencies.
}
// Called when the command is initially scheduled.
@Override
public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
commandSwerveDrivetrain.applyRequest(()->
drive.withVelocityY(0.5*MaxSpeed)
.withVelocityX(0)
.withRotationalRate(0));
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
drive.withVelocityY(0);
}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}

View File

@ -11,10 +11,12 @@ import frc.robot.subsystems.Pince;
/* 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 Depart extends Command {
private Elevateur elevateur;
private Pince pince;
/** Creates a new L2. */
public Depart(Elevateur elevateur, Pince pince) {
this.elevateur = elevateur;
addRequirements(elevateur);
this.pince = pince;
addRequirements(elevateur, pince);
// Use addRequirements() here to declare subsystem dependencies.
}
@ -25,6 +27,13 @@ public class Depart extends Command {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(pince.position()){
pince.pivote(0);
pince.reset();
}
else{
pince.pivote(-0.2);
}
if(elevateur.limit2()==true){
elevateur.vitesse(0);
elevateur.reset();
@ -32,13 +41,13 @@ public class Depart extends Command {
else{
elevateur.vitesse(.5);
}
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
elevateur.vitesse(0);
pince.pivote(0);
}
// Returns true when the command should end.

View File

@ -26,24 +26,14 @@ public class L2 extends Command {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(elevateur.position()<=elevateur.encodeurelevateurL2bas() && elevateur.position()>=elevateur.encodeurelevateurL2haut()){
elevateur.vitesse(0);
if(pince.encodeurpivot()>=15 && pince.encodeurpivot()<=16.5){
pince.pivote(0);
}
else if(elevateur.position()>=elevateur.encodeurelevateurL2bas()){
elevateur.vitesse(-0.2);
else if(pince.encodeurpivot()>=15){
pince.pivote(-0.2);
}
else{
elevateur.vitesse(.2);
// }
// if(pince.encodeurpivot()>=500 && pince.encodeurpivot()<=510){
// pince.pivote(0);
// }
// else if(pince.encodeurpivot()>=510){
// pince.pivote(0.2);
// }
// else{
// pince.pivote(-0.2);
pince.pivote(0.1);
}
}

View File

@ -30,22 +30,23 @@ public class L3 extends Command {
public void execute() {
if(elevateur.position()<=elevateur.encodeurelevateurL3bas() && elevateur.position()>=elevateur.encodeurelevateurL3haut()){
elevateur.vitesse(0);
pince.pivote(-0.15);
if(pince.encodeurpivot()>=20 && pince.encodeurpivot()<=21){
pince.pivote(0);
}
else if(elevateur.position()>=elevateur.encodeurelevateurL3bas()){
elevateur.vitesse(-0.2);
else if(pince.encodeurpivot()>=20){
pince.pivote(-0.15);
}
else{
elevateur.vitesse(.2);
pince.pivote(0.15);
}
}
else if(elevateur.position()>=elevateur.encodeurelevateurL3bas()){
elevateur.vitesse(-0.7);
}
else{
elevateur.vitesse(0.25);
}
// if(pince.encodeurpivot()>=700 && pince.encodeurpivot()<=710){
// pince.pivote(0);
// }
// else if(pince.encodeurpivot()>=710){
// pince.pivote(0.2);
// }
// else{
// pince.pivote(-0.2);
// }
}
// Called once the command ends or is interrupted.

View File

@ -29,22 +29,23 @@ public class L4 extends Command {
public void execute() {
if(elevateur.position()<=elevateur.encodeurelevateurL4bas() && elevateur.position()>=elevateur.encodeurelevateurL4haut()){
elevateur.vitesse(0);
pince.pivote(-0.15);
if(pince.encodeurpivot()>=20 && pince.encodeurpivot()<=21){
pince.pivote(0);
}
else if(elevateur.position()>=elevateur.encodeurelevateurL4bas()){
elevateur.vitesse(-0.2);
else if(pince.encodeurpivot()>=20){
pince.pivote(-0.15);
}
else{
elevateur.vitesse(.2);
pince.pivote(0.15);
}
}
else if(elevateur.position()>=elevateur.encodeurelevateurL4bas()){
elevateur.vitesse(-0.7);
}
else{
elevateur.vitesse(.25);
}
// if(pince.encodeurpivot()>=800 && pince.encodeurpivot()<=809){
// pince.pivote(0);
// }
// else if(pince.encodeurpivot()>=810){
// pince.pivote(0.2);
// }
// else{
// pince.pivote(-0.2);
// }
}
// Called once the command ends or is interrupted.

View File

@ -7,6 +7,7 @@ package frc.robot.commands.Elevateur;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Bougie;
import frc.robot.subsystems.Elevateur;
import frc.robot.subsystems.Pince;
@ -15,39 +16,60 @@ public class StationPince extends Command {
ShuffleboardTab teb = Shuffleboard.getTab("teb");
private Pince pince;
private Elevateur elevateur;
private Bougie bougie;
/** Creates a new L2Pince. */
public StationPince(Pince pince,Elevateur elevateur) {
public StationPince(Pince pince,Elevateur elevateur, Bougie bougie) {
this.elevateur = elevateur;
this.pince = pince;
addRequirements(pince,elevateur);
this.bougie = bougie;
addRequirements(pince, elevateur, bougie);
// Use addRequirements() here to declare subsystem dependencies.
}
// Called when the command is initially scheduled.
@Override
public void initialize() {}
public void initialize() {
}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
pince.aspirecoral(0.5);
if(pince.encodeurpivot()<=elevateur.encodeurelevateurstationbas() && pince.encodeurpivot()>=elevateur.encodeurelevateurstationhaut()){
pince.pivote(0);
if(pince.emperagecoral() >= 18){
pince.x = true;
}
else if(pince.encodeurpivot()>=elevateur.encodeurelevateurstationbas()){
pince.pivote(0.2);
}
else{
pince.pivote(-0.2);
}
if(elevateur.position()>=400 && elevateur.position()<=410){
if(elevateur.position()<=-0.4 && elevateur.position()>= -0.5){
elevateur.vitesse(0);
}
else if(elevateur.position()>=410){
elevateur.vitesse(0.3);
else if(elevateur.position()>=-0.4){
elevateur.vitesse(-0.7);
}
else{
elevateur.vitesse(-.3);
elevateur.vitesse(0.25);
}
if(pince.x){
pince.aspirecoral(0);
bougie.Bleu();
pince.pivote(-0.2);
if(pince.position()){
pince.pivote(0);
}
}
else{
pince.aspirecoral(0.25);
}
if (!pince.x){
pince.pivote(-0.15);
if(pince.encodeurpivot()>=10 && pince.encodeurpivot()<=11){
pince.pivote(0);
}
else if(pince.encodeurpivot()>=10.5){
pince.pivote(-0.15);
}
else{
pince.pivote(0.15);
}
}
}
@ -56,6 +78,8 @@ public class StationPince extends Command {
public void end(boolean interrupted) {
pince.pivote(0);
pince.aspirecoral(0);
elevateur.vitesse(0);
pince.x =false;
}
// Returns true when the command should end.

View File

@ -2,22 +2,19 @@
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot.commands.requin;
package frc.robot.commands.Elevateur;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Bougie;
import frc.robot.subsystems.Requin;
import frc.robot.subsystems.Elevateur;
/* 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 aspire extends Command {
/** Creates a new aspire. */
private Requin requin;
private Bougie bougie;
public aspire(Requin requin, Bougie bougie) {
public class balonL2 extends Command {
private Elevateur elevateur;
/** Creates a new L2. */
public balonL2(Elevateur elevateur) {
this.elevateur = elevateur;
addRequirements(elevateur);
// Use addRequirements() here to declare subsystem dependencies.
this.requin = requin;
this.bougie = bougie;
addRequirements(requin, bougie);
}
// Called when the command is initially scheduled.
@ -27,20 +24,21 @@ public class aspire extends Command {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(requin.amp()> 60){
requin.balaye(0);
bougie.Vert();
if(elevateur.position()<=-2 && elevateur.position()>=-2.2){
elevateur.vitesse(0);
}
else
{
requin.balaye(0.5);
else if(elevateur.position()>= -1.95){
elevateur.vitesse(-0.7);
}
else{
elevateur.vitesse(0.25);
}
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
requin.balaye(0);
elevateur.vitesse(0);
}
// Returns true when the command should end.

View File

@ -2,17 +2,18 @@
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot.commands.grimpeur;
package frc.robot.commands.Elevateur;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Grimpeur;
import frc.robot.subsystems.Elevateur;
/* 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 GrimpeurBas extends Command {
private Grimpeur grimpeur;
/** Creates a new GrimpeurBas. */
public GrimpeurBas(Grimpeur grimpeur) {
this.grimpeur = grimpeur;
addRequirements(grimpeur);
public class balonL3 extends Command {
private Elevateur elevateur;
/** Creates a new L2. */
public balonL3(Elevateur elevateur) {
this.elevateur = elevateur;
addRequirements(elevateur);
// Use addRequirements() here to declare subsystem dependencies.
}
@ -23,20 +24,21 @@ public class GrimpeurBas extends Command {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(grimpeur.encodeur()>=-38.5 && grimpeur.encodeur()<=-39.19){
grimpeur.grimpe(0);
if(elevateur.position()<=-4 && elevateur.position()>=-4.1){
elevateur.vitesse(0);
}
else if(grimpeur.encodeur()>=-38.5){
grimpeur.grimpe(-0.5);
else if(elevateur.position()>= -4){
elevateur.vitesse(-0.7);
}
else{grimpeur.grimpe(0.5);
else{
elevateur.vitesse(0.25);
}
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
grimpeur.grimpe(0);
elevateur.vitesse(0);
}
// Returns true when the command should end.

View File

@ -48,10 +48,10 @@ public class AprilTag3G extends Command {
double a = limelight3g.getX();
if(limelight3g.getV() == true){
drivetrain.setControl(drive.
withRotationalRate(-a/5).
withVelocityX(x.getAsDouble()).
withVelocityY(y.getAsDouble()));
System.out.println(a/5);
withRotationalRate(-a/7).
withVelocityY(x.getAsDouble()).
withVelocityX(-y.getAsDouble()));
System.out.println(a/7);
}
else{
drivetrain.setControl(drive.
@ -73,6 +73,6 @@ public class AprilTag3G extends Command {
// Returns true when the command should end.
@Override
public boolean isFinished() {
return limelight3g.getX()<1 && limelight3g.getX()>-1;
return false;
}
}

View File

@ -37,7 +37,6 @@ public class Algue_inspire extends Command {
}
else{
pince.aspirealgue(0.5);
}
}

View File

@ -27,13 +27,16 @@ public class CorailAspir extends Command {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(pince.emperagecoral() > 60){
if(pince.emperagecoral() > 15){
pince.aspirecoral(0);
bougie.Bleu();
}
else{
pince.aspirecoral(0.5);
}
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
@ -43,6 +46,6 @@ public class CorailAspir extends Command {
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
return pince.emperagecoral()>13;
}
}

View File

@ -26,14 +26,14 @@ public class CoralExpire extends Command {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
/* je crois que ce nest pas necessaire
if(pince.emperagecoral() > 60){
pince.aspirecoral(0);
}
else{
*/
pince.aspirecoral(-.5);
bougie.Jaune();
}
}
// Called once the command ends or is interrupted.
@Override

View File

@ -29,7 +29,7 @@ public class DepartPince extends Command {
pince.reset();
}
else{
pince.pivote(.2);
pince.pivote(-0.2);
}
}

View File

@ -1,56 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot.commands.grimpeur;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Bougie;
import frc.robot.subsystems.Grimpeur;
/* 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 GrimperHaut extends Command {
private Grimpeur grimpeur;
private Bougie bougie;
/** Creates a new Grimper. */
public GrimperHaut(Grimpeur grimpeur, Bougie bougie) {
this.grimpeur = grimpeur;
this.bougie = bougie;
addRequirements(grimpeur,bougie);
// Use addRequirements() here to declare subsystem dependencies.
}
// Called when the command is initially scheduled.
@Override
public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(grimpeur.stop()==true){
grimpeur.grimpe(0);
grimpeur.reset();
bougie.RainBow();
}
else{
grimpeur.grimpe(0.5);
bougie.RainBowStop();
}
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
grimpeur.grimpe(0);
if(grimpeur.stop()){
bougie.RainBow();
}
}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return grimpeur.stop()==true;
}
}

View File

@ -1,59 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot.commands.grimpeur;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Bougie;
import frc.robot.subsystems.Grimpeur;
/* 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 GrimpeurManuelhaut extends Command {
private Grimpeur grimpeur;
private Bougie bougie;
/** Creates a new GrimpeurManuel. */
public GrimpeurManuelhaut(Grimpeur grimpeur,Bougie bougie) {
this.grimpeur = grimpeur;
this.bougie = bougie;
addRequirements(grimpeur, bougie);
// Use addRequirements() here to declare subsystem dependencies.
}
// Called when the command is initially scheduled.
@Override
public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(grimpeur.stop()){
bougie.RainBow();
grimpeur.grimpe(-0.5);
}
else{
bougie.RainBowStop();
grimpeur.grimpe(-0.5);
}
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
grimpeur.grimpe(0);
if(grimpeur.stop()){
bougie.RainBow();
}
else{bougie.RainBowStop();}
}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}

View File

@ -1,39 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot.commands.grimpeur;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Grimpeur;
/* 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 ResetGrimpeur extends Command {
private Grimpeur grimpeur;
/** Creates a new ResetGrimpeur. */
public ResetGrimpeur(Grimpeur grimpeur) {
this.grimpeur = grimpeur;
addRequirements(grimpeur);
// Use addRequirements() here to declare subsystem dependencies.
}
// Called when the command is initially scheduled.
@Override
public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
grimpeur.reset();
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}

View File

@ -27,25 +27,28 @@ public class BalayeuseAlgue extends Command {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(requin.encodeur()>=500 && requin.encodeur()<=510)
{
requin.rotationer(0);
if(requin.amp()> 60){
requin.balaye(0);
double cibleMin = 550;
double cibleMax = 650;
if(requin.amp()>=78.2){
requin.xRequin = true;
}
if(requin.xRequin){
bougie.Vert();
requin.balaye(0);
}
else
{
requin.balaye(0.5);
if(!requin.xRequin){
if(requin.encodeur()<=cibleMax && requin.encodeur()>=cibleMin){
requin.rotationer(0);
requin.balaye(-0.4);
}
}
else if(requin.encodeur()>=510){
requin.rotationer(0.5);
else if(requin.encodeur()>=cibleMax){
requin.rotationer(-0.1);
}
else{
requin.rotationer(-0.5);
requin.rotationer(0.3);
}
}
}
// Called once the command ends or is interrupted.
@ -53,6 +56,7 @@ public class BalayeuseAlgue extends Command {
public void end(boolean interrupted) {
requin.rotationer(0);
requin.balaye(0);
requin.xRequin = false;
}
// Returns true when the command should end.

View File

@ -24,7 +24,7 @@ public class BalayeuseBas extends Command {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
requin.rotationer(-0.5);
requin.rotationer(0.2);
}
// Called once the command ends or is interrupted.
@Override

View File

@ -27,29 +27,27 @@ public class BalayeuseCoral extends Command {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(requin.encodeur()>=100 && requin.encodeur()<=110){
requin.rotationer(0);
if(requin.amp()>60){
double cibleMax = 1100;
double cibleMin = 900;
if(requin.amp()>=78.2){
requin.xRequin = true;
}
if(requin.xRequin){
requin.balaye(0);
bougie.Vert();
if(requin.enHaut()){
}
if (!requin.xRequin) {
if(requin.encodeur()<=cibleMax && requin.encodeur()>=cibleMin){
requin.rotationer(0);
requin.balaye(0.7);
}
else{
requin.rotationer(0.5);
}
}
else{
requin.balaye(0.5);
}
}
else if(requin.encodeur()>=110){
requin.rotationer(0.5);
}
else{
else if(requin.encodeur()>=cibleMax){
requin.rotationer(-0.5);
}
else{
requin.rotationer(0.5);
}
}
}
// Called once the command ends or is interrupted.
@ -57,6 +55,7 @@ public class BalayeuseCoral extends Command {
public void end(boolean interrupted) {
requin.rotationer(0);
requin.balaye(0);
requin.xRequin = false;
}
// Returns true when the command should end.

View File

@ -9,12 +9,11 @@ import frc.robot.subsystems.Bougie;
import frc.robot.subsystems.Requin;
/* 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 ExpireAlgue extends Command {
public class ExpireCorail extends Command {
private Requin requin;
private Bougie bougie;
/** Creates a new ExpireAlgue. */
public ExpireAlgue(Requin requin, Bougie bougie
) {
public ExpireCorail(Requin requin, Bougie bougie) {
this.requin = requin;
this.bougie = bougie;
addRequirements(requin,bougie);
@ -29,14 +28,14 @@ public class ExpireAlgue extends Command {
@Override
public void execute() {
if(requin.amp()> 60){
requin.balaye(-0.5);
requin.balaye(-0.1);
}
else
{
bougie.Rouge();
requin.balaye(-0.5);
}
requin.balaye(-0.1);
}
}
// Called once the command ends or is interrupted.
@Override

View File

@ -27,27 +27,15 @@ public class L1Requin extends Command {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(requin.encodeur()>=800 && requin.encodeur()<=810){
if(requin.encodeur()<=485 && requin.encodeur()>=385){
requin.rotationer(0);
if(requin.amp()>60){
requin.balaye(-0.5);
}
else{
requin.balaye(0);
bougie.Rouge();
}
}
else if(requin.encodeur()>=810){
requin.rotationer(0.5);
}
else{
else if(requin.encodeur()>=485){
requin.rotationer(-0.5);
}
else{
requin.rotationer(0.5);
}
}
// Called once the command ends or is interrupted.

View File

@ -29,13 +29,13 @@ public class exspire extends Command {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(requin.amp()> 60){
requin.balaye(-0.5);
}
else
if(requin.amp()> 15)
{
requin.balaye(0.2);
}
else{
bougie.Rouge();
requin.balaye(-0.5);
requin.balaye(0.2);
}
}

View File

@ -7,19 +7,20 @@ package frc.robot.commands;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Elevateur;
import frc.robot.subsystems.Pince;
import frc.robot.subsystems.Requin;
/* 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 reset extends Command {
/** Creates a new reset. */
private Elevateur elevateur;
private Pince pince;
public reset(Elevateur elevateur, Pince pince) {
private Requin requin;
public reset(Elevateur elevateur, Pince pince, Requin requin) {
// Use addRequirements() here to declare subsystem dependencies.
this.elevateur = elevateur;
this.pince = pince;
addRequirements(elevateur,pince);
this.requin = requin;
addRequirements(elevateur,pince, requin);
}
// Called when the command is initially scheduled.
@ -31,6 +32,7 @@ public class reset extends Command {
public void execute() {
elevateur.reset();
pince.reset();
requin.reset();
}
// Called once the command ends or is interrupted.

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, 64);
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;

View File

@ -1,9 +1,6 @@
package frc.robot.subsystems;
import static edu.wpi.first.units.Units.*;
import java.util.function.Supplier;
import com.ctre.phoenix6.SignalLogger;
import com.ctre.phoenix6.Utils;
import com.ctre.phoenix6.swerve.SwerveDrivetrainConstants;
import com.ctre.phoenix6.swerve.SwerveModuleConstants;
@ -44,38 +41,46 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
private final SwerveRequest.ApplyRobotSpeeds m_pathApplyRobotSpeeds = new SwerveRequest.ApplyRobotSpeeds();
/* SysId routine for characterizing translation. This is used to find PID gains for the drive motors. */
private final SwerveRequest.SysIdSwerveTranslation m_translationCharacterization = new SwerveRequest.SysIdSwerveTranslation();
private final SwerveRequest.SysIdSwerveSteerGains m_steerCharacterization = new SwerveRequest.SysIdSwerveSteerGains();
private final SwerveRequest.SysIdSwerveRotation m_rotationCharacterization = new SwerveRequest.SysIdSwerveRotation();
private void configureAutoBuilder() {
try {
var config = RobotConfig.fromGUISettings();
AutoBuilder.configure(
() -> getState().Pose, // Supplier of current robot pose
this::resetPose, // Consumer for seeding pose against auto
() -> getState().Speeds, // Supplier of current robot speeds
// Consumer of ChassisSpeeds and feedforwards to drive the robot
(speeds, feedforwards) -> setControl(
m_pathApplyRobotSpeeds.withSpeeds(speeds)
.withWheelForceFeedforwardsX(feedforwards.robotRelativeForcesXNewtons())
.withWheelForceFeedforwardsY(feedforwards.robotRelativeForcesYNewtons())
),
new PPHolonomicDriveController(
// PID constants for translation
new PIDConstants(63.167, 0, 0.54521),
// PID constants for rotation
new PIDConstants(7.9735, 0, 0.038499)
),
config,
// Assume the path needs to be flipped for Red vs Blue, this is normally the case
() -> DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red,
this // Subsystem for requirements
);
} catch (Exception ex) {
DriverStation.reportError("Failed to load PathPlanner config and configure AutoBuilder", ex.getStackTrace());
}
PPHolonomicDriveController.overrideRotationFeedback(()->{
return 0;
});
}
// private void configureAutoBuilder() {
// try {
// var config = RobotConfig.fromGUISettings();
// AutoBuilder.configure(
// () -> getState().Pose, // Supplier of current robot pose
// this::resetPose, // Consumer for seeding pose against auto
// () -> getState().Speeds, // Supplier of current robot speeds
// // Consumer of ChassisSpeeds and feedforwards to drive the robot
// (speeds, feedforwards) -> setControl(
// m_pathApplyRobotSpeeds.withSpeeds(speeds)
// .withWheelForceFeedforwardsY(feedforwards.robotRelativeForcesXNewtons())
// .withWheelForceFeedforwardsX(feedforwards.robotRelativeForcesYNewtons())
// ),
// new PPHolonomicDriveController(
// // PID constants for translation
// new PIDConstants(63.167, 0, 0.54521),
// // // PID constants for rotation
// // new PIDConstants(7.9735, 0, 0.038499)
// // PID constants for rotation
// new PIDConstants(43.502,0,2.7353)
// ),
// config,
// // Assume the path needs to be flipped for Red vs Blue, this is normally the case
// () -> DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red,
// this // Subsystem for requirements
// );
// } catch (Exception ex) {
// DriverStation.reportError("Failed to load PathPlanner config and configure AutoBuilder", ex.getStackTrace());
// }
// PPHolonomicDriveController.overrideRotationFeedback(()->{
// return 0;
// });
// }
/**
* Constructs a CTRE SwerveDrivetrain using the specified constants.
@ -95,7 +100,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
if (Utils.isSimulation()) {
startSimThread();
}
configureAutoBuilder();
//configureAutoBuilder();
}
/**
@ -120,7 +125,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
if (Utils.isSimulation()) {
startSimThread();
}
configureAutoBuilder();
// configureAutoBuilder();
}
/**
@ -153,7 +158,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
if (Utils.isSimulation()) {
startSimThread();
}
configureAutoBuilder();
//configureAutoBuilder();
}

View File

@ -18,17 +18,19 @@ public class Elevateur extends SubsystemBase {
private GenericEntry encodeurelevateurL2haut =
teb.add("encodeurelevateurL2haut", -0.9).getEntry();
private GenericEntry encodeurelevateurL3bas =
teb.add("ncodeurelevateurL3bas", -2.9).getEntry();
teb.add("encodeurelevateurL3bas", -3).getEntry();
private GenericEntry encodeurelevateurL3haut =
teb.add("encodeurelevateurL3haut", -3).getEntry();
teb.add("encodeurelevateurL3haut", -3.1).getEntry();
private GenericEntry encodeurelevateurL4bas =
teb.add("encodeurelevateurL4bas", -6.4).getEntry();
teb.add("encodeurelevateurL4bas", -6.3).getEntry();
private GenericEntry encodeurelevateurL4haut =
teb.add("encodeurelevateurL4haut", -6.5).getEntry();
private GenericEntry encodeurelevateurstationbas =
teb.add("encodeurelevateursationbas", -0.5).getEntry();
private GenericEntry encodeurelevateurstationhaut =
teb.add("encodeurelevateursationhaut", -0.4).getEntry();
private GenericEntry distanceDeploiePince =
teb.add("encodeurDeploiePince", 0.2).getEntry();
public Elevateur() {
teb.addDouble("encodeur elevateur",this::position);
@ -67,13 +69,13 @@ public class Elevateur extends SubsystemBase {
return encodeurelevateurL2haut.getDouble(-0.9);
}
public double encodeurelevateurL3bas(){
return encodeurelevateurL3bas.getDouble(-2.9);
return encodeurelevateurL3bas.getDouble(-2.8);
}
public double encodeurelevateurL3haut(){
return encodeurelevateurL3haut.getDouble(-3);
}
public double encodeurelevateurL4bas(){
return encodeurelevateurL4bas.getDouble(-6.4);
return encodeurelevateurL4bas.getDouble(-6.3);
}
public double encodeurelevateurL4haut(){
return encodeurelevateurL4haut.getDouble(-6.5);
@ -84,6 +86,10 @@ public class Elevateur extends SubsystemBase {
public double encodeurelevateurstationhaut(){
return encodeurelevateurstationhaut.getDouble(-0.4);
}
public double distanceDeploiePince(){
return distanceDeploiePince.getDouble(0.2);
}
@Override
public void periodic() {

View File

@ -1,40 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot.subsystems;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
public class Grimpeur extends SubsystemBase {
/** Creates a new Grimpeur. */
ShuffleboardTab teb = Shuffleboard.getTab("teb");
public Grimpeur() {
teb.addBoolean("limit grimpeur", this::stop);
teb.addDouble("encodeur grimpeur", this::encodeur);
}
final SparkMax grimpeur = new SparkMax(21,MotorType.kBrushless);
final DigitalInput limit1 = new DigitalInput(2);
public void grimpe(double vitesse){
grimpeur.set(vitesse);
}
public boolean stop(){
return limit1.get();
}
public double encodeur(){
return grimpeur.getEncoder().getPosition();
}
public void reset(){
grimpeur.getEncoder().setPosition(0);
}
@Override
public void periodic() {
// This method will be called once per scheduler run
}
}

View File

@ -17,6 +17,8 @@ public class Pince extends SubsystemBase {
public Pince() {
teb.addBoolean("limit pince",this::position);
teb.addDouble("encodeur pince", this::encodeurpivot);
teb.addDouble("amperage corail", this::emperagecoral);
teb.addDouble("amperage algue", this::emperagealgue);
}
final SparkMax coral = new SparkMax(20, MotorType.kBrushless);
final SparkMax pivoti = new SparkMax(14, MotorType.kBrushless);
@ -30,7 +32,7 @@ public void aspirecoral(double vitesse){
}
public void pivote(double vitesse){
if (position()) {
if (vitesse > 0) {
if (vitesse < 0) {
pivoti.set(0);
}
else{
@ -60,6 +62,7 @@ public double emperagecoral(){
public double emperagealgue(){
return algue1.getOutputCurrent();
}
public boolean x = false;
@Override
public void periodic() {

View File

@ -17,6 +17,8 @@ public class Requin extends SubsystemBase {
ShuffleboardTab teb = Shuffleboard.getTab("teb");
public Requin() {
teb.addBoolean("limit requin", this::enHaut);
teb.addDouble("amparge requin", this::amp);
teb.addDouble("encodeur requin", this::encodeur);
}
final SparkFlex balaye = new SparkFlex(15, MotorType.kBrushless);
@ -41,6 +43,7 @@ public class Requin extends SubsystemBase {
public double amp(){
return balaye.getOutputCurrent();
}
public boolean xRequin = false;
@Override
public void periodic() {
// This method will be called once per scheduler run