diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PedroConstants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PedroConstants.java index 4e98812..9b8ebb8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PedroConstants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PedroConstants.java @@ -52,16 +52,16 @@ public class PedroConstants { public static final double ROBOT_WEIGHT_IN_KG = 10.5; // Maximum velocity of the robot going forward - public static final double ROBOT_SPEED_FORWARD = 72.0693; + public static final double ROBOT_SPEED_FORWARD = 51.4598; // Maximum velocity of the robot going right - public static final double ROBOT_SPEED_LATERAL = 24.1401; + public static final double ROBOT_SPEED_LATERAL = 28.7119; // Rate of deceleration when power is cut-off when the robot is moving forward - public static final double FORWARD_ZERO_POWER_ACCEL = -74.3779; + public static final double FORWARD_ZERO_POWER_ACCEL = -61.125; // Rate of deceleration when power is cut-off when the robot is moving to the right - public static final double LATERAL_ZERO_POWER_ACCEL = -111.8409; + public static final double LATERAL_ZERO_POWER_ACCEL = -82.579633333; // Determines how fast your robot will decelerate as a factor of how fast your robot will coast to a stop public static final double ZERO_POWER_ACCEL_MULT = 4;