mode auto
This commit is contained in:
		| @@ -19,6 +19,7 @@ import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets; | |||||||
| import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; | import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; | ||||||
| import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout; | import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout; | ||||||
| import edu.wpi.first.wpilibj2.command.Command; | import edu.wpi.first.wpilibj2.command.Command; | ||||||
|  | import edu.wpi.first.wpilibj2.command.ParallelCommandGroup; | ||||||
| import edu.wpi.first.wpilibj2.command.RunCommand; | import edu.wpi.first.wpilibj2.command.RunCommand; | ||||||
| import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; | import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; | ||||||
| import edu.wpi.first.wpilibj2.command.button.CommandXboxController; | import edu.wpi.first.wpilibj2.command.button.CommandXboxController; | ||||||
| @@ -78,7 +79,6 @@ public class RobotContainer { | |||||||
|   private final CommandXboxController manette2 = new CommandXboxController(1); |   private final CommandXboxController manette2 = new CommandXboxController(1); | ||||||
|   private final Pigeon2 gyro = new Pigeon2(13); // ID du Pigeon 2 |   private final Pigeon2 gyro = new Pigeon2(13); // ID du Pigeon 2 | ||||||
|   public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain(); |   public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain(); | ||||||
|   //private final SendableChooser<Command> autoChooser; |  | ||||||
|   public double getAngle() { |   public double getAngle() { | ||||||
|     return gyro.getYaw().getValueAsDouble(); // Retourne l'angle actuel du robot |     return gyro.getYaw().getValueAsDouble(); // Retourne l'angle actuel du robot | ||||||
|   } |   } | ||||||
| @@ -160,24 +160,24 @@ public class RobotContainer { | |||||||
|         drivetrain.applyRequest(()-> |         drivetrain.applyRequest(()-> | ||||||
|         drive.withVelocityX(-0.1*MaxSpeed) |         drive.withVelocityX(-0.1*MaxSpeed) | ||||||
|        .withVelocityY(0) |        .withVelocityY(0) | ||||||
|        .withRotationalRate(0)).unless(()->!Reculer.getBoolean(true)).withTimeout(3), |        .withRotationalRate(0)).unless(()->!Reculer.getBoolean(true)).withTimeout(3.5), | ||||||
|       drivetrain.applyRequest(()-> |         drivetrain.applyRequest(()-> | ||||||
|       drive.withVelocityX(0.5*MaxSpeed) |          drive.withVelocityX(0.1*MaxSpeed) | ||||||
|      .withVelocityY(0) |         .withVelocityY(0) | ||||||
|      .withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(3), |         .withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(3.5), | ||||||
|      drivetrain.applyRequest(()-> |      drivetrain.applyRequest(()-> | ||||||
|      drive.withVelocityX(-0.5*MaxSpeed) |      drive.withVelocityX(-0.1*MaxSpeed) | ||||||
|     .withVelocityY(0) |     .withVelocityY(0) | ||||||
|     .withRotationalRate(0)).unless(()->!sortirAngle.getBoolean(true)).withTimeout(2), |     .withRotationalRate(0)).unless(()->!sortirAngle.getBoolean(true)).withTimeout(3), | ||||||
|        drivetrain.applyRequest(()-> |        drivetrain.applyRequest(()-> | ||||||
|         drive.withVelocityX(0) |         drive.withVelocityX(0) | ||||||
|        .withVelocityY(0) |        .withVelocityY(0) | ||||||
|        .withRotationalRate(0)).withTimeout(0.1), |        .withRotationalRate(0)).withTimeout(0.1), | ||||||
|         new L4(elevateur, pince).unless(()->!L4.getBoolean(true)).withTimeout(4), |         new L4(elevateur, pince).unless(()->!L4.getBoolean(true)).withTimeout(4), | ||||||
|         drivetrain.applyRequest(()-> |         drivetrain.applyRequest(()-> | ||||||
|         drive.withVelocityX(0.2*MaxSpeed) |         drive.withVelocityX(0.1*MaxSpeed) | ||||||
|        .withVelocityY(0) |        .withVelocityY(0) | ||||||
|        .withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(0.5), |        .withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(0.25), | ||||||
|        drivetrain.applyRequest(()-> |        drivetrain.applyRequest(()-> | ||||||
|        drive.withVelocityX(0*MaxSpeed) |        drive.withVelocityX(0*MaxSpeed) | ||||||
|       .withVelocityY(0) |       .withVelocityY(0) | ||||||
|   | |||||||
| @@ -26,10 +26,10 @@ public class L2 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() { | ||||||
|      if(pince.encodeurpivot()>=14 && pince.encodeurpivot()<=15){ |      if(pince.encodeurpivot()>=15 && pince.encodeurpivot()<=16.5){ | ||||||
|        pince.pivote(0); |        pince.pivote(0); | ||||||
|      } |      } | ||||||
|      else if(pince.encodeurpivot()>=14){ |      else if(pince.encodeurpivot()>=15){ | ||||||
|        pince.pivote(-0.2); |        pince.pivote(-0.2); | ||||||
|      } |      } | ||||||
|      else{ |      else{ | ||||||
|   | |||||||
| @@ -27,8 +27,8 @@ public class BalayeuseAlgue 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 cibleMin = 700; |     double cibleMin = 550; | ||||||
|     double cibleMax = 900; |     double cibleMax = 650; | ||||||
|  |  | ||||||
|      if(requin.amp()>=78.2){ |      if(requin.amp()>=78.2){ | ||||||
|        requin.xRequin = true; |        requin.xRequin = true; | ||||||
|   | |||||||
| @@ -28,12 +28,12 @@ public class ExpireCorail extends Command { | |||||||
|   @Override |   @Override | ||||||
|   public void execute() { |   public void execute() { | ||||||
|     if(requin.amp()> 60){ |     if(requin.amp()> 60){ | ||||||
|       requin.balaye(-0.4); |       requin.balaye(-0.2); | ||||||
|     } |     } | ||||||
|     else |     else | ||||||
|     { |     { | ||||||
|     bougie.Rouge(); |     bougie.Rouge(); | ||||||
|     requin.balaye(-0.4);    |     requin.balaye(-0.2);    | ||||||
|   } |   } | ||||||
| } | } | ||||||
|  |  | ||||||
|   | |||||||
| @@ -27,10 +27,10 @@ public class L1Requin 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() { | ||||||
|     if(requin.encodeur()<=530 &&  requin.encodeur()>=430){ |     if(requin.encodeur()<=485 &&  requin.encodeur()>=385){ | ||||||
|       requin.rotationer(0); |       requin.rotationer(0); | ||||||
|     } |     } | ||||||
|     else if(requin.encodeur()>=530){ |     else if(requin.encodeur()>=485){ | ||||||
|     requin.rotationer(-0.5); |     requin.rotationer(-0.5); | ||||||
|     } |     } | ||||||
|     else{ |     else{ | ||||||
|   | |||||||
| @@ -45,42 +45,42 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su | |||||||
|     private final SwerveRequest.SysIdSwerveSteerGains m_steerCharacterization = new SwerveRequest.SysIdSwerveSteerGains(); |     private final SwerveRequest.SysIdSwerveSteerGains m_steerCharacterization = new SwerveRequest.SysIdSwerveSteerGains(); | ||||||
|     private final SwerveRequest.SysIdSwerveRotation m_rotationCharacterization = new SwerveRequest.SysIdSwerveRotation(); |     private final SwerveRequest.SysIdSwerveRotation m_rotationCharacterization = new SwerveRequest.SysIdSwerveRotation(); | ||||||
|  |  | ||||||
|     private void configureAutoBuilder() { |     // private void configureAutoBuilder() { | ||||||
|         try { |     //     try { | ||||||
|             var config = RobotConfig.fromGUISettings(); |     //         var config = RobotConfig.fromGUISettings(); | ||||||
|             AutoBuilder.configure( |     //         AutoBuilder.configure( | ||||||
|                  |                  | ||||||
|                 () -> getState().Pose,   // Supplier of current robot pose |     //             () -> getState().Pose,   // Supplier of current robot pose | ||||||
|                 this::resetPose,         // Consumer for seeding pose against auto |     //             this::resetPose,         // Consumer for seeding pose against auto | ||||||
|                 () -> getState().Speeds, // Supplier of current robot speeds |     //             () -> getState().Speeds, // Supplier of current robot speeds | ||||||
|                  |                  | ||||||
|                 // Consumer of ChassisSpeeds and feedforwards to drive the robot |     //             // Consumer of ChassisSpeeds and feedforwards to drive the robot | ||||||
|                 (speeds, feedforwards) -> setControl( |     //             (speeds, feedforwards) -> setControl( | ||||||
|                     m_pathApplyRobotSpeeds.withSpeeds(speeds) |     //                 m_pathApplyRobotSpeeds.withSpeeds(speeds) | ||||||
|                         .withWheelForceFeedforwardsY(feedforwards.robotRelativeForcesXNewtons()) |     //                     .withWheelForceFeedforwardsY(feedforwards.robotRelativeForcesXNewtons()) | ||||||
|                         .withWheelForceFeedforwardsX(feedforwards.robotRelativeForcesYNewtons()) |     //                     .withWheelForceFeedforwardsX(feedforwards.robotRelativeForcesYNewtons()) | ||||||
|                 ), |     //             ), | ||||||
|                 new PPHolonomicDriveController( |     //             new PPHolonomicDriveController( | ||||||
|                     // PID constants for translation |     //                 // PID constants for translation | ||||||
|                     new PIDConstants(63.167, 0, 0.54521), |     //                 new PIDConstants(63.167, 0, 0.54521), | ||||||
|                     // // PID constants for rotation |     //                 // // PID constants for rotation | ||||||
|                     // new PIDConstants(7.9735, 0, 0.038499) |     //                 // new PIDConstants(7.9735, 0, 0.038499) | ||||||
|                     // PID constants for rotation |     //                 // PID constants for rotation | ||||||
|                     new PIDConstants(43.502,0,2.7353) |     //                 new PIDConstants(43.502,0,2.7353) | ||||||
|                 ), |     //             ), | ||||||
|                 config, |     //             config, | ||||||
|                 // Assume the path needs to be flipped for Red vs Blue, this is normally the case |     //             // Assume the path needs to be flipped for Red vs Blue, this is normally the case | ||||||
|                 () -> DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red, |     //             () -> DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red, | ||||||
|                 this // Subsystem for requirements |     //             this // Subsystem for requirements | ||||||
|                  |                  | ||||||
|             ); |     //         ); | ||||||
|         } catch (Exception ex) { |     //     } catch (Exception ex) { | ||||||
|             DriverStation.reportError("Failed to load PathPlanner config and configure AutoBuilder", ex.getStackTrace()); |     //         DriverStation.reportError("Failed to load PathPlanner config and configure AutoBuilder", ex.getStackTrace()); | ||||||
|         } |     //     } | ||||||
|          PPHolonomicDriveController.overrideRotationFeedback(()->{ |     //      PPHolonomicDriveController.overrideRotationFeedback(()->{ | ||||||
|             return 0; |     //         return 0; | ||||||
|          });   |     //      });   | ||||||
|         } |     //     } | ||||||
|  |  | ||||||
|     /** |     /** | ||||||
|      * Constructs a CTRE SwerveDrivetrain using the specified constants. |      * Constructs a CTRE SwerveDrivetrain using the specified constants. | ||||||
| @@ -100,7 +100,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su | |||||||
|         if (Utils.isSimulation()) { |         if (Utils.isSimulation()) { | ||||||
|             startSimThread(); |             startSimThread(); | ||||||
|         } |         } | ||||||
|         configureAutoBuilder(); |         //configureAutoBuilder(); | ||||||
|     } |     } | ||||||
|  |  | ||||||
|     /** |     /** | ||||||
| @@ -125,7 +125,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su | |||||||
|         if (Utils.isSimulation()) { |         if (Utils.isSimulation()) { | ||||||
|             startSimThread(); |             startSimThread(); | ||||||
|         } |         } | ||||||
|         configureAutoBuilder(); |      //   configureAutoBuilder(); | ||||||
|     } |     } | ||||||
|  |  | ||||||
|     /** |     /** | ||||||
| @@ -158,7 +158,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su | |||||||
|         if (Utils.isSimulation()) { |         if (Utils.isSimulation()) { | ||||||
|             startSimThread(); |             startSimThread(); | ||||||
|         } |         } | ||||||
|         configureAutoBuilder(); |         //configureAutoBuilder(); | ||||||
|     } |     } | ||||||
|  |  | ||||||
|      |      | ||||||
|   | |||||||
		Reference in New Issue
	
	Block a user