@@ -86,10 +86,12 @@ class MyOpModeKt : NextFTCOpMode() {
8686 )
8787 }
8888
89- val pathCommand = FollowPath (PedroComponent .follower.pathBuilder()
90- .addPath(BezierLine (startPose, scorePose))
91- .setLinearHeadingInterpolation(startPose.heading, scorePose.heading)
92- .build())
89+ val pathCommand by onInit {
90+ FollowPath (PedroComponent .follower.pathBuilder()
91+ .addPath(BezierLine (startPose, scorePose))
92+ .setLinearHeadingInterpolation(startPose.heading, scorePose.heading)
93+ .build())
94+ }
9395
9496 override fun onWaitForStart () {
9597 pathCommand.schedule()
@@ -106,17 +108,22 @@ public class MyOpMode extends NextFTCOpMode {
106108 private final Pose pickup2Pose = new Pose (30.0 , 131.0 , Math . toRadians(0.0 ));
107109 private final Pose pickup3Pose = new Pose (45.0 , 128.0 , Math . toRadians(90.0 ));
108110 private final Pose parkPose = new Pose (68.0 , 96.0 , Math . toRadians(- 90.0 ));
111+
112+ private FollowPath pathCommand;
109113
110114 public MyOpMode () {
111115 addComponents(
112116 new PedroComponent (Constants :: createFollower)
113117 );
114118 }
115119
116- private final FollowPath pathCommand = new FollowPath (PedroComponent . follower(). pathBuilder()
117- .addPath(new BezierLine (startPose, scorePose))
118- .setLinearHeadingInterpolation(startPose. getHeading(), scorePose. getHeading())
119- .build());
120+ @Override
121+ public void onInit () {
122+ pathCommand = new FollowPath (PedroComponent . follower(). pathBuilder()
123+ .addPath(new BezierLine (startPose, scorePose))
124+ .setLinearHeadingInterpolation(startPose. getHeading(), scorePose. getHeading())
125+ .build());
126+ }
120127
121128 @Override
122129 public void onWaitForStart () {
0 commit comments