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 36 additions and 16 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,5 +1,8 @@
package org.firstinspires.ftc.teamcode;
import static org.firstinspires.ftc.robotcore.external.BlocksOpModeCompanion.hardwareMap;
import static org.firstinspires.ftc.teamcode.TankDrive.PARAMS;
import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.canvas.Canvas;
@ -58,18 +61,24 @@ 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.RIGHT;
// drive model parameters
public double inPerTick = 1;
public double lateralInPerTick = inPerTick;
public double trackWidthTicks = 0;
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 = 0;
public double kV = 0;
public double kS = 0.7579547290234911;
public double kV = 0.0005724562271687877;
public double kA = 0;
// path profile parameters (in inches)
@ -217,10 +226,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,15 +238,17 @@ public final class MecanumDrive {
// TODO: reverse motor directions if needed
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
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
lazyImu = new LazyImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
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

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

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";