3 Commits

4 changed files with 57 additions and 49 deletions

View File

@ -2,11 +2,3 @@
Check out the [docs](https://rr.brott.dev/docs/v1-0/tuning/). Check out the [docs](https://rr.brott.dev/docs/v1-0/tuning/).
# Helpful Commands
To connect to the robot:
- Open up a command prompt (Hit the Windows key, then type CMD and hit enter)
- Enter the follwing command
- extend opmode
-

View File

@ -1,7 +1,6 @@
package org.firstinspires.ftc.teamcode; package org.firstinspires.ftc.teamcode;
import static org.firstinspires.ftc.robotcore.external.BlocksOpModeCompanion.hardwareMap; import static org.firstinspires.ftc.teamcode.MecanumDriveParameters.*;
import static org.firstinspires.ftc.teamcode.TankDrive.PARAMS;
import androidx.annotation.NonNull; import androidx.annotation.NonNull;
@ -57,29 +56,23 @@ import java.util.List;
@Config @Config
public final class MecanumDrive { public final class MecanumDrive {
public static class Params { 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 IMU Orientation
public RevHubOrientationOnRobot.LogoFacingDirection logoFacingDirection = See https://ftc-docs.firstinspires.org/en/latest/programming_resources/imu/imu.html?highlight=imu#physical-hub-mounting
RevHubOrientationOnRobot.LogoFacingDirection.DOWN; */
public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection = public RevHubOrientationOnRobot.LogoFacingDirection logoFacingDirection = RevHubOrientationOnRobot.LogoFacingDirection.UP;
RevHubOrientationOnRobot.UsbFacingDirection.RIGHT; public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection = RevHubOrientationOnRobot.UsbFacingDirection.FORWARD;
// drive model parameters // drive model parameters
public double inPerTick = 125.5/42126.8333333; public double inPerTick = INCHES_PER_TICK_VALUE;
public double lateralInPerTick = 0.0026542073080477006; public double lateralInPerTick = LATERAL_INCHES_PER_TICK_VALUE;
public double trackWidthTicks = 4012.7667474312616; public double trackWidthTicks = TRACK_WIDTH_IN_TICKS_VALUE;
public double par0Yticks = -2097.77;
public double par1ticks = -2097.77;
public double perpXTicks = -2497.77;
// feedforward parameters (in tick units) // feedforward parameters (in tick units)
public double kS = 0.7579547290234911; public double kS = KS_VALUE;
public double kV = 0.0005724562271687877; public double kV = KV_VALUE;
public double kA = 0; public double kA = KA_VALUE;
// path profile parameters (in inches) // path profile parameters (in inches)
public double maxWheelVel = 50; public double maxWheelVel = 50;
@ -103,15 +96,18 @@ public final class MecanumDrive {
public static Params PARAMS = new Params(); public static Params PARAMS = new Params();
public final MecanumKinematics kinematics = new MecanumKinematics( 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( public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel); PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
public final VelConstraint defaultVelConstraint = public final VelConstraint defaultVelConstraint =
new MinVelConstraint(Arrays.asList( new MinVelConstraint(Arrays.asList(
kinematics.new WheelVelConstraint(PARAMS.maxWheelVel), kinematics.new WheelVelConstraint(PARAMS.maxWheelVel),
new AngularVelConstraint(PARAMS.maxAngVel) new AngularVelConstraint(PARAMS.maxAngVel)
)); ));
public final AccelConstraint defaultAccelConstraint = public final AccelConstraint defaultAccelConstraint =
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel); new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
@ -144,11 +140,7 @@ public final class MecanumDrive {
leftBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.leftBack)); leftBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.leftBack));
rightBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightBack)); rightBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightBack));
rightFront = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightFront)); rightFront = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightFront));
imu = lazyImu.get(); imu = lazyImu.get();
// TODO: reverse encoders if needed
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
} }
@Override @Override
@ -224,31 +216,34 @@ public final class MecanumDrive {
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO); 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 Configure motors definitions
leftFront = hardwareMap.get(DcMotorEx.class, "Drive front lt"); */
leftBack = hardwareMap.get(DcMotorEx.class, "Drive back lt"); leftFront = hardwareMap.get(DcMotorEx.class, FRONT_LEFT_MOTOR);
rightBack = hardwareMap.get(DcMotorEx.class, "Drive back rt"); leftBack = hardwareMap.get(DcMotorEx.class, BACK_LEFT_MOTOR);
rightFront = hardwareMap.get(DcMotorEx.class, "Drive front rt"); rightFront = hardwareMap.get(DcMotorEx.class, FRONT_RIGHT_MOTOR);
rightBack = hardwareMap.get(DcMotorEx.class, BACK_RIGHT_MOTOR);
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
// TODO: reverse motor directions if needed /*
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE); Configure motors direction
leftFront.setDirection(DcMotorSimple.Direction.REVERSE); */
leftBack.setDirection(DcMotorSimple.Direction.REVERSE); //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
lazyImu = new LazyImu(hardwareMap, "adaimu", new RevHubOrientationOnRobot( 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)); PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
voltageSensor = hardwareMap.voltageSensor.iterator().next(); voltageSensor = hardwareMap.voltageSensor.iterator().next();
localizer =new ThreeDeadWheelLocalizer(hardwareMap, PARAMS.inPerTick); localizer = new DriveLocalizer();
FlightRecorder.write("MECANUM_PARAMS", PARAMS); 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";
}

View File

@ -33,7 +33,6 @@ import java.util.List;
public final class TuningOpModes { public final class TuningOpModes {
// TODO: change this to TankDrive.class if you're using tank // TODO: change this to TankDrive.class if you're using tank
// public static final Class<?> DRIVE_CLASS = MecanumDrive.class;
public static final Class<?> DRIVE_CLASS = MecanumDrive.class; public static final Class<?> DRIVE_CLASS = MecanumDrive.class;
public static final String GROUP = "quickstart"; public static final String GROUP = "quickstart";