From e85c503b5fba19d4cad91ac6bdba128a8287ed14 Mon Sep 17 00:00:00 2001 From: Carlos Rivas Date: Fri, 27 Dec 2024 02:00:27 -0800 Subject: [PATCH] Updated Follower to use PedroConstants --- .../teamcode/pedroPathing/follower/Follower.java | 16 ++++++++-------- .../pedroPathing/tuning/FollowerConstants.java | 7 ++++--- 2 files changed, 12 insertions(+), 11 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/follower/Follower.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/follower/Follower.java index 2b48991..57ba18d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/follower/Follower.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/follower/Follower.java @@ -1,5 +1,9 @@ package org.firstinspires.ftc.teamcode.pedroPathing.follower; +import static org.firstinspires.ftc.teamcode.PedroConstants.BACK_LEFT_MOTOR_DIRECTION; +import static org.firstinspires.ftc.teamcode.PedroConstants.BACK_RIGHT_MOTOR_DIRECTION; +import static org.firstinspires.ftc.teamcode.PedroConstants.FRONT_LEFT_MOTOR_DIRECTION; +import static org.firstinspires.ftc.teamcode.PedroConstants.FRONT_RIGHT_MOTOR_DIRECTION; import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.drivePIDFFeedForward; import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.drivePIDFSwitch; import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.forwardZeroPowerAcceleration; @@ -10,10 +14,6 @@ import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstan import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName; import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName; import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName; -import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorDirection; -import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorDirection; -import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorDirection; -import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorDirection; import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.secondaryDrivePIDFFeedForward; import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.secondaryHeadingPIDFFeedForward; import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.secondaryTranslationalPIDFFeedForward; @@ -159,10 +159,10 @@ public class Follower { * @param hardwareMap HardwareMap required * @param localizer the localizer you wish to use */ - public Follower(HardwareMap hardwareMap, Localizer localizer) { - this.hardwareMap = hardwareMap; - initialize(localizer); - } +// public Follower(HardwareMap hardwareMap, Localizer localizer) { +// this.hardwareMap = hardwareMap; +// initialize(localizer); +// } /** * This initializes the follower. diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/FollowerConstants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/FollowerConstants.java index 038101c..0c325d9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/FollowerConstants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/FollowerConstants.java @@ -3,6 +3,7 @@ package org.firstinspires.ftc.teamcode.pedroPathing.tuning; import static org.firstinspires.ftc.teamcode.PedroConstants.*; import com.acmerobotics.dashboard.config.Config; +import com.qualcomm.robotcore.hardware.DcMotorSimple; import org.firstinspires.ftc.teamcode.pedroPathing.util.CustomFilteredPIDFCoefficients; import org.firstinspires.ftc.teamcode.pedroPathing.util.CustomPIDFCoefficients; @@ -30,10 +31,10 @@ public class FollowerConstants { public static String rightFrontMotorName = FRONT_RIGHT_MOTOR; public static String rightRearMotorName = BACK_RIGHT_MOTOR; - public static DcMotorSimple.Direction leftFrontMotorDirection = LEFT_FRONT_MOTOR_DIRECTION; + public static DcMotorSimple.Direction leftFrontMotorDirection = FRONT_RIGHT_MOTOR_DIRECTION; public static DcMotorSimple.Direction rightFrontMotorDirection = FRONT_RIGHT_MOTOR_DIRECTION; - public static DcMotorSimple.Direction leftRearMotorDirection = REAR_LEFT_MOTOR_DIRECTION; - public static DcMotorSimple.Direction rightRearMotorDirection = REAR_RIGHT_MOTOR_DIRECTION; + public static DcMotorSimple.Direction leftRearMotorDirection = BACK_LEFT_MOTOR_DIRECTION; + public static DcMotorSimple.Direction rightRearMotorDirection = BACK_RIGHT_MOTOR_DIRECTION; // This section is for setting the actual drive vector for the front left wheel, if the robot // is facing a heading of 0 radians with the wheel centered at (0,0)