3 Commits

Author SHA1 Message Date
e329bbc16d latest update 2024-09-24 15:38:10 -07:00
cc8b126e75 Set correct wheel direction 2024-09-03 15:57:13 -07:00
1c16c6beb5 enabled deadwheels and changed right side direction 2024-08-29 17:13:14 -07:00
2 changed files with 33 additions and 57 deletions

View File

@ -1,7 +1,5 @@
package org.firstinspires.ftc.teamcode; package org.firstinspires.ftc.teamcode;
import static org.firstinspires.ftc.teamcode.MecanumDriveParameters.*;
import androidx.annotation.NonNull; import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.canvas.Canvas; import com.acmerobotics.dashboard.canvas.Canvas;
@ -56,23 +54,24 @@ 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
IMU Orientation // 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 =
*/ RevHubOrientationOnRobot.LogoFacingDirection.DOWN;
public RevHubOrientationOnRobot.LogoFacingDirection logoFacingDirection = RevHubOrientationOnRobot.LogoFacingDirection.UP; public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection =
public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection = RevHubOrientationOnRobot.UsbFacingDirection.FORWARD; RevHubOrientationOnRobot.UsbFacingDirection.LEFT;
// drive model parameters // drive model parameters
public double inPerTick = INCHES_PER_TICK_VALUE; //public double inPerTick = 37619.0/112;
public double lateralInPerTick = LATERAL_INCHES_PER_TICK_VALUE; public double inPerTick = 18760.5/56;
public double trackWidthTicks = TRACK_WIDTH_IN_TICKS_VALUE; public double lateralInPerTick = 293.2046574609792;
public double trackWidthTicks = 3968.437903995162;
// feedforward parameters (in tick units) // feedforward parameters (in tick units)
public double kS = KS_VALUE; public double kS = 0.7748584778215575;
public double kV = KV_VALUE; public double kV = 0.0005849868585467051;
public double kA = KA_VALUE; public double kA = 0;
// path profile parameters (in inches) // path profile parameters (in inches)
public double maxWheelVel = 50; public double maxWheelVel = 50;
@ -96,18 +95,15 @@ 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.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
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);
@ -140,7 +136,9 @@ 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();
} }
@Override @Override
@ -216,34 +214,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)
Configure motors definitions // see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
*/ leftFront = hardwareMap.get(DcMotorEx.class, "Drive front lt");
leftFront = hardwareMap.get(DcMotorEx.class, FRONT_LEFT_MOTOR); leftBack = hardwareMap.get(DcMotorEx.class, "Drive back lt");
leftBack = hardwareMap.get(DcMotorEx.class, BACK_LEFT_MOTOR); rightBack = hardwareMap.get(DcMotorEx.class, "Drive back rt");
rightFront = hardwareMap.get(DcMotorEx.class, FRONT_RIGHT_MOTOR); rightFront = hardwareMap.get(DcMotorEx.class, "Drive front rt");
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
Configure motors direction // leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
*/ rightFront.setDirection(DcMotorSimple.Direction.FORWARD);
//leftFront.setDirection(DcMotorSimple.Direction.REVERSE); rightBack.setDirection(DcMotorSimple.Direction.FORWARD);
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
leftBack.setDirection(DcMotorSimple.Direction.REVERSE);
/*
IMU Orientation Application // 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, "imu", 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);
} }

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