Compare commits
2 Commits
master
...
branch-ale
Author | SHA1 | Date | |
---|---|---|---|
3580b475a2 | |||
65d020c39f |
@ -2,3 +2,11 @@
|
|||||||
|
|
||||||
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
|
||||||
|
-
|
@ -1,5 +1,8 @@
|
|||||||
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.TankDrive.PARAMS;
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.canvas.Canvas;
|
import com.acmerobotics.dashboard.canvas.Canvas;
|
||||||
@ -58,18 +61,24 @@ public final class MecanumDrive {
|
|||||||
// TODO: fill in these values based on
|
// 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
|
// see https://ftc-docs.firstinspires.org/en/latest/programming_resources/imu/imu.html?highlight=imu#physical-hub-mounting
|
||||||
public RevHubOrientationOnRobot.LogoFacingDirection logoFacingDirection =
|
public RevHubOrientationOnRobot.LogoFacingDirection logoFacingDirection =
|
||||||
RevHubOrientationOnRobot.LogoFacingDirection.UP;
|
RevHubOrientationOnRobot.LogoFacingDirection.DOWN;
|
||||||
public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection =
|
public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection =
|
||||||
RevHubOrientationOnRobot.UsbFacingDirection.FORWARD;
|
RevHubOrientationOnRobot.UsbFacingDirection.RIGHT;
|
||||||
|
|
||||||
// drive model parameters
|
// drive model parameters
|
||||||
public double inPerTick = 1;
|
public double inPerTick = 125.5/42126.8333333;
|
||||||
public double lateralInPerTick = inPerTick;
|
public double lateralInPerTick = 0.0026542073080477006;
|
||||||
public double trackWidthTicks = 0;
|
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)
|
// feedforward parameters (in tick units)
|
||||||
public double kS = 0;
|
public double kS = 0.7579547290234911;
|
||||||
public double kV = 0;
|
public double kV = 0.0005724562271687877;
|
||||||
public double kA = 0;
|
public double kA = 0;
|
||||||
|
|
||||||
// path profile parameters (in inches)
|
// 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)
|
// 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
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
leftFront = hardwareMap.get(DcMotorEx.class, "leftFront");
|
leftFront = hardwareMap.get(DcMotorEx.class, "Drive front lt");
|
||||||
leftBack = hardwareMap.get(DcMotorEx.class, "leftBack");
|
leftBack = hardwareMap.get(DcMotorEx.class, "Drive back lt");
|
||||||
rightBack = hardwareMap.get(DcMotorEx.class, "rightBack");
|
rightBack = hardwareMap.get(DcMotorEx.class, "Drive back rt");
|
||||||
rightFront = hardwareMap.get(DcMotorEx.class, "rightFront");
|
rightFront = hardwareMap.get(DcMotorEx.class, "Drive front rt");
|
||||||
|
|
||||||
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
@ -229,15 +238,17 @@ public final class MecanumDrive {
|
|||||||
|
|
||||||
// TODO: reverse motor directions if needed
|
// TODO: reverse motor directions if needed
|
||||||
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
// 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)
|
// 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
|
// 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));
|
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
||||||
|
|
||||||
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
||||||
|
|
||||||
localizer = new DriveLocalizer();
|
localizer =new ThreeDeadWheelLocalizer(hardwareMap, PARAMS.inPerTick);
|
||||||
|
|
||||||
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
|
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
|
||||||
}
|
}
|
||||||
|
@ -38,9 +38,9 @@ public final class ThreeDeadWheelLocalizer implements Localizer {
|
|||||||
// TODO: make sure your config has **motors** with these names (or change them)
|
// 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
|
// 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
|
// 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")));
|
par0 = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "encoder left")));
|
||||||
par1 = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par1")));
|
par1 = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "encoder right")));
|
||||||
perp = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "perp")));
|
perp = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "encoder back")));
|
||||||
|
|
||||||
// TODO: reverse encoder directions if needed
|
// TODO: reverse encoder directions if needed
|
||||||
// par0.setDirection(DcMotorSimple.Direction.REVERSE);
|
// par0.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
@ -33,6 +33,7 @@ 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";
|
||||||
|
Reference in New Issue
Block a user