-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathConstants.java
More file actions
104 lines (85 loc) · 5.65 KB
/
Constants.java
File metadata and controls
104 lines (85 loc) · 5.65 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
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
package frc.robot;
import edu.wpi.first.wpilibj.geometry.Translation2d;
import edu.wpi.first.wpilibj.kinematics.SwerveDriveKinematics;
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.util.Units;
public final class Constants {
public static final class ModuleConstants {
public static final double kWheelDiameterMeters = Units.inchesToMeters(4);
public static final double kDriveMotorGearRatio = 1 / 5.8462;
public static final double kTurningMotorGearRatio = 1 / 18.0;
public static final double kDriveEncoderRot2Meter = kDriveMotorGearRatio * Math.PI * kWheelDiameterMeters;
public static final double kTurningEncoderRot2Rad = kTurningMotorGearRatio * 2 * Math.PI;
public static final double kDriveEncoderRPM2MeterPerSec = kDriveEncoderRot2Meter / 60;
public static final double kTurningEncoderRPM2RadPerSec = kTurningEncoderRot2Rad / 60;
public static final double kPTurning = 0.5;
}
public static final class DriveConstants {
public static final double kTrackWidth = Units.inchesToMeters(21);
// Distance between right and left wheels
public static final double kWheelBase = Units.inchesToMeters(25.5);
// Distance between front and back wheels
public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics(
new Translation2d(kWheelBase / 2, -kTrackWidth / 2),
new Translation2d(kWheelBase / 2, kTrackWidth / 2),
new Translation2d(-kWheelBase / 2, -kTrackWidth / 2),
new Translation2d(-kWheelBase / 2, kTrackWidth / 2));
public static final int kFrontLeftDriveMotorPort = 8;
public static final int kBackLeftDriveMotorPort = 2;
public static final int kFrontRightDriveMotorPort = 6;
public static final int kBackRightDriveMotorPort = 4;
public static final int kFrontLeftTurningMotorPort = 7;
public static final int kBackLeftTurningMotorPort = 1;
public static final int kFrontRightTurningMotorPort = 5;
public static final int kBackRightTurningMotorPort = 3;
public static final boolean kFrontLeftTurningEncoderReversed = true;
public static final boolean kBackLeftTurningEncoderReversed = true;
public static final boolean kFrontRightTurningEncoderReversed = true;
public static final boolean kBackRightTurningEncoderReversed = true;
public static final boolean kFrontLeftDriveEncoderReversed = true;
public static final boolean kBackLeftDriveEncoderReversed = true;
public static final boolean kFrontRightDriveEncoderReversed = false;
public static final boolean kBackRightDriveEncoderReversed = false;
public static final int kFrontLeftDriveAbsoluteEncoderPort = 0;
public static final int kBackLeftDriveAbsoluteEncoderPort = 2;
public static final int kFrontRightDriveAbsoluteEncoderPort = 1;
public static final int kBackRightDriveAbsoluteEncoderPort = 3;
public static final boolean kFrontLeftDriveAbsoluteEncoderReversed = false;
public static final boolean kBackLeftDriveAbsoluteEncoderReversed = false;
public static final boolean kFrontRightDriveAbsoluteEncoderReversed = false;
public static final boolean kBackRightDriveAbsoluteEncoderReversed = false;
public static final double kFrontLeftDriveAbsoluteEncoderOffsetRad = -0.254;
public static final double kBackLeftDriveAbsoluteEncoderOffsetRad = -1.252;
public static final double kFrontRightDriveAbsoluteEncoderOffsetRad = -1.816;
public static final double kBackRightDriveAbsoluteEncoderOffsetRad = -4.811;
public static final double kPhysicalMaxSpeedMetersPerSecond = 5;
public static final double kPhysicalMaxAngularSpeedRadiansPerSecond = 2 * 2 * Math.PI;
public static final double kTeleDriveMaxSpeedMetersPerSecond = kPhysicalMaxSpeedMetersPerSecond / 4;
public static final double kTeleDriveMaxAngularSpeedRadiansPerSecond = //
kPhysicalMaxAngularSpeedRadiansPerSecond / 4;
public static final double kTeleDriveMaxAccelerationUnitsPerSecond = 3;
public static final double kTeleDriveMaxAngularAccelerationUnitsPerSecond = 3;
}
public static final class AutoConstants {
public static final double kMaxSpeedMetersPerSecond = DriveConstants.kPhysicalMaxSpeedMetersPerSecond / 4;
public static final double kMaxAngularSpeedRadiansPerSecond = //
DriveConstants.kPhysicalMaxAngularSpeedRadiansPerSecond / 10;
public static final double kMaxAccelerationMetersPerSecondSquared = 3;
public static final double kMaxAngularAccelerationRadiansPerSecondSquared = Math.PI / 4;
public static final double kPXController = 1.5;
public static final double kPYController = 1.5;
public static final double kPThetaController = 3;
public static final TrapezoidProfile.Constraints kThetaControllerConstraints = //
new TrapezoidProfile.Constraints(
kMaxAngularSpeedRadiansPerSecond,
kMaxAngularAccelerationRadiansPerSecondSquared);
}
public static final class OIConstants {
public static final int kDriverControllerPort = 0;
public static final int kDriverYAxis = 1;
public static final int kDriverXAxis = 0;
public static final int kDriverRotAxis = 4;
public static final int kDriverFieldOrientedButtonIdx = 1;
public static final double kDeadband = 0.05;
}
}