Latest configurations for black competition robot
This commit is contained in:
@ -40,26 +40,26 @@ public class PedroConstants {
|
||||
// Robot encoder direction
|
||||
public static final double LEFT_ENCODER_DIRECTION = Encoder.FORWARD;
|
||||
public static final double RIGHT_ENCODER_DIRECTION = Encoder.FORWARD;
|
||||
public static final double BACK_ENCODER_DIRECTION = Encoder.FORWARD;
|
||||
public static final double BACK_ENCODER_DIRECTION = Encoder.REVERSE;
|
||||
|
||||
/*
|
||||
Pedro's parameters
|
||||
*/
|
||||
|
||||
// The weight of the robot in Kilograms
|
||||
public static final double ROBOT_WEIGHT_IN_KG = 8.5;
|
||||
public static final double ROBOT_WEIGHT_IN_KG = 10.5;
|
||||
|
||||
// Maximum velocity of the robot going forward
|
||||
public static final double ROBOT_SPEED_FORWARD = 81.34056;
|
||||
public static final double ROBOT_SPEED_FORWARD = 72.0693;
|
||||
|
||||
// Maximum velocity of the robot going right
|
||||
public static final double ROBOT_SPEED_LATERAL = 65.43028;
|
||||
public static final double ROBOT_SPEED_LATERAL = 24.1401;
|
||||
|
||||
// Rate of deceleration when power is cut-off when the robot is moving forward
|
||||
public static final double FORWARD_ZERO_POWER_ACCEL = -34.62719;
|
||||
public static final double FORWARD_ZERO_POWER_ACCEL = -74.3779;
|
||||
|
||||
// Rate of deceleration when power is cut-off when the robot is moving to the right
|
||||
public static final double LATERAL_ZERO_POWER_ACCEL = -78.15554;
|
||||
public static final double LATERAL_ZERO_POWER_ACCEL = -111.8409;
|
||||
|
||||
// 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;
|
||||
|
@ -65,9 +65,9 @@ public class ThreeWheelIMULocalizer extends Localizer {
|
||||
private double previousIMUOrientation;
|
||||
private double deltaRadians;
|
||||
private double totalHeading;
|
||||
public static double FORWARD_TICKS_TO_INCHES = 0.0038;//8192 * 1.37795 * 2 * Math.PI * 0.5008239963;
|
||||
public static double STRAFE_TICKS_TO_INCHES = -0.0033;//8192 * 1.37795 * 2 * Math.PI * 0.5018874659;
|
||||
public static double TURN_TICKS_TO_RADIANS = 0.002995;//8192 * 1.37795 * 2 * Math.PI * 0.5;
|
||||
public static double FORWARD_TICKS_TO_INCHES = 0.004;//8192 * 1.37795 * 2 * Math.PI * 0.5008239963;
|
||||
public static double STRAFE_TICKS_TO_INCHES = -0.0036;//8192 * 1.37795 * 2 * Math.PI * 0.5018874659;
|
||||
public static double TURN_TICKS_TO_RADIANS = 0.0043;//8192 * 1.37795 * 2 * Math.PI * 0.5;
|
||||
|
||||
public static boolean useIMU = true;
|
||||
|
||||
|
@ -52,7 +52,7 @@ public class LateralZeroPowerAccelerationTuner extends OpMode {
|
||||
|
||||
private PoseUpdater poseUpdater;
|
||||
|
||||
public static double VELOCITY = 30;
|
||||
public static double VELOCITY = 50;
|
||||
|
||||
private double previousVelocity;
|
||||
|
||||
|
Reference in New Issue
Block a user