3 Commits

Author SHA1 Message Date
e329bbc16d latest update 2024-09-24 15:38:10 -07:00
cc8b126e75 Set correct wheel direction 2024-09-03 15:57:13 -07:00
1c16c6beb5 enabled deadwheels and changed right side direction 2024-08-29 17:13:14 -07:00
2 changed files with 21 additions and 17 deletions

View File

@ -58,18 +58,19 @@ public final class MecanumDrive {
// TODO: fill in these values based on
// see https://ftc-docs.firstinspires.org/en/latest/programming_resources/imu/imu.html?highlight=imu#physical-hub-mounting
public RevHubOrientationOnRobot.LogoFacingDirection logoFacingDirection =
RevHubOrientationOnRobot.LogoFacingDirection.UP;
RevHubOrientationOnRobot.LogoFacingDirection.DOWN;
public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection =
RevHubOrientationOnRobot.UsbFacingDirection.FORWARD;
RevHubOrientationOnRobot.UsbFacingDirection.LEFT;
// drive model parameters
public double inPerTick = 1;
public double lateralInPerTick = inPerTick;
public double trackWidthTicks = 0;
//public double inPerTick = 37619.0/112;
public double inPerTick = 18760.5/56;
public double lateralInPerTick = 293.2046574609792;
public double trackWidthTicks = 3968.437903995162;
// feedforward parameters (in tick units)
public double kS = 0;
public double kV = 0;
public double kS = 0.7748584778215575;
public double kV = 0.0005849868585467051;
public double kA = 0;
// path profile parameters (in inches)
@ -138,8 +139,6 @@ public final class MecanumDrive {
imu = lazyImu.get();
// TODO: reverse encoders if needed
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
}
@Override
@ -217,10 +216,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 +228,11 @@ public final class MecanumDrive {
// TODO: reverse motor directions if needed
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
rightFront.setDirection(DcMotorSimple.Direction.FORWARD);
rightBack.setDirection(DcMotorSimple.Direction.FORWARD);
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
leftBack.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 +241,7 @@ public final class MecanumDrive {
voltageSensor = hardwareMap.voltageSensor.iterator().next();
localizer = new DriveLocalizer();
localizer = new ThreeDeadWheelLocalizer(hardwareMap, PARAMS.inPerTick);
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
}

View File

@ -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);