From 9db94c089dbe758638b9ef1bf603bb40fcb870ab Mon Sep 17 00:00:00 2001 From: Ryan Brott Date: Sat, 19 Aug 2023 19:29:18 -0700 Subject: [PATCH] Move quickstart files to separate module --- TeamCode/build.gradle | 3 + .../ftc/teamcode/ActionOpMode.java | 26 -- .../ftc/teamcode/{util => }/Localizer.java | 2 +- .../ftc/teamcode/MecanumDrive.java | 110 ++++----- .../firstinspires/ftc/teamcode/TankDrive.java | 59 +++-- .../ftc/teamcode/ThreeDeadWheelLocalizer.java | 38 +-- .../ftc/teamcode/TwoDeadWheelLocalizer.java | 29 ++- .../org/firstinspires/ftc/teamcode/readme.md | 131 ---------- .../teamcode/tuning/AngularRampLogger.java | 167 ------------- .../ftc/teamcode/tuning/DriveView.java | 210 ---------------- .../ftc/teamcode/tuning/ForwardPushTest.java | 36 --- .../teamcode/tuning/ForwardRampLogger.java | 96 -------- .../ftc/teamcode/tuning/LateralPushTest.java | 41 ---- .../ftc/teamcode/tuning/LocalizationTest.java | 61 ----- .../teamcode/tuning/ManualFeedbackTuner.java | 42 ---- .../tuning/ManualFeedforwardTuner.java | 104 -------- .../tuning/MecanumMotorDirectionDebugger.java | 93 ------- .../ftc/teamcode/tuning/SplineTest.java | 37 --- .../ftc/teamcode/tuning/TuningFiles.java | 174 -------------- .../ftc/teamcode/tuning/TuningOpModes.java | 47 ---- .../ftc/teamcode/util/Encoder.java | 21 -- .../ftc/teamcode/util/LogFiles.java | 227 ------------------ .../teamcode/util/LynxFirmwareVersion.java | 108 --------- .../ftc/teamcode/util/MidpointTimer.java | 17 -- .../ftc/teamcode/util/OverflowEncoder.java | 63 ----- .../ftc/teamcode/util/Paths.java | 34 --- .../ftc/teamcode/util/RawEncoder.java | 44 ---- .../ftc/teamcode/util/RollingThreeMedian.java | 16 -- 28 files changed, 144 insertions(+), 1892 deletions(-) delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/ActionOpMode.java rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/{util => }/Localizer.java (77%) delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/readme.md delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/AngularRampLogger.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/DriveView.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ForwardPushTest.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ForwardRampLogger.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/LateralPushTest.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/LocalizationTest.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ManualFeedbackTuner.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ManualFeedforwardTuner.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/MecanumMotorDirectionDebugger.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/SplineTest.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/TuningFiles.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/TuningOpModes.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/util/Encoder.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/util/LogFiles.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/util/LynxFirmwareVersion.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/util/MidpointTimer.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/util/OverflowEncoder.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/util/Paths.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/util/RawEncoder.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/util/RollingThreeMedian.java diff --git a/TeamCode/build.gradle b/TeamCode/build.gradle index dd806f2..fee9e96 100644 --- a/TeamCode/build.gradle +++ b/TeamCode/build.gradle @@ -27,6 +27,7 @@ repositories { maven { url = 'https://maven.brott.dev/' } + mavenLocal() } dependencies { @@ -38,4 +39,6 @@ dependencies { implementation 'com.acmerobotics.roadrunner:actions:1.0.0-beta2' implementation 'com.fasterxml.jackson.core:jackson-databind:2.12.7' + + implementation "com.acmerobotics.roadrunner:ftc:0.1.0-SNAPSHOT" } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/ActionOpMode.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/ActionOpMode.java deleted file mode 100644 index 6142bd9..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/ActionOpMode.java +++ /dev/null @@ -1,26 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import com.acmerobotics.dashboard.FtcDashboard; -import com.acmerobotics.dashboard.canvas.Canvas; -import com.acmerobotics.dashboard.telemetry.TelemetryPacket; -import com.acmerobotics.roadrunner.Action; -import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; - -public abstract class ActionOpMode extends LinearOpMode { - private final FtcDashboard dash = FtcDashboard.getInstance(); - - protected void runBlocking(Action a) { - Canvas c = new Canvas(); - a.preview(c); - - boolean b = true; - while (b && !isStopRequested()) { - TelemetryPacket p = new TelemetryPacket(); - p.fieldOverlay().getOperations().addAll(c.getOperations()); - - b = a.run(p); - - dash.sendTelemetryPacket(p); - } - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/util/Localizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Localizer.java similarity index 77% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/util/Localizer.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Localizer.java index c04ad80..974ab79 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/util/Localizer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Localizer.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.util; +package org.firstinspires.ftc.teamcode; import com.acmerobotics.roadrunner.Time; import com.acmerobotics.roadrunner.Twist2dDual; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java index 6a8009f..7021624 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java @@ -23,6 +23,12 @@ import com.acmerobotics.roadrunner.TurnConstraints; import com.acmerobotics.roadrunner.Twist2dDual; import com.acmerobotics.roadrunner.Vector2d; import com.acmerobotics.roadrunner.VelConstraint; +import com.acmerobotics.roadrunner.ftc.Encoder; +import com.acmerobotics.roadrunner.ftc.FlightRecorder; +import com.acmerobotics.roadrunner.ftc.LynxFirmware; +import com.acmerobotics.roadrunner.ftc.OverflowEncoder; +import com.acmerobotics.roadrunner.ftc.PositionVelocityPair; +import com.acmerobotics.roadrunner.ftc.RawEncoder; import com.qualcomm.hardware.lynx.LynxModule; import com.qualcomm.hardware.rev.RevHubOrientationOnRobot; import com.qualcomm.robotcore.hardware.DcMotor; @@ -32,12 +38,6 @@ import com.qualcomm.robotcore.hardware.IMU; import com.qualcomm.robotcore.hardware.VoltageSensor; import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; -import org.firstinspires.ftc.teamcode.util.LogFiles; -import org.firstinspires.ftc.teamcode.util.Encoder; -import org.firstinspires.ftc.teamcode.util.Localizer; -import org.firstinspires.ftc.teamcode.util.LynxFirmwareVersion; -import org.firstinspires.ftc.teamcode.util.OverflowEncoder; -import org.firstinspires.ftc.teamcode.util.RawEncoder; import java.lang.Math; import java.util.Arrays; @@ -46,49 +46,52 @@ import java.util.List; @Config public final class MecanumDrive { - // drive model parameters - public static double IN_PER_TICK = 0; - public static double LATERAL_IN_PER_TICK = 1; - public static double LATERAL_MULTIPLIER = IN_PER_TICK / LATERAL_IN_PER_TICK; - public static double TRACK_WIDTH_TICKS = 0; + public static class Params { + // drive model parameters + public double inPerTick = 0; + public double lateralInPerTick = 1; + public double trackWidthTicks = 0; - // feedforward parameters in tick units - public static double kS = 0; - public static double kV = 0; - public static double kA = 0; + // feedforward parameters in tick units + public double kS = 0; + public double kV = 0; + public double kA = 0; - // path profile parameters - public static double MAX_WHEEL_VEL = 50; - public static double MIN_PROFILE_ACCEL = -30; - public static double MAX_PROFILE_ACCEL = 50; + // path profile parameters + public double maxWheelVel = 50; + public double minProfileAccel = -30; + public double maxProfileAccel = 50; - // turn profile parameters - public static double MAX_ANG_VEL = Math.PI; // shared with path - public static double MAX_ANG_ACCEL = Math.PI; + // turn profile parameters + public double maxAngVel = Math.PI; // shared with path + public double maxAngAccel = Math.PI; - // path controller gains - public static double AXIAL_GAIN = 0.0; - public static double LATERAL_GAIN = 0.0; - public static double HEADING_GAIN = 0.0; // shared with turn + // path controller gains + public double axialGain = 0.0; + public double lateralGain = 0.0; + public double headingGain = 0.0; // shared with turn - public static double AXIAL_VEL_GAIN = 0.0; - public static double LATERAL_VEL_GAIN = 0.0; - public static double HEADING_VEL_GAIN = 0.0; // shared with turn + public double axialVelGain = 0.0; + public double lateralVelGain = 0.0; + public double headingVelGain = 0.0; // shared with turn + } + + public static Params PARAMS = new Params(); public final MecanumKinematics kinematics = new MecanumKinematics( - IN_PER_TICK * TRACK_WIDTH_TICKS, LATERAL_MULTIPLIER); + PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick); - public final MotorFeedforward feedforward = new MotorFeedforward(kS, kV / IN_PER_TICK, kA / IN_PER_TICK); + public final MotorFeedforward feedforward = new MotorFeedforward(PARAMS.kS, PARAMS.kV / PARAMS.inPerTick, PARAMS.kA / PARAMS.inPerTick); public final TurnConstraints defaultTurnConstraints = new TurnConstraints( - MAX_ANG_VEL, -MAX_ANG_ACCEL, MAX_ANG_ACCEL); + PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel); public final VelConstraint defaultVelConstraint = new MinVelConstraint(Arrays.asList( - kinematics.new WheelVelConstraint(MAX_WHEEL_VEL), - new AngularVelConstraint(MAX_ANG_VEL) + kinematics.new WheelVelConstraint(PARAMS.maxWheelVel), + new AngularVelConstraint(PARAMS.maxAngVel) )); public final AccelConstraint defaultAccelConstraint = - new ProfileAccelConstraint(MIN_PROFILE_ACCEL, MAX_PROFILE_ACCEL); + new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel); public final DcMotorEx leftFront, leftBack, rightBack, rightFront; @@ -99,8 +102,6 @@ public final class MecanumDrive { public final Localizer localizer; public Pose2d pose; - public final double inPerTick = IN_PER_TICK; - private final LinkedList poseHistory = new LinkedList<>(); public class DriveLocalizer implements Localizer { @@ -125,10 +126,10 @@ public final class MecanumDrive { @Override public Twist2dDual