changed mecanum

This commit is contained in:
Olivier Demers 2022-11-29 18:48:52 -05:00
parent 6772c3936e
commit b479222986

View File

@ -22,7 +22,7 @@ private WPI_TalonSRX arriereGauche = new WPI_TalonSRX(Constants.MoteurArriereGau
private WPI_TalonSRX arriereDroit = new WPI_TalonSRX(Constants.MoteurArriereDroit); private WPI_TalonSRX arriereDroit = new WPI_TalonSRX(Constants.MoteurArriereDroit);
private MecanumDrive mecanum = new MecanumDrive(avantGauche, arriereGauche, avantDroit, arriereDroit); private MecanumDrive mecanum;
private AHRS gyroscope = new AHRS(); private AHRS gyroscope = new AHRS();
public double getangle() { public double getangle() {
@ -35,7 +35,7 @@ public void drive(double y, double x, double rot){
public BasePilotable() { public BasePilotable() {
avantDroit.setInverted(true); avantDroit.setInverted(true);
arriereDroit.setInverted(true); arriereDroit.setInverted(true);
mecanum = new MecanumDrive(avantGauche, arriereGauche, avantDroit, arriereDroit);
} }
@Override @Override