mirror of
https://github.com/Team4388/2024AcrossTheRidgebotiverse.git
synced 2026-06-08 16:28:03 -06:00
update speeds
This commit is contained in:
@@ -68,7 +68,7 @@ public final class Constants {
|
|||||||
public static final class PIDConstants {
|
public static final class PIDConstants {
|
||||||
public static final int SWERVE_SLOT_IDX = 0;
|
public static final int SWERVE_SLOT_IDX = 0;
|
||||||
public static final int SWERVE_PID_LOOP_IDX = 1;
|
public static final int SWERVE_PID_LOOP_IDX = 1;
|
||||||
public static final Gains SWERVE_GAINS = new Gains(32, 0.0, 0.0, 0.0, 0, 0.0);
|
public static final Gains SWERVE_GAINS = new Gains(50, 0.0, 0.32, 0.0, 0, 0.0);
|
||||||
|
|
||||||
public static final Gains TEST_SWERVE_GAINS = new Gains(1.2, 0.0, 0.0, 0.0, 0, 0.0);
|
public static final Gains TEST_SWERVE_GAINS = new Gains(1.2, 0.0, 0.0, 0.0, 0, 0.0);
|
||||||
|
|
||||||
@@ -88,7 +88,7 @@ public final class Constants {
|
|||||||
public static final int CANCODER_TICKS_PER_ROTATION = 1;
|
public static final int CANCODER_TICKS_PER_ROTATION = 1;
|
||||||
|
|
||||||
public static final double JOYSTICK_TO_METERS_PER_SECOND_FAST = 6.22;
|
public static final double JOYSTICK_TO_METERS_PER_SECOND_FAST = 6.22;
|
||||||
public static final double JOYSTICK_TO_METERS_PER_SECOND_SLOW = JOYSTICK_TO_METERS_PER_SECOND_FAST * 0.3;
|
public static final double JOYSTICK_TO_METERS_PER_SECOND_SLOW = JOYSTICK_TO_METERS_PER_SECOND_FAST * 0.5;
|
||||||
|
|
||||||
public static final double MOTOR_REV_PER_WHEEL_REV = 5.12;
|
public static final double MOTOR_REV_PER_WHEEL_REV = 5.12;
|
||||||
public static final double MOTOR_REV_PER_STEER_REV = 12.8;
|
public static final double MOTOR_REV_PER_STEER_REV = 12.8;
|
||||||
|
|||||||
@@ -308,8 +308,8 @@ public class RobotContainer {
|
|||||||
|
|
||||||
// ! /* Speed */
|
// ! /* Speed */
|
||||||
new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON) // final
|
new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON) // final
|
||||||
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.setToTurbo()));
|
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.setToTurbo()))
|
||||||
// .onFalse(new InstantCommand(() -> m_robotSwerveDrive.setToFast()));
|
.onFalse(new InstantCommand(() -> m_robotSwerveDrive.setToFast()));
|
||||||
|
|
||||||
new JoystickButton(getDeadbandedDriverController(), XboxController.LEFT_BUMPER_BUTTON) // final
|
new JoystickButton(getDeadbandedDriverController(), XboxController.LEFT_BUMPER_BUTTON) // final
|
||||||
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.setToSlow()));
|
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.setToSlow()));
|
||||||
|
|||||||
@@ -36,7 +36,7 @@ public class SwerveDrive extends SubsystemBase {
|
|||||||
|
|
||||||
private RobotGyro gyro;
|
private RobotGyro gyro;
|
||||||
|
|
||||||
public double speedAdjust = SwerveDriveConstants.Conversions.JOYSTICK_TO_METERS_PER_SECOND_FAST; // * slow by default
|
public double speedAdjust = SwerveDriveConstants.Conversions.JOYSTICK_TO_METERS_PER_SECOND_SLOW; // * slow by default
|
||||||
public double rotSpeedAdjust = SwerveDriveConstants.MIN_ROT_SPEED;
|
public double rotSpeedAdjust = SwerveDriveConstants.MIN_ROT_SPEED;
|
||||||
public double autoSpeedAdjust = SwerveDriveConstants.Conversions.JOYSTICK_TO_METERS_PER_SECOND_SLOW;
|
public double autoSpeedAdjust = SwerveDriveConstants.Conversions.JOYSTICK_TO_METERS_PER_SECOND_SLOW;
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user