-
Notifications
You must be signed in to change notification settings - Fork 1
Expand file tree
/
Copy pathConstants.java
More file actions
63 lines (48 loc) · 2.56 KB
/
Constants.java
File metadata and controls
63 lines (48 loc) · 2.56 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
package org.firstinspires.ftc.teamcode.pedroPathing;
import com.pedropathing.follower.Follower;
import com.pedropathing.follower.FollowerConstants;
import com.pedropathing.ftc.FollowerBuilder;
import com.pedropathing.ftc.drivetrains.MecanumConstants;
import com.pedropathing.ftc.localization.constants.PinpointConstants;
import com.pedropathing.paths.PathConstraints;
import com.qualcomm.hardware.gobilda.GoBildaPinpointDriver;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
public class Constants {
public static FollowerConstants followerConstants = new FollowerConstants()
.forwardZeroPowerAcceleration(-24.667070883046957)
.lateralZeroPowerAcceleration(-55.781291998825026)
.useSecondaryTranslationalPIDF(true)
.useSecondaryHeadingPIDF(true)
.useSecondaryDrivePIDF(true)
.mass(10);
public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, 1, 1);
public static MecanumConstants driveConstants = new MecanumConstants()
.maxPower(1)
.xVelocity(75.85668849194144)
.yVelocity(58.173999696265994D)
.rightFrontMotorName("rfmotor2")
.rightRearMotorName("rbmotor3")
.leftRearMotorName("lbmotor1")
.leftFrontMotorName("lfmotor0")
.leftFrontMotorDirection(DcMotorSimple.Direction.REVERSE)
.leftRearMotorDirection(DcMotorSimple.Direction.REVERSE)
.rightFrontMotorDirection(DcMotorSimple.Direction.FORWARD)
.rightRearMotorDirection(DcMotorSimple.Direction.FORWARD);
public static PinpointConstants localizerConstants = new PinpointConstants()
.forwardPodY(-3.17)
.strafePodX(-3.75)
.distanceUnit(DistanceUnit.INCH)
.hardwareMapName("pinpoint")
.encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD)
.forwardEncoderDirection(GoBildaPinpointDriver.EncoderDirection.REVERSED)
.strafeEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD);
public static Follower createFollower(HardwareMap hardwareMap) {
return new FollowerBuilder(followerConstants, hardwareMap)
.pathConstraints(pathConstraints)
.mecanumDrivetrain(driveConstants)
.pinpointLocalizer(localizerConstants)
.build();
}
}