From 66bb5c747f0d3f1d051e60eb49ef44e6052819e8 Mon Sep 17 00:00:00 2001 From: DanTheMan-byte Date: Wed, 28 Jan 2026 19:42:08 -0600 Subject: [PATCH] before merge --- .../autonomous/ProtoAutoClose_V4.java | 4 +- .../ftc/teamcode/libs/RR/MecanumDrive.java | 277 +++++++++--------- 2 files changed, 142 insertions(+), 139 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/ProtoAutoClose_V4.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/ProtoAutoClose_V4.java index 9e00607..b06cae2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/ProtoAutoClose_V4.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/ProtoAutoClose_V4.java @@ -97,7 +97,7 @@ public class ProtoAutoClose_V4 extends LinearOpMode { public static double normalIntakeTime = 3.0; public static double shoot1Turr = 0.57; public static double shoot0XTolerance = 1.0; - public static double turretShootPos = 0.6; + public static double turretShootPos = 0.5; public static double shootAllTime = 1.8; public static double shoot0Time = 1.6; public static double intake1Time = 3.0; @@ -609,6 +609,8 @@ public class ProtoAutoClose_V4 extends LinearOpMode { TrajectoryActionBuilder pickup3 = null; TrajectoryActionBuilder shoot3 = null; + robot.limelight.start(); + robot.light.setPosition(1); while (opModeInInit()) { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/libs/RR/MecanumDrive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/libs/RR/MecanumDrive.java index d2f9547..3b465db 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/libs/RR/MecanumDrive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/libs/RR/MecanumDrive.java @@ -5,9 +5,7 @@ import androidx.annotation.NonNull; import com.acmerobotics.dashboard.canvas.Canvas; import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.telemetry.TelemetryPacket; -import com.acmerobotics.roadrunner.AccelConstraint; -import com.acmerobotics.roadrunner.Action; -import com.acmerobotics.roadrunner.Actions; +import com.acmerobotics.roadrunner.*; import com.acmerobotics.roadrunner.AngularVelConstraint; import com.acmerobotics.roadrunner.DualNum; import com.acmerobotics.roadrunner.HolonomicController; @@ -16,20 +14,12 @@ import com.acmerobotics.roadrunner.MinVelConstraint; import com.acmerobotics.roadrunner.MotorFeedforward; import com.acmerobotics.roadrunner.Pose2d; import com.acmerobotics.roadrunner.Pose2dDual; -import com.acmerobotics.roadrunner.PoseVelocity2d; -import com.acmerobotics.roadrunner.PoseVelocity2dDual; import com.acmerobotics.roadrunner.ProfileAccelConstraint; -import com.acmerobotics.roadrunner.ProfileParams; -import com.acmerobotics.roadrunner.Rotation2d; import com.acmerobotics.roadrunner.Time; import com.acmerobotics.roadrunner.TimeTrajectory; import com.acmerobotics.roadrunner.TimeTurn; import com.acmerobotics.roadrunner.TrajectoryActionBuilder; -import com.acmerobotics.roadrunner.TrajectoryBuilderParams; import com.acmerobotics.roadrunner.TurnConstraints; -import com.acmerobotics.roadrunner.Twist2d; -import com.acmerobotics.roadrunner.Twist2dDual; -import com.acmerobotics.roadrunner.Vector2d; import com.acmerobotics.roadrunner.VelConstraint; import com.acmerobotics.roadrunner.ftc.DownsampledWriter; import com.acmerobotics.roadrunner.ftc.Encoder; @@ -56,131 +46,13 @@ import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumCommandMessage; import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumLocalizerInputsMessage; import org.firstinspires.ftc.teamcode.libs.RR.messages.PoseMessage; +import java.lang.Math; import java.util.Arrays; import java.util.LinkedList; import java.util.List; @Config public final class MecanumDrive { - public static Params PARAMS = new Params(); - public final MecanumKinematics kinematics = new MecanumKinematics( - PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick); - public final TurnConstraints defaultTurnConstraints = new TurnConstraints( - PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel); - public final VelConstraint defaultVelConstraint = - new MinVelConstraint(Arrays.asList( - kinematics.new WheelVelConstraint(PARAMS.maxWheelVel), - new AngularVelConstraint(PARAMS.maxAngVel) - )); - public final AccelConstraint defaultAccelConstraint = - new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel); - public final DcMotorEx leftFront, leftBack, rightBack, rightFront; - public final VoltageSensor voltageSensor; - public final LazyImu lazyImu; - public final Localizer localizer; - private final LinkedList poseHistory = new LinkedList<>(); - private final DownsampledWriter estimatedPoseWriter = new DownsampledWriter("ESTIMATED_POSE", 50_000_000); - private final DownsampledWriter targetPoseWriter = new DownsampledWriter("TARGET_POSE", 50_000_000); - private final DownsampledWriter driveCommandWriter = new DownsampledWriter("DRIVE_COMMAND", 50_000_000); - private final DownsampledWriter mecanumCommandWriter = new DownsampledWriter("MECANUM_COMMAND", 50_000_000); - public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) { - LynxFirmware.throwIfModulesAreOutdated(hardwareMap); - - for (LynxModule module : hardwareMap.getAll(LynxModule.class)) { - module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO); - } - - // 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, "fl"); - leftBack = hardwareMap.get(DcMotorEx.class, "bl"); - rightBack = hardwareMap.get(DcMotorEx.class, "br"); - rightFront = hardwareMap.get(DcMotorEx.class, "fr"); - - leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); - leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); - rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); - rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); - - // TODO: reverse motor directions if needed - // - 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 LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot( - PARAMS.logoFacingDirection, PARAMS.usbFacingDirection)); - - voltageSensor = hardwareMap.voltageSensor.iterator().next(); - - localizer = new PinpointLocalizer(hardwareMap, PARAMS.inPerTick, pose); - - FlightRecorder.write("MECANUM_PARAMS", PARAMS); - } - - public void setDrivePowers(PoseVelocity2d powers) { - MecanumKinematics.WheelVelocities