Skip to content

Commit

Permalink
fix: driver flipping needs to be done in execute for some reason (at …
Browse files Browse the repository at this point in the history
…least in sim)
  • Loading branch information
mimizh2418 committed Feb 10, 2024
1 parent dfdb03f commit e524577
Show file tree
Hide file tree
Showing 2 changed files with 30 additions and 33 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,6 @@

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
Expand All @@ -20,8 +15,6 @@ public class SwerveDriveCommand extends Command {
private final SlewRateLimiter yLimiter = new SlewRateLimiter(2);
private final SlewRateLimiter rotLimiter = new SlewRateLimiter(3);

private boolean isFlipped;

public SwerveDriveCommand(Drivetrain drivetrain, CommandXboxController controller) {
this.drivetrain = drivetrain;
this.controller = controller;
Expand All @@ -33,38 +26,20 @@ public void initialize() {
xLimiter.reset(0);
yLimiter.reset(0);
rotLimiter.reset(0);
isFlipped =
DriverStation.getAlliance().isPresent()
&& DriverStation.getAlliance().get() == DriverStation.Alliance.Red;

}

@Override
public void execute() {
double xPercent = xLimiter.calculate(-controller.getLeftY());
double yPercent = yLimiter.calculate(-controller.getLeftX());
double rotPercent = rotLimiter.calculate(-controller.getRightX());

// Apply deadband
double linearMagnitude = MathUtil.applyDeadband(Math.hypot(xPercent, yPercent), 0.1);
Rotation2d linearDirection = new Rotation2d(xPercent, yPercent);
double omega = MathUtil.applyDeadband(rotPercent, 0.1);
boolean isFlipped =
DriverStation.getAlliance().isPresent()
&& DriverStation.getAlliance().get() == DriverStation.Alliance.Red;

// Calculate new linear velocity
Translation2d linearVelocity =
new Pose2d(new Translation2d(), linearDirection)
.transformBy(new Transform2d(linearMagnitude, 0.0, new Rotation2d())).getTranslation();
double xPercent = MathUtil.applyDeadband(xLimiter.calculate(-controller.getLeftY()), 0.1);
double yPercent = MathUtil.applyDeadband(yLimiter.calculate(-controller.getLeftX()), 0.1);
double rotPercent = MathUtil.applyDeadband(rotLimiter.calculate(-controller.getRightX()), 0.1);

// Convert to field relative speeds & send command
drivetrain.runVelocity(
ChassisSpeeds.fromFieldRelativeSpeeds(
linearVelocity.getX() * drivetrain.getMaxLinearSpeedMetersPerSec(),
linearVelocity.getY() * drivetrain.getMaxLinearSpeedMetersPerSec(),
omega * drivetrain.getMaxAngularSpeedRadPerSec(),
isFlipped
? drivetrain.getRotation().plus(Rotation2d.fromDegrees(180))
: drivetrain.getRotation()
)
);
drivetrain.drivePercent(xPercent, yPercent, rotPercent, isFlipped);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
Expand Down Expand Up @@ -125,6 +126,27 @@ public void runVelocity(ChassisSpeeds speeds) {
Logger.recordOutput("SwerveStates/SetpointsOptimized", optimizedSetpointStates);
}

public void drivePercent(double xPercent, double yPercent, double rotPercent, boolean isFlipped) {
Rotation2d linearDirection = new Rotation2d(xPercent, yPercent);
double linearMagnitude = Math.hypot(xPercent, yPercent);

Translation2d linearVelocity =
new Pose2d(new Translation2d(), linearDirection)
.transformBy(new Transform2d(linearMagnitude, 0.0, new Rotation2d())).getTranslation();

// Convert to field relative
runVelocity(
ChassisSpeeds.fromFieldRelativeSpeeds(
linearVelocity.getX() * getMaxLinearSpeedMetersPerSec(),
linearVelocity.getY() * getMaxLinearSpeedMetersPerSec(),
rotPercent * getMaxAngularSpeedRadPerSec(),
isFlipped
? getRotation().plus(Rotation2d.fromDegrees(180))
: getRotation()
)
);
}

/**
* Stops the drive.
*/
Expand Down

0 comments on commit e524577

Please sign in to comment.