Skip to content

Commit 9e66d09

Browse files
committed
Pedro Tuning Tue Oct 28 08:29:18 PM EDT 2025
1 parent ea41392 commit 9e66d09

File tree

2 files changed

+26
-9
lines changed

2 files changed

+26
-9
lines changed

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/BasicDrive.kt

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -41,10 +41,10 @@ class BasicDrive : LinearOpMode() {
4141
hubs = hardwareMap.getAll(LynxModule::class.java) as MutableList<LynxModule>
4242
hubs.forEach { it.bulkCachingMode = LynxModule.BulkCachingMode.AUTO }
4343

44-
val br = hardwareMap["m0"] as DcMotorEx
45-
val fl = hardwareMap["m3"] as DcMotorEx
46-
val bl = hardwareMap["m2"] as DcMotorEx
47-
val fr = hardwareMap["m1"] as DcMotorEx
44+
val br = hardwareMap["m3"] as DcMotorEx // m3
45+
val fl = hardwareMap["m0"] as DcMotorEx // m0
46+
val bl = hardwareMap["m1"] as DcMotorEx // m1
47+
val fr = hardwareMap["m2"] as DcMotorEx // m2
4848

4949
val odom = hardwareMap["odom"] as GoBildaPinpointDriver
5050

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Pedro/Constants.java

Lines changed: 22 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -5,30 +5,47 @@
55
import com.pedropathing.follower.FollowerConstants;
66
import com.pedropathing.ftc.FollowerBuilder;
77
import com.pedropathing.ftc.drivetrains.MecanumConstants;
8+
import com.pedropathing.ftc.localization.constants.PinpointConstants;
89
import com.pedropathing.paths.PathConstraints;
10+
import com.qualcomm.hardware.gobilda.GoBildaPinpointDriver;
911
import com.qualcomm.robotcore.hardware.DcMotorSimple;
1012
import com.qualcomm.robotcore.hardware.HardwareMap;
13+
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
1114

1215
public class Constants {
1316
public static FollowerConstants followerConstants = new FollowerConstants()
1417
.mass(12);
1518

1619
public static MecanumConstants driveConstants = new MecanumConstants()
1720
.maxPower(1)
18-
.rightFrontMotorName("m1")
19-
.rightRearMotorName("m0")
20-
.leftFrontMotorName("m3")
21-
.leftRearMotorName("m2")
21+
.rightFrontMotorName("m2")
22+
.rightRearMotorName("m3")
23+
.leftFrontMotorName("m0")
24+
.leftRearMotorName("m1")
2225
.leftFrontMotorDirection(DcMotorSimple.Direction.REVERSE)
2326
.leftRearMotorDirection(DcMotorSimple.Direction.REVERSE)
2427
.rightFrontMotorDirection(DcMotorSimple.Direction.FORWARD)
25-
.rightRearMotorDirection(DcMotorSimple.Direction.FORWARD);
28+
.rightRearMotorDirection(DcMotorSimple.Direction.FORWARD)
29+
.xVelocity(147.58413)
30+
.yVelocity(131.245);
2631

2732
public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, 1, 1);
2833

34+
public static PinpointConstants localizerConstants = new PinpointConstants()
35+
.hardwareMapName("odom")
36+
.distanceUnit(DistanceUnit.INCH)
37+
.encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD)
38+
.forwardEncoderDirection(GoBildaPinpointDriver.EncoderDirection.REVERSED)
39+
.strafeEncoderDirection(GoBildaPinpointDriver.EncoderDirection.REVERSED)
40+
.forwardPodY(-6.375)
41+
.strafePodX(1.44);
42+
43+
44+
2945
public static Follower createFollower(HardwareMap hardwareMap) {
3046
return new FollowerBuilder(followerConstants, hardwareMap)
3147
.pathConstraints(pathConstraints)
48+
.pinpointLocalizer(localizerConstants)
3249
.mecanumDrivetrain(driveConstants)
3350
.build();
3451
}

0 commit comments

Comments
 (0)