From dfe6813a5b8ed89772ba6653093a787c71a6c1ae Mon Sep 17 00:00:00 2001 From: Jacob <102424561+jjophoven@users.noreply.github.com> Date: Mon, 18 May 2026 21:03:48 -0500 Subject: [PATCH 1/2] remove exponential notation for braking coefficients --- .../ftc/teamcode/pedroPathing/Tuning.java | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java index b31f6f596965..e2b410f30a78 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java @@ -919,13 +919,13 @@ public void loop() { telemetryM.debug("Tuning Complete"); telemetryM.debug("Braking Profile:"); - telemetryM.debug("kQuadratic", coefficients[1]); - telemetryM.debug("kLinear", coefficients[0]); + telemetryM.debug("kQuadratic", String.format("%.8f", coefficients[1])); + telemetryM.debug("kLinear", String.format("%.8f", coefficients[0])); telemetryM.update(telemetry); telemetryM.debug("Tuning Complete"); telemetryM.debug("Braking Profile:"); - telemetryM.debug("kQuadraticFriction", coefficients[1]); - telemetryM.debug("kLinearBraking", coefficients[0]); + telemetryM.debug("kQuadraticFriction", String.format("%.8f", coefficients[1])); + telemetryM.debug("kLinearBraking", String.format("%.8f", coefficients[0])); for (BrakeRecord record : brakeData) { Pose p = record.pose; telemetryM.debug(String.format("t=%.0f ms, x=%.2f, y=%.2f, θ=%.2f, v=%.2f", @@ -1790,4 +1790,4 @@ public static void drawPoseHistory(PoseHistory poseTracker) { public static void sendPacket() { panelsField.update(); } -} \ No newline at end of file +} From 5da62fb478621b094d711b64611d4fc336b9e352 Mon Sep 17 00:00:00 2001 From: Jacob <102424561+jjophoven@users.noreply.github.com> Date: Tue, 19 May 2026 07:33:23 -0500 Subject: [PATCH 2/2] Add format method for improved telemetry output --- .../ftc/teamcode/pedroPathing/Tuning.java | 21 ++++++++++++------- 1 file changed, 13 insertions(+), 8 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java index e2b410f30a78..dce1801b8877 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/Tuning.java @@ -6,6 +6,7 @@ import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.follower; import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.stopRobot; import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.telemetryM; +import static org.firstinspires.ftc.teamcode.pedroPathing.Tuning.format; import com.bylazar.configurables.PanelsConfigurables; import com.bylazar.configurables.annotations.Configurable; @@ -127,6 +128,10 @@ public static void stopRobot() { follower.startTeleopDrive(true); follower.setTeleOpDrive(0,0,0,true); } + + public static String format(double value, int decimalPlaces) { + return String.format("%." + decimalPlaces + "f", value); + } } /** @@ -429,7 +434,7 @@ public void loop() { average += velocity; } average /= velocities.size(); - telemetryM.debug("Forward Velocity: " + average); + telemetryM.debug("Forward Velocity: " + format(average, 3)); telemetryM.debug("\n"); telemetryM.debug("Press A to set the Forward Velocity temporarily (while robot remains on)."); @@ -537,7 +542,7 @@ public void loop() { } average /= velocities.size(); - telemetryM.debug("Strafe Velocity: " + average); + telemetryM.debug("Strafe Velocity: " + format(average, 3)); telemetryM.debug("\n"); telemetryM.debug("Press A to set the Lateral Velocity temporarily (while robot remains on)."); telemetryM.update(telemetry); @@ -643,7 +648,7 @@ public void loop() { } average /= accelerations.size(); - telemetryM.debug("Forward Zero Power Acceleration (Deceleration): " + average); + telemetryM.debug("Forward Zero Power Acceleration (Deceleration): " + format(average, 3)); telemetryM.debug("\n"); telemetryM.debug("Press A to set the Forward Zero Power Acceleration temporarily (while robot remains on)."); telemetryM.update(telemetry); @@ -747,7 +752,7 @@ public void loop() { } average /= accelerations.size(); - telemetryM.debug("Lateral Zero Power Acceleration (Deceleration): " + average); + telemetryM.debug("Lateral Zero Power Acceleration (Deceleration): " + format(average, 3)); telemetryM.debug("\n"); telemetryM.debug("Press A to set the Lateral Zero Power Acceleration temporarily (while robot remains on)."); telemetryM.update(telemetry); @@ -919,13 +924,13 @@ public void loop() { telemetryM.debug("Tuning Complete"); telemetryM.debug("Braking Profile:"); - telemetryM.debug("kQuadratic", String.format("%.8f", coefficients[1])); - telemetryM.debug("kLinear", String.format("%.8f", coefficients[0])); + telemetryM.debug("kQuadratic", format(coefficients[1], 8))); + telemetryM.debug("kLinear", format(coefficients[0], 7)); telemetryM.update(telemetry); telemetryM.debug("Tuning Complete"); telemetryM.debug("Braking Profile:"); - telemetryM.debug("kQuadraticFriction", String.format("%.8f", coefficients[1])); - telemetryM.debug("kLinearBraking", String.format("%.8f", coefficients[0])); + telemetryM.debug("kQuadraticFriction", format(coefficients[1], 8)); + telemetryM.debug("kLinearBraking", format(coefficients[0], 7)); for (BrakeRecord record : brakeData) { Pose p = record.pose; telemetryM.debug(String.format("t=%.0f ms, x=%.2f, y=%.2f, θ=%.2f, v=%.2f",