mirror of
https://github.com/Team4388/2022NoWayHome.git
synced 2026-06-09 00:38:05 -06:00
Merge branch 'full-robot-test' into vision-odo-not-proto
This commit is contained in:
@@ -39,8 +39,8 @@ public final class Constants {
|
||||
public static final double JOYSTICK_TO_METERS_PER_SECOND_SLOW = 2;
|
||||
public static final double MAX_SPEED_FEET_PER_SEC = 20; // redundant constant?
|
||||
public static final double SPEED_FEET_PER_SECOND_AT_FULL_POWER = 20; // redundant constant?
|
||||
|
||||
//IDs
|
||||
|
||||
// IDs
|
||||
public static final int LEFT_FRONT_STEER_CAN_ID = 2;
|
||||
public static final int LEFT_FRONT_WHEEL_CAN_ID = 3;
|
||||
public static final int RIGHT_FRONT_STEER_CAN_ID = 4;
|
||||
@@ -54,24 +54,34 @@ public final class Constants {
|
||||
public static final int LEFT_BACK_STEER_CAN_ENCODER_ID = 12;
|
||||
public static final int RIGHT_BACK_STEER_CAN_ENCODER_ID = 13;
|
||||
public static final int GYRO_ID = 14;
|
||||
|
||||
|
||||
// offsets are in degrees
|
||||
// NATHAN if you truncate or round or simplify these i will cry
|
||||
public static final double LEFT_FRONT_ENCODER_OFFSET = 181.45-3.30;//181.7578125;//180.0;//315.0 +45;//180.0;
|
||||
public static final double RIGHT_FRONT_ENCODER_OFFSET = 360.-59.0625+0.18;//360.-59.0625;//315.0;//224.296875 + 90;//300.0;
|
||||
public static final double LEFT_BACK_ENCODER_OFFSET = 360.-128.222;//308.408203125;//225.0;//45.87890625;//360.0 - 128.0;
|
||||
public static final double RIGHT_BACK_ENCODER_OFFSET = 360.+2.15-3.637;//180-2.021484375;//0.0;//134.384765625 + 45;
|
||||
// public static final double LEFT_FRONT_ENCODER_OFFSET = 181.45 - 3.30;//
|
||||
// 181.7578125;//180.0;//315.0 +45;//180.0;
|
||||
// public static final double RIGHT_FRONT_ENCODER_OFFSET = 360. - 59.0625 +
|
||||
// 0.18;// 360.-59.0625;//315.0;//224.296875 +
|
||||
// public static final double LEFT_BACK_ENCODER_OFFSET = 360. - 128.222;//
|
||||
// 308.408203125;//225.0;//45.87890625;//360.0
|
||||
// public static final double RIGHT_BACK_ENCODER_OFFSET = 360. + 2.15 - 3.637;//
|
||||
// 180-2.021484375;//0.0;//134.384765625
|
||||
|
||||
public static final double RIGHT_FRONT_ENCODER_OFFSET = (4 * 360. - 152.05 - 180 - 90) % 360.;
|
||||
public static final double LEFT_FRONT_ENCODER_OFFSET = (4 * 360. - 232.58 + 180 - 90) % 360.;
|
||||
public static final double LEFT_BACK_ENCODER_OFFSET = (4 * 360. - 189.50 - 90) % 360.;
|
||||
public static final double RIGHT_BACK_ENCODER_OFFSET = (4 * 360. - 9.31 - 180 - 90) % 360.;
|
||||
|
||||
// swerve PID constants
|
||||
public static final int SWERVE_SLOT_IDX = 0;
|
||||
public static final int SWERVE_PID_LOOP_IDX = 1;
|
||||
public static final int SWERVE_TIMEOUT_MS = 30;
|
||||
public static final Gains SWERVE_GAINS = new Gains(1.0, 0.0, 1.0, 0.0, 0, 1.0);
|
||||
public static final Gains SWERVE_GAINS = new Gains(1.5, 0.0, 0.0, 0.0, 0, 1.0);
|
||||
|
||||
// swerve auto constants
|
||||
public static final PIDController X_CONTROLLER = new PIDController(0.5, 0.0, 0.0);
|
||||
public static final PIDController Y_CONTROLLER = new PIDController(2.0, 0.0, 0.0);
|
||||
public static final ProfiledPIDController THETA_CONTROLLER = new ProfiledPIDController (15.0, 0.1, 0.3, new TrapezoidProfile.Constraints(Math.PI, Math.PI));
|
||||
public static final ProfiledPIDController THETA_CONTROLLER = new ProfiledPIDController(15.0, 0.1, 0.3,
|
||||
new TrapezoidProfile.Constraints(Math.PI, Math.PI));
|
||||
public static final boolean PATH_RECORD_VELOCITY = true;
|
||||
public static final double PATH_MAX_VELOCITY = 5.0;
|
||||
public static final double PATH_MAX_ACCELERATION = 5.0;
|
||||
@@ -89,19 +99,19 @@ public final class Constants {
|
||||
// wheel diameter: official = 4 in, measured = 3.8 in
|
||||
/* Ratio Calculation */
|
||||
public static final double MOTOR_REV_PER_STEER_REV = 12.8;
|
||||
public static final double MOTOR_REV_PER_WHEEL_REV = 5.142857;
|
||||
public static final double MOTOR_REV_PER_WHEEL_REV = 6.12;// 5.142857;
|
||||
public static final double WHEEL_DIAMETER_INCHES = 4.0;
|
||||
public static final double TICKS_PER_MOTOR_REV = 2048;
|
||||
public static final double INCHES_PER_WHEEL_REV = WHEEL_DIAMETER_INCHES * Math.PI;
|
||||
public static final double INCHES_PER_METER = 39.370;
|
||||
public static final double METERS_PER_INCH = 1/INCHES_PER_METER;
|
||||
|
||||
public static final double WHEEL_REV_PER_MOTOR_REV = 1/MOTOR_REV_PER_WHEEL_REV;
|
||||
public static final double METERS_PER_INCH = 1 / INCHES_PER_METER;
|
||||
|
||||
public static final double WHEEL_REV_PER_MOTOR_REV = 1 / MOTOR_REV_PER_WHEEL_REV;
|
||||
public static final double TICKS_PER_WHEEL_REV = TICKS_PER_MOTOR_REV * MOTOR_REV_PER_WHEEL_REV;
|
||||
public static final double TICKS_PER_INCH = TICKS_PER_WHEEL_REV/INCHES_PER_WHEEL_REV;
|
||||
public static final double INCHES_PER_TICK = 1/TICKS_PER_INCH;
|
||||
public static final double TICKS_PER_INCH = TICKS_PER_WHEEL_REV / INCHES_PER_WHEEL_REV;
|
||||
public static final double INCHES_PER_TICK = 1 / TICKS_PER_INCH;
|
||||
public static final double TICK_TIME_TO_SECONDS = 0.1;
|
||||
public static final double SECONDS_TO_TICK_TIME = 1/TICK_TIME_TO_SECONDS;
|
||||
public static final double SECONDS_TO_TICK_TIME = 1 / TICK_TIME_TO_SECONDS;
|
||||
|
||||
// misc
|
||||
public static final int SMARTDASHBOARD_UPDATE_FRAME = 2;
|
||||
@@ -132,20 +142,22 @@ public final class Constants {
|
||||
public static final int SHOOTER_TIMEOUT_MS = 32;
|
||||
public static final int SHOOTER_SLOT_IDX = 0;
|
||||
public static final int SHOOTER_PID_LOOP_IDX = 1;
|
||||
public static final SupplyCurrentLimitConfiguration SUPPLY_CURRENT_LIMIT_CONFIG = new SupplyCurrentLimitConfiguration(true, 60, 40, 0.5);
|
||||
public static final SupplyCurrentLimitConfiguration SUPPLY_CURRENT_LIMIT_CONFIG = new SupplyCurrentLimitConfiguration(
|
||||
true, 60, 40, 0.5);
|
||||
public static final int SHOOTER_FALCON_LEFT_CAN_ID = 23;
|
||||
public static final int SHOOTER_FALCON_RIGHT_CAN_ID = 24;
|
||||
public static final int SHOOTER_FALCON_RIGHT_CAN_ID = 24;
|
||||
public static final int SHOOTER_ROTATE_ID = 31; // TODO: find this value
|
||||
public static final double TURRET_SPEED_MULTIPLIER = 0.1d;
|
||||
public static final int DEGREES_PER_ROT = 0;
|
||||
public static final int TURRET_MOTOR_POS_AT_ZERO_ROT = 0;
|
||||
public static final int TURRET_MOTOR_ROTS_PER_ROT = 0;
|
||||
public static final double ENCODER_TICKS_PER_REV = 2048;
|
||||
|
||||
|
||||
|
||||
|
||||
// Shoot Command Constants
|
||||
public static final Gains SHOOT_GAINS = new Gains(0.1, 0.0, 0.0, 0.0, 0, 1.0);
|
||||
|
||||
/* Turret Constants */
|
||||
//ID
|
||||
// ID
|
||||
public static final int TURRET_MOTOR_CAN_ID = 30;
|
||||
public static final Gains SHOOTER_TURRET_GAINS = new Gains(0.6, 0.0, 0.0, 0.0, 0, 1.0);
|
||||
public static final Gains SHOOTER_ANGLE_GAINS = new Gains(0.05, 0.0, 0.0, 0.0, 0, 0.3);
|
||||
@@ -161,25 +173,26 @@ public final class Constants {
|
||||
public static final double DIG_DEADZONE_RIGHT = 60.0;
|
||||
|
||||
public static final int SHOOTER_FALCON_BALLER_ID = 0; // TODO: find
|
||||
public static final int SHOOTER_FALCON_BALLER_FOLLOWER_ID = 0; //"//
|
||||
|
||||
public static final Gains DRUM_SHOOTER_GAINS = new Gains(0,0,0,0,0,0); // TODO: tune values
|
||||
public static final int SHOOTER_FALCON_BALLER_FOLLOWER_ID = 0; // "//
|
||||
|
||||
public static final Gains DRUM_SHOOTER_GAINS = new Gains(0, 0, 0, 0, 0, 0); // TODO: tune values
|
||||
|
||||
/* Hood Constants */
|
||||
public static final int SHOOTER_ANGLE_ADJUST_ID = 32;
|
||||
public static final double HOOD_MOTOR_ROTS_PER_ROT = 1; //TODO: Find
|
||||
public static final double HOOD_MOTOR_POS_AT_ZERO_ROT = 0; //TODO: Find
|
||||
public static final float HOOD_FORWARD_LIMIT = 0; //TODO: find
|
||||
public static final float HOOD_REVERSE_LIMIT = 0; //TODO: find
|
||||
|
||||
public static final double HOOD_MOTOR_ROTS_PER_ROT = 1; // TODO: Find
|
||||
public static final double HOOD_MOTOR_POS_AT_ZERO_ROT = 0; // TODO: Find
|
||||
public static final float HOOD_FORWARD_LIMIT = 0; // TODO: find
|
||||
public static final float HOOD_REVERSE_LIMIT = 0; // TODO: find
|
||||
|
||||
}
|
||||
|
||||
public static final class VisionConstants {
|
||||
// public static final double TURN_P_VALUE = 0.8;
|
||||
// public static final double X_ANGLE_ERROR = 0.5;
|
||||
// public static final double GRAV = 385.83;
|
||||
// public static final double TARGET_HEIGHT = 67.5;
|
||||
// public static final double FOV = 29.8; //Field of view limelight
|
||||
|
||||
public static final double LIME_ANGLE = 24.7;
|
||||
|
||||
public static final String NAME = "photonCamera";
|
||||
|
||||
Reference in New Issue
Block a user