Skip to content

Commit

Permalink
Added turntoAngle
Browse files Browse the repository at this point in the history
Binded turntoAngle to a controller button.

Co-Authored-By: ShasshU <143851930+ShasshU@users.noreply.github.com>
Co-Authored-By: Newbie9012 <175752595+Newbie9012@users.noreply.github.com>
  • Loading branch information
3 people committed Oct 26, 2024
1 parent 802b6d2 commit 20f324e
Show file tree
Hide file tree
Showing 3 changed files with 20 additions and 4 deletions.
7 changes: 4 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,6 @@ public class RobotContainer {

public CANdleSubSystem CANdle = new CANdleSubSystem();
private SwerveJoystickCommand swerveJoystickCommand;
public boolean turnToAngleMode = false;

/**
* The container for the robot. Contain
Expand Down Expand Up @@ -171,7 +170,7 @@ public void initDefaultCommands_teleop() {
// driverController::getR2Button, // Precision/"Sniper Button"
() -> driverController.getR2Button(), // Precision mode (disabled)
() -> {
if (turnToAngleMode) {
if (swerveDrive.getTurnToAngleMode()) {
return (
driverController.getRightX() > 0.0
|| driverController.getRightY() > 0.0
Expand Down Expand Up @@ -306,6 +305,8 @@ public void configureBindings_teleop() {
)
);



commandOperatorController.povUp().onTrue(
Commands.runOnce(() -> superSystem.incrementOffset(0.5))
);
Expand All @@ -317,7 +318,7 @@ public void configureBindings_teleop() {
);
commandDriverController.touchpad().whileTrue(superSystem.shoot())
.whileFalse(superSystem.stow());
commandDriverController.
commandDriverController.triangle().onTrue(swerveDrive.toggleTurnToAngleMode());

commandDriverController.L2().whileTrue(Commands.sequence(
Commands.race(
Expand Down
6 changes: 5 additions & 1 deletion src/main/java/frc/robot/commands/SwerveJoystickCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.Constants.ControllerConstants;
import frc.robot.Constants.SwerveAutoConstants;
import frc.robot.Constants.SwerveDriveConstants;
Expand All @@ -26,7 +27,6 @@
import frc.robot.util.filters.Filter;
import frc.robot.util.filters.FilterSeries;
import frc.robot.util.filters.ScaleFilter;

public class SwerveJoystickCommand extends Command {
private final SwerveDrivetrain swerveDrive;
private final Supplier<Double> xSpdFunction, ySpdFunction, turningSpdFunction;
Expand Down Expand Up @@ -122,6 +122,7 @@ public void initialize() {}

@Override
public void execute() {

if (towSupplier.get()) {
swerveDrive.setModuleStates(SwerveDriveConstants.towModuleStates);
return;
Expand Down Expand Up @@ -199,6 +200,9 @@ public void execute() {

}




public double getTargetAngle() {
return targetAngle;
}
Expand Down
11 changes: 11 additions & 0 deletions src/main/java/frc/robot/subsystems/swerve/SwerveDrivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -479,6 +479,17 @@ public Command turnToSubwoofer(double angleTolerance) {
command.addRequirements(this);
return command;
}

public boolean turnToAngleMode = false;

public Command toggleTurnToAngleMode() {
return Commands.runOnce(() -> turnToAngleMode = !turnToAngleMode);
}

public boolean getTurnToAngleMode() {
return turnToAngleMode;
}

/**
* Get the position of each swerve module
* @return An array of swerve module positions
Expand Down

0 comments on commit 20f324e

Please sign in to comment.