|
5 | 5 | import com.pedropathing.follower.FollowerConstants; |
6 | 6 | import com.pedropathing.ftc.FollowerBuilder; |
7 | 7 | import com.pedropathing.ftc.drivetrains.MecanumConstants; |
| 8 | +import com.pedropathing.ftc.localization.constants.PinpointConstants; |
8 | 9 | import com.pedropathing.paths.PathConstraints; |
| 10 | +import com.qualcomm.hardware.gobilda.GoBildaPinpointDriver; |
9 | 11 | import com.qualcomm.robotcore.hardware.DcMotorSimple; |
10 | 12 | import com.qualcomm.robotcore.hardware.HardwareMap; |
| 13 | +import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; |
11 | 14 |
|
12 | 15 | public class Constants { |
13 | 16 | public static FollowerConstants followerConstants = new FollowerConstants() |
14 | 17 | .mass(12); |
15 | 18 |
|
16 | 19 | public static MecanumConstants driveConstants = new MecanumConstants() |
17 | 20 | .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") |
22 | 25 | .leftFrontMotorDirection(DcMotorSimple.Direction.REVERSE) |
23 | 26 | .leftRearMotorDirection(DcMotorSimple.Direction.REVERSE) |
24 | 27 | .rightFrontMotorDirection(DcMotorSimple.Direction.FORWARD) |
25 | | - .rightRearMotorDirection(DcMotorSimple.Direction.FORWARD); |
| 28 | + .rightRearMotorDirection(DcMotorSimple.Direction.FORWARD) |
| 29 | + .xVelocity(147.58413) |
| 30 | + .yVelocity(131.245); |
26 | 31 |
|
27 | 32 | public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, 1, 1); |
28 | 33 |
|
| 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 | + |
29 | 45 | public static Follower createFollower(HardwareMap hardwareMap) { |
30 | 46 | return new FollowerBuilder(followerConstants, hardwareMap) |
31 | 47 | .pathConstraints(pathConstraints) |
| 48 | + .pinpointLocalizer(localizerConstants) |
32 | 49 | .mecanumDrivetrain(driveConstants) |
33 | 50 | .build(); |
34 | 51 | } |
|
0 commit comments