Skip to content
This repository has been archived by the owner on Aug 31, 2024. It is now read-only.

Commit

Permalink
Merge pull request #75 from rh-robotics/milo-drive-constants
Browse files Browse the repository at this point in the history
  • Loading branch information
IsaccBarker authored Jan 25, 2024
2 parents 1d45619 + 0fb9d2e commit d2c5fee
Showing 1 changed file with 13 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,8 @@ public class DriveConstants {
/*
* These are motor constants that should be listed online for your motors.
*/
public static final double TICKS_PER_REV = 1;
public static final double MAX_RPM = 1;
public static final double TICKS_PER_REV = 3895.9;
public static final double MAX_RPM = 312.0;

/*
* Set RUN_USING_ENCODER to true to enable built-in hub velocity control using drive encoders.
Expand All @@ -32,8 +32,8 @@ public class DriveConstants {
* 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 = false;
public static PIDFCoefficients MOTOR_VELO_PID = new PIDFCoefficients(0, 0, 0,
public static final boolean RUN_USING_ENCODER = true;
public static PIDFCoefficients MOTOR_VELO_PID = new PIDFCoefficients(0.061, 0.00473, 0.0,
getMotorVelocityF(MAX_RPM / 60 * TICKS_PER_REV));

/*
Expand All @@ -44,9 +44,9 @@ public class DriveConstants {
* 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 = 2; // in
public static double GEAR_RATIO = 1; // output (wheel) speed / input (motor) speed
public static double TRACK_WIDTH = 1; // in
public static double WHEEL_RADIUS = 3.77953; // in
public static double GEAR_RATIO = 1.0 / 10.71; // output (wheel) speed / input (motor) speed
public static double TRACK_WIDTH = 10.6299; // in

/*
* These are the feedforward parameters used to model the drive motor behavior. If you are using
Expand All @@ -55,8 +55,8 @@ public class DriveConstants {
* empirically tuned.
*/
public static double kV = 1.0 / rpmToVelocity(MAX_RPM);
public static double kA = 0;
public static double kStatic = 0;
public static double kA = 1.95;
public static double kStatic = 0.02;

/*
* These values are used to generate the trajectories for you robot. To ensure proper operation,
Expand All @@ -65,10 +65,10 @@ public class DriveConstants {
* small and gradually increase them later after everything is working. All distance units are
* inches.
*/
public static double MAX_VEL = 30;
public static double MAX_ACCEL = 30;
public static double MAX_ANG_VEL = Math.toRadians(60);
public static double MAX_ANG_ACCEL = Math.toRadians(60);
public static double MAX_VEL = 25;
public static double MAX_ACCEL = 25;
public static double MAX_ANG_VEL = Math.toRadians(50);
public static double MAX_ANG_ACCEL = Math.toRadians(50);

/*
* Adjust the orientations here to match your robot. See the FTC SDK documentation for details.
Expand Down

0 comments on commit d2c5fee

Please sign in to comment.