-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathdriveConstants.java
108 lines (97 loc) · 5.46 KB
/
driveConstants.java
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
105
106
107
108
package org.firstinspires.ftc.teamcode;
import com.acmerobotics.dashboard.config.Config;
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
/*
* Constants shared between multiple drive types.
*
* Constants generated by LearnRoadRunner.com/drive-constants
*
* TODO: Tune or adjust the following constants to fit your robot. Note that the non-final
* fields may also be edited through the dashboard (connect to the robot's WiFi network and
* navigate to https://192.168.49.1:8080/dash). Make sure to save the values here after you
* adjust them in the dashboard; **config variable changes don't persist between app restarts**.
*
* These are not the only parameters; some are located in the localizer classes, drive base classes,
* and op modes themselves.
*/
@Config
public class driveConstants {
/*
* These are motor constants that should be listed online for your motors.
*/
public static final double TICKS_PER_REV = 500.6;
public static final double MAX_RPM = 312;
/*
* Set RUN_USING_ENCODER to true to enable built-in hub velocity control using drive encoders.
* Set this flag to false if drive encoders are not present and an alternative localization
* method is in use (e.g., tracking wheels).
*
* If using the built-in motor velocity PID, update MOTOR_VELO_PID with the tuned coefficients
* from DriveVelocityPIDTuner.
*/
public static final boolean RUN_USING_ENCODER = true;
public static PIDFCoefficients MOTOR_VELO_PID = new PIDFCoefficients(70, 0.2, 2,
18);
//getMotorVelocityF(MAX_RPM / 60 * TICKS_PER_REV)
/*
* These are physical constants that can be determined from your robot (including the track
* width; it will be tune empirically later although a rough estimate is important). Users are
* free to chose whichever linear distance unit they would like so long as it is consistently
* used. The default values were selected with inches in mind. Road runner uses radians for
* angular distances although most angular parameters are wrapped in Math.toRadians() for
* convenience. Make sure to exclude any gear ratio included in MOTOR_CONFIG from GEAR_RATIO.
*/
public static double WHEEL_RADIUS = 1.9685; // in
public static double GEAR_RATIO = 1; // output (wheel) speed / input (motor) speed
public static double TRACK_WIDTH = 11.25; // in
/*
* These are the feedforward parameters used to model the drive motor behavior. If you are using
* the built-in velocity PID, *these values are fine as is*. However, if you do not have drive
* motor encoders or have elected not to use them for velocity control, these values should be
* empirically tuned.
*/
public static double kV = 1.0 / rpmToVelocity(MAX_RPM);
public static double kA = 0;
public static double kStatic = 0;
/*
* These values are used to generate the trajectories for you robot. To ensure proper operation,
* the constraints should never exceed ~80% of the robot's actual capabilities. While Road
* Runner is designed to enable faster autonomous motion, it is a good idea for testing to start
* small and gradually increase them later after everything is working. All distance units are
* inches.
*/
/*
* Note from LearnRoadRunner.com:
* The velocity and acceleration constraints were calculated based on the following equation:
* ((MAX_RPM / 60) * GEAR_RATIO * WHEEL_RADIUS * 2 * Math.PI) * 0.85
* Resulting in 54.66855022514893 in/s.
* This is only 85% of the theoretical maximum velocity of the bot, following the recommendation above.
* This is capped at 85% because there are a number of variables that will prevent your bot from actually
* reaching this maximum velocity: voltage dropping over the game, bot weight, general mechanical inefficiencies, etc.
* However, you can push this higher yourself if you'd like. Perhaps raise it to 90-95% of the theoretically
* max velocity. The theoretically maximum velocity is 64.31594144135168 in/s.
* Just make sure that your bot can actually reach this maximum velocity. Path following will be detrimentally
* affected if it is aiming for a velocity not actually possible.
*
* The maximum acceleration is somewhat arbitrary and it is recommended that you tweak this yourself based on
* actual testing. Just set it at a reasonable value and keep increasing until your path following starts
* to degrade. As of now, it simply mirrors the velocity, resulting in 54.66855022514893 in/s/s
*
* Maximum Angular Velocity is calculated as: maximum velocity / trackWidth * (180 / Math.PI) but capped at 360°/s.
* You are free to raise this on your own if you would like. It is best determined through experimentation.
*/
public static double MAX_VEL = 57.24855022514893;
public static double MAX_ACCEL = 57.24855022514893;
public static double MAX_ANG_VEL = 4.6;
public static double MAX_ANG_ACCEL = 4.6;
public static double encoderTicksToInches(double ticks) {
return WHEEL_RADIUS * 2 * Math.PI * GEAR_RATIO * ticks / TICKS_PER_REV;
}
public static double rpmToVelocity(double rpm) {
return rpm * GEAR_RATIO * 2 * Math.PI * WHEEL_RADIUS / 60.0;
}
public static double getMotorVelocityF(double ticksPerSecond) {
// see https://docs.google.com/document/d/1tyWrXDfMidwYyP_5H4mZyVgaEswhOC35gvdmP-V-5hA/edit#heading=h.61g9ixenznbx
return 32767 / ticksPerSecond;
}
}