From 6a3f65d4c52857aa3e31d18f6432b1c658e5b291 Mon Sep 17 00:00:00 2001 From: DanTheMan-byte Date: Fri, 10 Apr 2026 19:53:54 -0500 Subject: [PATCH] before adding pidf constants --- .../ftc/teamcode/pedroPathing/Constants.java | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java index 7144cad..f1e2af8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Constants.java @@ -14,7 +14,9 @@ import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; public class Constants { public static FollowerConstants followerConstants = new FollowerConstants() - .mass(15.5); + .mass(15.5) + .forwardZeroPowerAcceleration(-29.512) + .lateralZeroPowerAcceleration(-72.872); public static MecanumConstants driveConstants = new MecanumConstants() .maxPower(1) @@ -32,8 +34,8 @@ public class Constants { public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, 1, 1); public static PinpointConstants localizerConstants = new PinpointConstants() - .forwardPodY(7.5) - .strafePodX(3.75) + .forwardPodY(-7.5) + .strafePodX(-3.75) .distanceUnit(DistanceUnit.INCH) .hardwareMapName("pinpoint") .encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD)