2 Commits

Author SHA1 Message Date
3580b475a2 Update values for Competition robot 2024-09-17 16:06:16 -07:00
65d020c39f added localizer ticks 2024-09-07 19:12:18 -07:00
4 changed files with 49 additions and 57 deletions

View File

@ -2,3 +2,11 @@
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,6 +1,7 @@
package org.firstinspires.ftc.teamcode;
import static org.firstinspires.ftc.teamcode.MecanumDriveParameters.*;
import static org.firstinspires.ftc.robotcore.external.BlocksOpModeCompanion.hardwareMap;
import static org.firstinspires.ftc.teamcode.TankDrive.PARAMS;
import androidx.annotation.NonNull;
@ -56,23 +57,29 @@ import java.util.List;
@Config
public final class MecanumDrive {
public static class Params {
/*
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;
// 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.RIGHT;
// drive model parameters
public double inPerTick = INCHES_PER_TICK_VALUE;
public double lateralInPerTick = LATERAL_INCHES_PER_TICK_VALUE;
public double trackWidthTicks = TRACK_WIDTH_IN_TICKS_VALUE;
public double inPerTick = 125.5/42126.8333333;
public double lateralInPerTick = 0.0026542073080477006;
public double trackWidthTicks = 4012.7667474312616;
public double par0Yticks = -2097.77;
public double par1ticks = -2097.77;
public double perpXTicks = -2497.77;
// feedforward parameters (in tick units)
public double kS = KS_VALUE;
public double kV = KV_VALUE;
public double kA = KA_VALUE;
public double kS = 0.7579547290234911;
public double kV = 0.0005724562271687877;
public double kA = 0;
// path profile parameters (in inches)
public double maxWheelVel = 50;
@ -96,18 +103,15 @@ 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);
@ -140,7 +144,11 @@ 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();
// TODO: reverse encoders if needed
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
}
@Override
@ -216,34 +224,31 @@ public final class MecanumDrive {
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
}
/*
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);
// 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");
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
/*
Configure motors direction
*/
//leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
// TODO: reverse motor directions if needed
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
leftBack.setDirection(DcMotorSimple.Direction.REVERSE);
/*
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(
// 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
lazyImu = new LazyImu(hardwareMap, "adaimu", new RevHubOrientationOnRobot(
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
voltageSensor = hardwareMap.voltageSensor.iterator().next();
localizer = new DriveLocalizer();
localizer =new ThreeDeadWheelLocalizer(hardwareMap, PARAMS.inPerTick);
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
}

View File

@ -1,22 +0,0 @@
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,6 +33,7 @@ import java.util.List;
public final class TuningOpModes {
// 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 String GROUP = "quickstart";