Skip to content
This repository was archived by the owner on Aug 29, 2025. It is now read-only.

Commit 2f914c2

Browse files
committed
Update the Quickstart to v1.0.3 of Pedro:
- Update dependency to 1.0.3 - Update the Tuners and Examples to match the new method of updating the Constants. Note: Now users will have to call `Constants.setConstants(FConstants.class, LConstants.class);` before initalizing their follower (`follower = new Follower(hardwareMap);`).
1 parent ff5a433 commit 2f914c2

16 files changed

+48
-16
lines changed

TeamCode/src/main/java/pedroPathing/examples/Circle.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
import com.acmerobotics.dashboard.FtcDashboard;
44
import com.acmerobotics.dashboard.config.Config;
55
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
6+
import com.pedropathing.util.Constants;
67
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
78
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
89
import org.firstinspires.ftc.robotcore.external.Telemetry;
@@ -42,7 +43,8 @@ public class Circle extends OpMode {
4243
*/
4344
@Override
4445
public void init() {
45-
follower = new Follower(hardwareMap, FConstants.class, LConstants.class);
46+
Constants.setConstants(FConstants.class, LConstants.class);
47+
follower = new Follower(hardwareMap);
4648

4749
circle = follower.pathBuilder()
4850
.addPath(new BezierCurve(new Point(0,0, Point.CARTESIAN), new Point(RADIUS,0, Point.CARTESIAN), new Point(RADIUS, RADIUS, Point.CARTESIAN)))

TeamCode/src/main/java/pedroPathing/examples/ExampleBucketAuto.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
import com.pedropathing.pathgen.Path;
88
import com.pedropathing.pathgen.PathChain;
99
import com.pedropathing.pathgen.Point;
10+
import com.pedropathing.util.Constants;
1011
import com.pedropathing.util.Timer;
1112
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
1213
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
@@ -264,7 +265,8 @@ public void init() {
264265
opmodeTimer = new Timer();
265266
opmodeTimer.resetTimer();
266267

267-
follower = new Follower(hardwareMap, FConstants.class, LConstants.class);
268+
Constants.setConstants(FConstants.class, LConstants.class);
269+
follower = new Follower(hardwareMap);
268270
follower.setStartingPose(startPose);
269271
buildPaths();
270272
}

TeamCode/src/main/java/pedroPathing/examples/ExampleFieldCentricTeleop.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22

33
import com.pedropathing.follower.Follower;
44
import com.pedropathing.localization.Pose;
5+
import com.pedropathing.util.Constants;
56
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
67
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
78

@@ -23,7 +24,8 @@ public class ExampleFieldCentricTeleop extends OpMode {
2324
/** This method is call once when init is played, it initializes the follower **/
2425
@Override
2526
public void init() {
26-
follower = new Follower(hardwareMap, FConstants.class, LConstants.class);
27+
Constants.setConstants(FConstants.class, LConstants.class);
28+
follower = new Follower(hardwareMap);
2729
follower.setStartingPose(startPose);
2830
}
2931

TeamCode/src/main/java/pedroPathing/examples/ExampleRobotCentricTeleop.java

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,10 @@
11
package pedroPathing.examples;
22

3+
import android.provider.SyncStateContract;
4+
35
import com.pedropathing.follower.Follower;
46
import com.pedropathing.localization.Pose;
7+
import com.pedropathing.util.Constants;
58
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
69
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
710

@@ -23,7 +26,8 @@ public class ExampleRobotCentricTeleop extends OpMode {
2326
/** This method is call once when init is played, it initializes the follower **/
2427
@Override
2528
public void init() {
26-
follower = new Follower(hardwareMap, FConstants.class, LConstants.class);
29+
Constants.setConstants(FConstants.class,LConstants.class);
30+
follower = new Follower(hardwareMap);
2731
follower.setStartingPose(startPose);
2832
}
2933

TeamCode/src/main/java/pedroPathing/examples/Triangle.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
import com.pedropathing.pathgen.BezierLine;
88
import com.pedropathing.pathgen.PathChain;
99
import com.pedropathing.pathgen.Point;
10+
import com.pedropathing.util.Constants;
1011
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
1112
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
1213

@@ -57,7 +58,8 @@ public void loop() {
5758
*/
5859
@Override
5960
public void init() {
60-
follower = new Follower(hardwareMap, FConstants.class, LConstants.class);
61+
Constants.setConstants(FConstants.class, LConstants.class);
62+
follower = new Follower(hardwareMap);
6163
follower.setStartingPose(startPose);
6264

6365
triangle = follower.pathBuilder()

TeamCode/src/main/java/pedroPathing/tuners_tests/automatic/ForwardVelocityTuner.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
import com.acmerobotics.dashboard.FtcDashboard;
1313
import com.acmerobotics.dashboard.config.Config;
1414
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
15+
import com.pedropathing.util.Constants;
1516
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
1617
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
1718
import com.qualcomm.robotcore.hardware.DcMotor;
@@ -71,7 +72,8 @@ public class ForwardVelocityTuner extends OpMode {
7172
*/
7273
@Override
7374
public void init() {
74-
poseUpdater = new PoseUpdater(hardwareMap, FConstants.class, LConstants.class);
75+
Constants.setConstants(FConstants.class, LConstants.class);
76+
poseUpdater = new PoseUpdater(hardwareMap);
7577

7678
leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName);
7779
leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName);

TeamCode/src/main/java/pedroPathing/tuners_tests/automatic/ForwardZeroPowerAccelerationTuner.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
import com.acmerobotics.dashboard.config.Config;
1414
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
1515
import com.pedropathing.follower.FollowerConstants;
16+
import com.pedropathing.util.Constants;
1617
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
1718
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
1819
import com.qualcomm.robotcore.hardware.DcMotor;
@@ -75,7 +76,8 @@ public class ForwardZeroPowerAccelerationTuner extends OpMode {
7576
*/
7677
@Override
7778
public void init() {
78-
poseUpdater = new PoseUpdater(hardwareMap, FConstants.class, LConstants.class);
79+
Constants.setConstants(FConstants.class, LConstants.class);
80+
poseUpdater = new PoseUpdater(hardwareMap);
7981

8082
leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName);
8183
leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName);

TeamCode/src/main/java/pedroPathing/tuners_tests/automatic/LateralZeroPowerAccelerationTuner.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
import com.acmerobotics.dashboard.config.Config;
1414
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
1515
import com.pedropathing.follower.FollowerConstants;
16+
import com.pedropathing.util.Constants;
1617
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
1718
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
1819
import com.qualcomm.robotcore.hardware.DcMotor;
@@ -75,7 +76,8 @@ public class LateralZeroPowerAccelerationTuner extends OpMode {
7576
*/
7677
@Override
7778
public void init() {
78-
poseUpdater = new PoseUpdater(hardwareMap, FConstants.class, LConstants.class);
79+
Constants.setConstants(FConstants.class, LConstants.class);
80+
poseUpdater = new PoseUpdater(hardwareMap);
7981

8082
leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName);
8183
leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName);

TeamCode/src/main/java/pedroPathing/tuners_tests/automatic/StrafeVelocityTuner.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
import com.acmerobotics.dashboard.FtcDashboard;
1414
import com.acmerobotics.dashboard.config.Config;
1515
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
16+
import com.pedropathing.util.Constants;
1617
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
1718
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
1819
import com.qualcomm.robotcore.hardware.DcMotor;
@@ -72,7 +73,8 @@ public class StrafeVelocityTuner extends OpMode {
7273
*/
7374
@Override
7475
public void init() {
75-
poseUpdater = new PoseUpdater(hardwareMap, FConstants.class, LConstants.class);
76+
Constants.setConstants(FConstants.class, LConstants.class);
77+
poseUpdater = new PoseUpdater(hardwareMap);
7678

7779
leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName);
7880
leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName);

TeamCode/src/main/java/pedroPathing/tuners_tests/localization/ForwardTuner.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
import com.acmerobotics.dashboard.FtcDashboard;
44
import com.acmerobotics.dashboard.config.Config;
55
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
6+
import com.pedropathing.util.Constants;
67
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
78
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
89

@@ -42,7 +43,8 @@ public class ForwardTuner extends OpMode {
4243
*/
4344
@Override
4445
public void init() {
45-
poseUpdater = new PoseUpdater(hardwareMap, FConstants.class, LConstants.class);
46+
Constants.setConstants(FConstants.class, LConstants.class);
47+
poseUpdater = new PoseUpdater(hardwareMap);
4648

4749
dashboardPoseTracker = new DashboardPoseTracker(poseUpdater);
4850

0 commit comments

Comments
 (0)