|
15 | 15 | import frc.robot.subsystems.drive.DriveBase;
|
16 | 16 | import frc.robot.subsystems.drive.DriveConstants;
|
17 | 17 | import frc.robot.util.AllianceFlipUtil;
|
| 18 | +import frc.robot.util.LoggedTunableNumber; |
18 | 19 | import java.text.DecimalFormat;
|
19 | 20 | import java.text.NumberFormat;
|
20 | 21 | import java.util.LinkedList;
|
|
25 | 26 | public class DriveCommands {
|
26 | 27 | // Drive
|
27 | 28 | private static final double DEADBAND = 0.1;
|
| 29 | + |
| 30 | + private static final LoggedTunableNumber LINEAR_VELOCITY_SCALAR = |
| 31 | + new LoggedTunableNumber("TeleopDrive/LinearVelocityScalar", 1.0, true); |
| 32 | + private static final LoggedTunableNumber ANGULAR_VELOCITY_SCALAR = |
| 33 | + new LoggedTunableNumber("TeleopDrive/AngularVelocityScalar", 1.0, true); |
| 34 | + |
28 | 35 | private static final double ANGLE_KP = 5.0;
|
29 | 36 | private static final double ANGLE_KD = 0.4;
|
30 | 37 | private static final double ANGLE_MAX_VELOCITY = 8.0;
|
@@ -57,11 +64,13 @@ public static Command joystickDrive(
|
57 | 64 | omega = Math.copySign(Math.pow(omega, 2), omega);
|
58 | 65 |
|
59 | 66 | // Generate robot relative speeds
|
| 67 | + double linearVelocityScalar = LINEAR_VELOCITY_SCALAR.get(); |
| 68 | + double angularVelocityScalar = ANGULAR_VELOCITY_SCALAR.get(); |
60 | 69 | var speeds =
|
61 | 70 | new ChassisSpeeds(
|
62 |
| - x * DriveConstants.maxLinearVelocityMetersPerSec, |
63 |
| - y * DriveConstants.maxLinearVelocityMetersPerSec, |
64 |
| - omega * DriveConstants.maxAngularVelocityRadPerSec); |
| 71 | + x * DriveConstants.maxLinearVelocityMetersPerSec * linearVelocityScalar, |
| 72 | + y * DriveConstants.maxLinearVelocityMetersPerSec * linearVelocityScalar, |
| 73 | + omega * DriveConstants.maxAngularVelocityRadPerSec * angularVelocityScalar); |
65 | 74 |
|
66 | 75 | // Convert to field relative
|
67 | 76 | Rotation2d rotation = RobotState.getInstance().getRotation();
|
@@ -109,10 +118,11 @@ public static Command joystickDriveAtAngle(
|
109 | 118 | rotation.getRadians(), rotationSupplier.get().getRadians());
|
110 | 119 |
|
111 | 120 | // Generate robot relative speeds
|
| 121 | + double linearVelocityScalar = LINEAR_VELOCITY_SCALAR.get(); |
112 | 122 | var speeds =
|
113 | 123 | new ChassisSpeeds(
|
114 |
| - x * DriveConstants.maxLinearVelocityMetersPerSec, |
115 |
| - y * DriveConstants.maxLinearVelocityMetersPerSec, |
| 124 | + x * DriveConstants.maxLinearVelocityMetersPerSec * linearVelocityScalar, |
| 125 | + y * DriveConstants.maxLinearVelocityMetersPerSec * linearVelocityScalar, |
116 | 126 | omega);
|
117 | 127 |
|
118 | 128 | // Convert to field relative
|
|
0 commit comments