Add drive constants

This commit is contained in:
Yash Karandikar 2022-11-07 16:38:25 -06:00
parent ddfc36c657
commit add1c09bdd
2 changed files with 5 additions and 5 deletions

View file

@ -22,8 +22,8 @@ public class DriveConstants {
/*
* These are motor constants that should be listed online for your motors.
*/
public static final double TICKS_PER_REV = 560;
public static final double MAX_RPM = 300;
public static final double TICKS_PER_REV = 1120;
public static final double MAX_RPM = 150;
/*
* Set RUN_USING_ENCODER to true to enable built-in hub velocity control using drive encoders.
@ -45,9 +45,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 = 1.4763; // in
public static double WHEEL_RADIUS = 1.5; // in
public static double GEAR_RATIO = 1; // output (wheel) speed / input (motor) speed
public static double TRACK_WIDTH = 16; // in
public static double TRACK_WIDTH = 15.75; // in
/*
* These are the feedforward parameters used to model the drive motor behavior. If you are using

View file

@ -309,7 +309,7 @@ public class SampleMecanumDrive extends MecanumDrive {
// expected). This bug does NOT affect orientation.
//
// See https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/251 for details.
return (double) -imu.getAngularVelocity().xRotationRate;
return (double) -imu.getAngularVelocity().yRotationRate;
}
public static TrajectoryVelocityConstraint getVelocityConstraint(double maxVel, double maxAngularVel, double trackWidth) {