From 6c93d58f0998852492a7f2392d4738ea0d389355 Mon Sep 17 00:00:00 2001 From: Antoine PerreaultE Date: Wed, 10 Jan 2024 19:03:59 -0500 Subject: [PATCH] dgfbcg --- src/main/java/frc/robot/RobotContainer.java | 1 - src/main/java/frc/robot/commands/Avancer.java | 8 +++----- src/main/java/frc/robot/commands/Force1.java | 2 +- src/main/java/frc/robot/commands/LanceurAuto.java | 2 +- src/main/java/frc/robot/subsystems/Drive.java | 12 +----------- 5 files changed, 6 insertions(+), 19 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index ce14323..1a7439c 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -31,7 +31,6 @@ import frc.robot.commands.Force5; import frc.robot.commands.Force6; import frc.robot.commands.Force7; import frc.robot.commands.LanceurAuto; -import frc.robot.commands.Force1; import frc.robot.commands.AvancerGauche; import frc.robot.commands.accumulateurtest; import frc.robot.subsystems.Accumulateur; diff --git a/src/main/java/frc/robot/commands/Avancer.java b/src/main/java/frc/robot/commands/Avancer.java index 8701962..d1d3887 100644 --- a/src/main/java/frc/robot/commands/Avancer.java +++ b/src/main/java/frc/robot/commands/Avancer.java @@ -38,18 +38,16 @@ public class Avancer extends CommandBase { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - drive.drive(0.5, 0.2, 0); + drive.drive(0.5, -0.2, 0); } // Called once the command ends or is interrupted. @Override - public void end(boolean interrupted) { - drive.drive(0, 0, 0); - } + public void end(boolean interrupted) {} // Returns true when the command should end. @Override public boolean isFinished() { - return drive.distance()[0].distanceMeters>0.01; + return drive.distance()[0].distanceMeters>1; } } diff --git a/src/main/java/frc/robot/commands/Force1.java b/src/main/java/frc/robot/commands/Force1.java index 4a8e3d7..030dee6 100644 --- a/src/main/java/frc/robot/commands/Force1.java +++ b/src/main/java/frc/robot/commands/Force1.java @@ -31,7 +31,7 @@ public class Force1 extends CommandBase { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - lanceur.lancer(0.3); + lanceur.lancer(0.33); } // Called once the command ends or is interrupted. diff --git a/src/main/java/frc/robot/commands/LanceurAuto.java b/src/main/java/frc/robot/commands/LanceurAuto.java index 843e131..f90f116 100644 --- a/src/main/java/frc/robot/commands/LanceurAuto.java +++ b/src/main/java/frc/robot/commands/LanceurAuto.java @@ -24,7 +24,7 @@ public class LanceurAuto extends CommandBase { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - lanceur.lancer(0.75); + lanceur.lancer(0.755); } // Called once the command ends or is interrupted. diff --git a/src/main/java/frc/robot/subsystems/Drive.java b/src/main/java/frc/robot/subsystems/Drive.java index 5b8b66a..088ca3b 100644 --- a/src/main/java/frc/robot/subsystems/Drive.java +++ b/src/main/java/frc/robot/subsystems/Drive.java @@ -7,25 +7,15 @@ package frc.robot.subsystems; import java.io.File; import java.io.IOException; -import edu.wpi.first.cameraserver.CameraServer; import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.math.kinematics.SwerveModulePosition; import edu.wpi.first.wpilibj.Filesystem; import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout; -import com.revrobotics.CANSparkMax; -import com.revrobotics.CANSparkMaxLowLevel.MotorType; - -import edu.wpi.first.math.geometry.Translation2d; -import edu.wpi.first.math.kinematics.SwerveModulePosition; -import edu.wpi.first.wpilibj.Filesystem; -import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import frc.robot.Constants; import swervelib.SwerveDrive; -import swervelib.encoders.CanAndCoderSwerve; import swervelib.parser.SwerveParser; public class Drive extends SubsystemBase { @@ -49,7 +39,7 @@ public class Drive extends SubsystemBase { final CanAndCoderSwerve arrieregaucheangle = new CanAndCoderSwerve(Constants.arrieregaucheAngle); final CanAndCoderSwerve arrieredroitangle = new CanAndCoderSwerve(Constants.arrieredroitAngle); */ public void drive(double x, double y, double zRotation){ - swerveDrive.drive(new Translation2d(x, y), zRotation, false, false); + swerveDrive.drive(new Translation2d(x, y), zRotation, true, false); }