3 Commits

2 changed files with 57 additions and 33 deletions

View File

@ -1,5 +1,7 @@
package org.firstinspires.ftc.teamcode;
import static org.firstinspires.ftc.teamcode.MecanumDriveParameters.*;
import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.canvas.Canvas;
@ -54,24 +56,23 @@ import java.util.List;
@Config
public final class MecanumDrive {
public static class Params {
// IMU orientation
// 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.DOWN;
public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection =
RevHubOrientationOnRobot.UsbFacingDirection.LEFT;
/*
IMU Orientation
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;
public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection = RevHubOrientationOnRobot.UsbFacingDirection.FORWARD;
// drive model parameters
//public double inPerTick = 37619.0/112;
public double inPerTick = 18760.5/56;
public double lateralInPerTick = 293.2046574609792;
public double trackWidthTicks = 3968.437903995162;
public double inPerTick = INCHES_PER_TICK_VALUE;
public double lateralInPerTick = LATERAL_INCHES_PER_TICK_VALUE;
public double trackWidthTicks = TRACK_WIDTH_IN_TICKS_VALUE;
// feedforward parameters (in tick units)
public double kS = 0.7748584778215575;
public double kV = 0.0005849868585467051;
public double kA = 0;
public double kS = KS_VALUE;
public double kV = KV_VALUE;
public double kA = KA_VALUE;
// path profile parameters (in inches)
public double maxWheelVel = 50;
@ -95,15 +96,18 @@ public final class MecanumDrive {
public static Params PARAMS = new Params();
public final MecanumKinematics kinematics = new MecanumKinematics(
PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
PARAMS.inPerTick * PARAMS.trackWidthTicks,
PARAMS.inPerTick / PARAMS.lateralInPerTick);
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
public final VelConstraint defaultVelConstraint =
new MinVelConstraint(Arrays.asList(
kinematics.new WheelVelConstraint(PARAMS.maxWheelVel),
new AngularVelConstraint(PARAMS.maxAngVel)
));
public final AccelConstraint defaultAccelConstraint =
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
@ -136,9 +140,7 @@ public final class MecanumDrive {
leftBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.leftBack));
rightBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightBack));
rightFront = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightFront));
imu = lazyImu.get();
}
@Override
@ -214,34 +216,34 @@ public final class MecanumDrive {
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
}
// 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, "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");
/*
Configure motors definitions
*/
leftFront = hardwareMap.get(DcMotorEx.class, FRONT_LEFT_MOTOR);
leftBack = hardwareMap.get(DcMotorEx.class, BACK_LEFT_MOTOR);
rightFront = hardwareMap.get(DcMotorEx.class, FRONT_RIGHT_MOTOR);
rightBack = hardwareMap.get(DcMotorEx.class, BACK_RIGHT_MOTOR);
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
// 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);
/*
Configure motors direction
*/
//leftFront.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
/*
IMU Orientation Application
See https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
*/
lazyImu = new LazyImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
voltageSensor = hardwareMap.voltageSensor.iterator().next();
localizer = new ThreeDeadWheelLocalizer(hardwareMap, PARAMS.inPerTick);
localizer = new DriveLocalizer();
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
}

View File

@ -0,0 +1,22 @@
package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.hardware.DcMotorEx;
public class MecanumDriveParameters {
// Roadrunner tuning parameters
public static final double INCHES_PER_TICK_VALUE = 125.5/42126.8333333;
public static final double LATERAL_INCHES_PER_TICK_VALUE = 0.0026542073080477006;
public static final double TRACK_WIDTH_IN_TICKS_VALUE = 4012.7667474312616;
// FeedForward parameters (in tick units)
public static final double KS_VALUE = 0.7579547290234911;
public static final double KV_VALUE = 0.0005724562271687877;
public static final double KA_VALUE = 0;
// Robot motor configurations
public static final String FRONT_LEFT_MOTOR = "Drive front lt";
public static final String BACK_LEFT_MOTOR = "Drive back lt";
public static final String FRONT_RIGHT_MOTOR = "Drive front rt";
public static final String BACK_RIGHT_MOTOR = "Drive back rt";
}