Skip to content

Commit

Permalink
switch to functional command builder syntax
Browse files Browse the repository at this point in the history
  • Loading branch information
rohan committed Sep 3, 2023
1 parent 368dd12 commit f7ae3ca
Show file tree
Hide file tree
Showing 4 changed files with 12 additions and 14 deletions.
5 changes: 2 additions & 3 deletions src/main/java/com/arc852/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -54,9 +54,8 @@ public Arm() {
* @return command that does the thing
*/
public Command set(double radians) {
return new InstantCommand(
() -> pos = MathUtil.clamp(radians, Constants.Arm.MIN_ANGLE, Constants.Arm.MAX_ANGLE),
this);
return runOnce(
() -> pos = MathUtil.clamp(radians, Constants.Arm.MIN_ANGLE, Constants.Arm.MAX_ANGLE));
}

@Log
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/com/arc852/subsystems/Elevator.java
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ public Elevator() {
* @return Command
*/
public Command set(double percent) {
return new InstantCommand(() -> pos = percent * (MAX_HEIGHT - MIN_HEIGHT) + MIN_HEIGHT, this);
return runOnce(() -> pos = percent * (MAX_HEIGHT - MIN_HEIGHT) + MIN_HEIGHT);
}

@Log
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/com/arc852/subsystems/Grabber.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,18 +36,18 @@ public Command open() {
}

public Command close() {
return new InstantCommand(
return runOnce(
() -> {
leftSolenoid.set(true);
rightSolenoid.set(false);
});
}

public Command spinForward() {
return new StartEndCommand(() -> motor.set(.2), () -> motor.set(0), this);
return startEnd(() -> motor.set(.2), () -> motor.set(0));
}

public Command spinBackward() {
return new StartEndCommand(() -> motor.set(-.2), () -> motor.set(0), this);
return startEnd(() -> motor.set(-.2), () -> motor.set(0));
}
}
13 changes: 6 additions & 7 deletions src/main/java/com/arc852/subsystems/Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@ public Command autoBalance() {
pid.setSetpoint(0);
pid.setTolerance(3);

return new RunCommand(
return run(
() -> {
double power = pid.calculate(gyro.getPitch());
double translationVal = MathUtil.applyDeadband(power, Constants.stickDeadband);
Expand Down Expand Up @@ -225,7 +225,7 @@ public Command drive(
SlewRateLimiter translationLimiter = new SlewRateLimiter(2);
SlewRateLimiter strafeLimiter = new SlewRateLimiter(2);

return new RunCommand(
return run(
() -> {
double translationVal =
translationLimiter.calculate(
Expand All @@ -242,23 +242,22 @@ public Command drive(
rotationVal * Constants.Swerve.maxAngularVelocity,
!robotCentricSup.getAsBoolean(),
true);
},
this);
});
}

public Command drive(
DoubleSupplier translationSup, DoubleSupplier strafeSup, Supplier<Rotation2d> rohtation) {
SlewRateLimiter translationLimiter = new SlewRateLimiter(2);
SlewRateLimiter strafeLimiter = new SlewRateLimiter(2);

return new InstantCommand(
return runOnce(
() -> {
thetaController.reset(getPose().getRotation().getRadians());
thetaController.setGoal(rohtation.get().getRadians());
thetaController.setTolerance(0.05);
})
.andThen(
new RunCommand(
run(
() -> {
double translationVal =
translationLimiter.calculate(
Expand All @@ -279,7 +278,7 @@ public Command drive(
}

public Command lockWheels() {
return new InstantCommand(
return runOnce(
() -> {
for (SwerveModule mods : swerveModules) {
mods.setDesiredState(new SwerveModuleState(0, new Rotation2d(Math.PI)), false);
Expand Down

0 comments on commit f7ae3ca

Please sign in to comment.