Skip to content

Commit

Permalink
Drive directly back no shooty
Browse files Browse the repository at this point in the history
  • Loading branch information
TheMagneticDude committed Mar 5, 2024
1 parent 62bc027 commit 8240d95
Show file tree
Hide file tree
Showing 2 changed files with 36 additions and 0 deletions.
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
import frc.robot.commands.WinchCommand;
import frc.robot.commands.WinchPresetCommand;
import frc.robot.commands.ZeroHeadingCommand;
import frc.robot.commands.auto.DriveAutoCommand;
import frc.robot.commands.auto.ShootAndDriveAutoCommand;
import frc.robot.commands.auto.TurnAndShootAutoCommand;
import frc.robot.subsystems.ClimberSubsystem;
Expand Down Expand Up @@ -86,6 +87,9 @@ public RobotContainer() {
m_chosenAuto.addOption("Drive, turn, and shoot from right",
new TurnAndShootAutoCommand(m_shooterSubsystem, m_robotDrive, new Pose2d(), -55));

m_chosenAuto.addOption("Drive back only",
new DriveAutoCommand(m_shooterSubsystem, m_robotDrive, new Pose2d(0,0,Rotation2d.fromDegrees(0)))); //drive back only auto

m_tab.add(m_chosenAuto);

// Configure the button bindings
Expand Down
32 changes: 32 additions & 0 deletions src/main/java/frc/robot/commands/auto/DriveAutoCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands.auto;

import java.util.function.Supplier;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.ParallelRaceGroup;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import frc.robot.commands.SetPoseCommand;
import frc.robot.commands.ShootCommand;
import frc.robot.commands.SwerveDriveCommand;
import frc.robot.commands.TurnThetaCommand;
import frc.robot.subsystems.ShooterSubsystem;
import frc.robot.subsystems.SwerveSubsystem;

public class DriveAutoCommand extends SequentialCommandGroup {
public DriveAutoCommand(ShooterSubsystem shoot, SwerveSubsystem swerve, Pose2d startingOffset) {
super(
new SetPoseCommand(swerve, startingOffset).withTimeout(0),
new SwerveDriveCommand(swerve, supplyDouble(0), supplyDouble(-.3), supplyDouble(0), true, supplyBoolean(true), supplyDouble(-1))
.withTimeout(3),
new TurnThetaCommand(swerve, 0)
);
}

private static Supplier<Double> supplyDouble(double d) {return new Supplier<Double>() {@Override public Double get() {return d;}};}
private static Supplier<Boolean> supplyBoolean(boolean b) {return new Supplier<Boolean>() {@Override public Boolean get() {return b;}};}
}

0 comments on commit 8240d95

Please sign in to comment.