From 7e0b287cd09b5893f5569f1ae2d852b6402032d5 Mon Sep 17 00:00:00 2001 From: j5155 <54331556+j5155@users.noreply.github.com> Date: Wed, 25 Sep 2024 21:07:42 -0800 Subject: [PATCH] bump lib --- TeamCode/build.gradle | 2 +- .../java/org/firstinspires/ftc/teamcode/PinpointDrive.java | 6 +++--- .../ftc/teamcode/SensorGoBildaPinpointExample.java | 4 ++-- .../firstinspires/ftc/teamcode/tuning/TuningOpModes.java | 4 ++-- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/TeamCode/build.gradle b/TeamCode/build.gradle index 4d9937226f5c..1cba582e72c3 100644 --- a/TeamCode/build.gradle +++ b/TeamCode/build.gradle @@ -38,5 +38,5 @@ dependencies { implementation "com.acmerobotics.roadrunner:core:1.0.0" implementation "com.acmerobotics.roadrunner:actions:1.0.0" implementation "com.acmerobotics.dashboard:dashboard:0.4.16" - implementation "com.github.jdhs-ftc:road-runner-ftc-otos:622d5b95a5" + implementation "com.github.jdhs-ftc:road-runner-ftc-otos:447094304b" } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PinpointDrive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PinpointDrive.java index 3bc2a8c8269a..9a83c6208327 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PinpointDrive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PinpointDrive.java @@ -97,9 +97,9 @@ public PoseVelocity2d updatePoseEstimate() { // Potential alternate solution: timestamp the pose set and backtrack it based on speed? pinpoint.setPosition(pose); } - pinpoint.bulkUpdate(); // RR LOCALIZER NOTE: this is not ideal for loop times. + pinpoint.updatePoseAndVelocity(); // RR LOCALIZER NOTE: this is not ideal for loop times. // Driver needs update to be optimized - pose = pinpoint.getPosition(); + pose = pinpoint.getPositionRR(); lastPinpointPose = pose; // RR standard @@ -110,7 +110,7 @@ public PoseVelocity2d updatePoseEstimate() { FlightRecorder.write("ESTIMATED_POSE", new PoseMessage(pose)); - return pinpoint.getVelocity(); + return pinpoint.getVelocityRR(); } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/SensorGoBildaPinpointExample.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/SensorGoBildaPinpointExample.java index 1c55aab37ba7..75851aa830c9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/SensorGoBildaPinpointExample.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/SensorGoBildaPinpointExample.java @@ -160,7 +160,7 @@ of time each cycle takes and finds the frequency (number of updates per second) /* gets the current Position (x & y in inches, and heading in radians) of the robot, and prints it. */ - Pose2d pos = odo.getPosition(); + Pose2d pos = odo.getPositionRR(); String data = String.format(Locale.US, "{X: %.3f, Y: %.3f, H: %.3f}", pos.position.x, pos.position.y, pos.heading.toDouble()); telemetry.addData("Position", data); @@ -168,7 +168,7 @@ gets the current Position (x & y in inches, and heading in radians) of the robot /* gets the current Velocity (x & y in inches/sec and heading in radians/sec) and prints it. */ - PoseVelocity2d vel = odo.getVelocity(); + PoseVelocity2d vel = odo.getVelocityRR(); String velocity = String.format(Locale.US,"{XVel: %.3f, YVel: %.3f, HVel: %.3f}", vel.linearVel.x, vel.linearVel.y, vel.angVel); telemetry.addData("Velocity", velocity); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/TuningOpModes.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/TuningOpModes.java index f98166115b61..9b06e84d7a48 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/TuningOpModes.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/TuningOpModes.java @@ -44,8 +44,8 @@ public static void register(OpModeManager manager) { List leftEncs = new ArrayList<>(), rightEncs = new ArrayList<>(); List parEncs = new ArrayList<>(), perpEncs = new ArrayList<>(); - parEncs.add(new PinpointEncoder(pd.pinpoint,false, PinpointDrive.PARAMS.xDirection == GoBildaPinpointDriver.EncoderDirection.FORWARD, pd.leftBack)); - perpEncs.add(new PinpointEncoder(pd.pinpoint,true,PinpointDrive.PARAMS.yDirection == GoBildaPinpointDriver.EncoderDirection.FORWARD, pd.leftBack)); + parEncs.add(new PinpointEncoder(pd.pinpoint,false, pd.leftBack)); + perpEncs.add(new PinpointEncoder(pd.pinpoint,true, pd.leftBack)); return new DriveView( DriveType.MECANUM,