diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index cdb9911..39e0872 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -44,7 +44,7 @@ public class Constants { // Limit switch public static int guideurhaut = 4; - public static int guideurbas = 5; + public static int guideurbas = 6; public static int photocellacc = 2; //piston diff --git a/src/main/java/frc/robot/command/GuiderHaut.java b/src/main/java/frc/robot/command/GuiderHaut.java index 74719ca..a0863a3 100644 --- a/src/main/java/frc/robot/command/GuiderHaut.java +++ b/src/main/java/frc/robot/command/GuiderHaut.java @@ -27,7 +27,7 @@ public class GuiderHaut extends Command { guideur.guider(0); } else{ - guideur.guider(-0.5); + guideur.guider(-0.4); } } diff --git a/src/main/java/frc/robot/subsystem/Drive.java b/src/main/java/frc/robot/subsystem/Drive.java index 4e03980..54c88ab 100644 --- a/src/main/java/frc/robot/subsystem/Drive.java +++ b/src/main/java/frc/robot/subsystem/Drive.java @@ -21,6 +21,11 @@ import swervelib.parser.SwerveParser; public class Drive extends SubsystemBase { /** Creates a new Drive. */ + public static final boolean kFrontLeftDriveMotorReversed = false; + public static final boolean kBackLeftDriveMotorReversed = false; + public static final boolean kFrontRightDriveMotorReversed = true; + public static final boolean kBackRightDriveMotorReversed = true; + SwerveDrive swerveDrive; File swerveJsonDirectory = new File(Filesystem.getDeployDirectory(),"swerve");