s
This commit is contained in:
parent
7374e670f8
commit
d81b5a6911
@ -44,7 +44,7 @@ public class Constants {
|
|||||||
|
|
||||||
// Limit switch
|
// Limit switch
|
||||||
public static int guideurhaut = 4;
|
public static int guideurhaut = 4;
|
||||||
public static int guideurbas = 5;
|
public static int guideurbas = 6;
|
||||||
public static int photocellacc = 2;
|
public static int photocellacc = 2;
|
||||||
|
|
||||||
//piston
|
//piston
|
||||||
|
@ -27,7 +27,7 @@ public class GuiderHaut extends Command {
|
|||||||
guideur.guider(0);
|
guideur.guider(0);
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
guideur.guider(-0.5);
|
guideur.guider(-0.4);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -21,6 +21,11 @@ import swervelib.parser.SwerveParser;
|
|||||||
public class Drive extends SubsystemBase {
|
public class Drive extends SubsystemBase {
|
||||||
/** Creates a new Drive. */
|
/** 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;
|
SwerveDrive swerveDrive;
|
||||||
|
|
||||||
File swerveJsonDirectory = new File(Filesystem.getDeployDirectory(),"swerve");
|
File swerveJsonDirectory = new File(Filesystem.getDeployDirectory(),"swerve");
|
||||||
|
Loading…
x
Reference in New Issue
Block a user