Skip to content

Commit

Permalink
Cap max speeds for driving.
Browse files Browse the repository at this point in the history
  • Loading branch information
frc1987 committed Apr 21, 2024
1 parent b36105d commit a3ff669
Showing 1 changed file with 7 additions and 3 deletions.
10 changes: 7 additions & 3 deletions src/main/java/frc/robot/commands/movement/SwerveCommand.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
package frc.robot.commands.movement;

import com.ctre.phoenix6.mechanisms.swerve.SwerveRequest;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj2.command.Command;
Expand All @@ -23,6 +25,8 @@
*/
public class SwerveCommand extends Command {

static private final double MAX_SPEED_TRANSLATION = 2.0;

private final PIDController THETA_CONTROLLER;
private final IntSupplier POV_DEGREE;
private boolean isCardinalLocking = false;
Expand Down Expand Up @@ -109,13 +113,13 @@ public void execute() {
// DRIVETRAIN.getPose().getRotation().getDegrees(), THETA_CONTROLLER.getSetpoint());
// }

double rotationalVelocity = rotationPercentage;
double rotationalVelocity = MathUtil.clamp(rotationPercentage, -Math.PI, Math.PI);

DRIVETRAIN.setControl(
DRIVE_REQUEST
.withVelocityX(xPercentage) // Drive forward with
.withVelocityX(MathUtil.clamp(xPercentage, -MAX_SPEED_TRANSLATION, MAX_SPEED_TRANSLATION)) // Drive forward with
// negative Y (forward)
.withVelocityY(yPercentage) // Drive left with negative X (left)
.withVelocityY(MathUtil.clamp(yPercentage, -MAX_SPEED_TRANSLATION, MAX_SPEED_TRANSLATION)) // Drive left with negative X (left)
.withRotationalRate(rotationalVelocity));
}

Expand Down

0 comments on commit a3ff669

Please sign in to comment.