Skip to content

Commit

Permalink
Created ShooterBase subsystem and command using right trigger
Browse files Browse the repository at this point in the history
  • Loading branch information
StewardHail3433 committed Jan 14, 2024
1 parent b85507f commit 6a5ee36
Show file tree
Hide file tree
Showing 4 changed files with 123 additions and 1 deletion.
24 changes: 23 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,15 +4,37 @@

package frc.robot;

import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.commands.ShooterBaseCommand;
import frc.robot.subsystems.shooter.ShooterBase;

public class RobotContainer {
public final XboxController controller;
public final ShooterBase shooter;

public RobotContainer() {
controller = new XboxController(0);

boolean swerveBot = false;
boolean tankBot = false;

if (swerveBot) {
shooter = null;
} else if (tankBot) {
shooter = null;
} else {
shooter = new ShooterBase();
}


configureBindings();
}

private void configureBindings() {}
private void configureBindings() {
shooter.setDefaultCommand(new ShooterBaseCommand(shooter, () -> controller.getRightTriggerAxis() ));
}

public Command getAutonomousCommand() {
return Commands.print("No autonomous command configured");
Expand Down
52 changes: 52 additions & 0 deletions src/main/java/frc/robot/commands/ShooterBaseCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
package frc.robot.commands;



import java.util.Map;
import java.util.function.DoubleSupplier;

import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.shooter.ShooterBase;

public class ShooterBaseCommand extends Command {
ShooterBase shooter;
DoubleSupplier rightTriggerAxis;
ShuffleboardTab tab;
GenericEntry speedEntry;

public ShooterBaseCommand(ShooterBase shooter, DoubleSupplier rightTriggerAxis) {
this.shooter = shooter;
this.rightTriggerAxis = rightTriggerAxis;

//create shooter tab on ShuffleBoard
tab = Shuffleboard.getTab("Shooter");

addRequirements(shooter);
}
@Override
public void initialize() {
// create speed entry under Shooter tab as a number sider with min = -1 and max = 1
speedEntry = tab.add("speed", 0).withWidget(BuiltInWidgets.kNumberSlider)
.withProperties(Map.of("min", -1, "max", 1)).getEntry();

//sets default value to 0.0
speedEntry.setValue(0.0);
}


@Override
public void execute() {
//turns on motors if right trigger is fully pressed. else the motors turn off.
if (rightTriggerAxis.getAsDouble() == 1.0) {
shooter.setSpeed(speedEntry.getDouble(0.0));
shooter.enable();
} else {
shooter.disable();
}
}
}
12 changes: 12 additions & 0 deletions src/main/java/frc/robot/subsystems/shooter/Shooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
package frc.robot.subsystems.shooter;

public interface Shooter {
// Disable the shooter
public default void disable() {}

// Enable the shooter with the .
public default void enable() {}

// Set the speed of the motors.
public default void setSpeed(double speed) {}
}
36 changes: 36 additions & 0 deletions src/main/java/frc/robot/subsystems/shooter/ShooterBase.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
package frc.robot.subsystems.shooter;

import edu.wpi.first.wpilibj.motorcontrol.Spark;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class ShooterBase extends SubsystemBase implements Shooter {
private final Spark ShooterMotorLeft;
private final Spark ShooterMotorRight;
private double voltage;

public ShooterBase() {
ShooterMotorLeft = new Spark(0);
ShooterMotorRight = new Spark(1);
voltage = 0;
}

@Override
public void disable() {
voltage = 0;
ShooterMotorLeft.stopMotor();
ShooterMotorRight.stopMotor();
//System.out.println(voltage);
}

@Override
public void enable() {
ShooterMotorLeft.setVoltage(voltage);
System.out.println(voltage);
}

@Override
public void setSpeed(double speed) {
//Sets the voltage to 5.0 times speed. the speed value is -1 1
this.voltage = 5.0 * speed;
}
}

0 comments on commit 6a5ee36

Please sign in to comment.