enabled deadwheels and changed right side direction
This commit is contained in:
@ -138,8 +138,6 @@ public final class MecanumDrive {
|
||||
|
||||
imu = lazyImu.get();
|
||||
|
||||
// TODO: reverse encoders if needed
|
||||
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
}
|
||||
|
||||
@Override
|
||||
@ -217,10 +215,10 @@ public final class MecanumDrive {
|
||||
|
||||
// TODO: make sure your config has motors with these names (or change them)
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
leftFront = hardwareMap.get(DcMotorEx.class, "leftFront");
|
||||
leftBack = hardwareMap.get(DcMotorEx.class, "leftBack");
|
||||
rightBack = hardwareMap.get(DcMotorEx.class, "rightBack");
|
||||
rightFront = hardwareMap.get(DcMotorEx.class, "rightFront");
|
||||
leftFront = hardwareMap.get(DcMotorEx.class, "Drive front lt");
|
||||
leftBack = hardwareMap.get(DcMotorEx.class, "Drive back lt");
|
||||
rightBack = hardwareMap.get(DcMotorEx.class, "Drive back rt");
|
||||
rightFront = hardwareMap.get(DcMotorEx.class, "Drive front rt");
|
||||
|
||||
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
@ -229,6 +227,9 @@ public final class MecanumDrive {
|
||||
|
||||
// TODO: reverse motor directions if needed
|
||||
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
rightFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
rightBack.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
|
||||
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
@ -237,7 +238,7 @@ public final class MecanumDrive {
|
||||
|
||||
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
||||
|
||||
localizer = new DriveLocalizer();
|
||||
localizer = new ThreeDeadWheelLocalizer(hardwareMap, PARAMS.inPerTick);
|
||||
|
||||
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
|
||||
}
|
||||
|
@ -38,9 +38,9 @@ public final class ThreeDeadWheelLocalizer implements Localizer {
|
||||
// TODO: make sure your config has **motors** with these names (or change them)
|
||||
// the encoders should be plugged into the slot matching the named motor
|
||||
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||
par0 = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par0")));
|
||||
par1 = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par1")));
|
||||
perp = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "perp")));
|
||||
par0 = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "encoder left")));
|
||||
par1 = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "encoder right")));
|
||||
perp = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "encoder back")));
|
||||
|
||||
// TODO: reverse encoder directions if needed
|
||||
// par0.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
|
Reference in New Issue
Block a user