Skip to content

Commit

Permalink
Format with Spotless
Browse files Browse the repository at this point in the history
  • Loading branch information
jonahsnider committed Sep 25, 2024
1 parent c6f25b5 commit 767271a
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 12 deletions.
15 changes: 10 additions & 5 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -133,11 +133,16 @@ public void testPeriodic() {}
public void testExit() {}

private void configureBindings() {
swerve.setDefaultCommand(swerve.run(() -> {
if (DriverStation.isTeleop()) {
swerve.driveTeleop(hardware.driverController.getLeftX(),hardware.driverController.getLeftY() , hardware.driverController.getRightX());
}
}));
swerve.setDefaultCommand(
swerve.run(
() -> {
if (DriverStation.isTeleop()) {
swerve.driveTeleop(
hardware.driverController.getLeftX(),
hardware.driverController.getLeftY(),
hardware.driverController.getRightX());
}
}));

hardware
.driverController
Expand Down
10 changes: 3 additions & 7 deletions src/main/java/frc/robot/swerve/SwerveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.config.RobotConfig;
import frc.robot.fms.FmsSubsystem;
import frc.robot.util.ControllerHelpers;
Expand Down Expand Up @@ -120,14 +119,11 @@ public void setFieldRelativeAutoSpeeds(ChassisSpeeds speeds) {
public void driveTeleop(double x, double y, double theta) {
double leftY =
-1.0
* ControllerHelpers.getExponent(
ControllerHelpers.getDeadbanded(x, leftYDeadband), 1.5);
* ControllerHelpers.getExponent(ControllerHelpers.getDeadbanded(x, leftYDeadband), 1.5);
double leftX =
ControllerHelpers.getExponent(
ControllerHelpers.getDeadbanded(y, leftXDeadband), 1.5);
ControllerHelpers.getExponent(ControllerHelpers.getDeadbanded(y, leftXDeadband), 1.5);
double rightX =
ControllerHelpers.getExponent(
ControllerHelpers.getDeadbanded(theta, rightXDeadband), 2);
ControllerHelpers.getExponent(ControllerHelpers.getDeadbanded(theta, rightXDeadband), 2);

if (RobotConfig.get().swerve().invertRotation()) {
rightX *= -1.0;
Expand Down

0 comments on commit 767271a

Please sign in to comment.