Skip to content

Commit

Permalink
add launcher
Browse files Browse the repository at this point in the history
  • Loading branch information
Keobkeig committed Apr 2, 2024
1 parent 9e10335 commit d3e83d2
Show file tree
Hide file tree
Showing 5 changed files with 175 additions and 0 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
package com.stuypulse.robot.commands.launcher;

import com.stuypulse.robot.subsystems.launcher.Launcher;

import edu.wpi.first.wpilibj2.command.Command;

public class LauncherHoldSpeed extends Command {

private final Launcher launcher;
private final Number launcherSpeed;

public LauncherHoldSpeed(Number launcherSpeed) {
launcher = Launcher.getInstance();
this.launcherSpeed = launcherSpeed;

addRequirements(launcher);
}

@Override
public void execute() {
launcher.setFeederSpeed(0);
launcher.setLaunchSpeed(launcherSpeed);
}

}
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
package com.stuypulse.robot.commands.launcher;

import com.stuypulse.robot.subsystems.launcher.Launcher;

import edu.wpi.first.wpilibj2.command.Command;

public class LauncherIntakeNote extends Command {
Launcher launcher;

public LauncherIntakeNote() {
launcher = Launcher.getInstance();
addRequirements(launcher);
}

@Override
public void execute() {
launcher.intake();
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
package com.stuypulse.robot.commands.launcher;

import com.stuypulse.robot.subsystems.launcher.Launcher;

import edu.wpi.first.wpilibj2.command.Command;

public class LauncherLaunch extends Command {

private final Launcher launcher;
private final Number feederSpeed;
private final Number launcherSpeed;

public LauncherLaunch(Number feederSpeed, Number launcherSpeed) {
this.launcherSpeed = launcherSpeed;
this.feederSpeed = feederSpeed;

launcher = Launcher.getInstance();
addRequirements(launcher);
}

@Override
public void initialize() {
launcher.launch(feederSpeed, launcherSpeed);
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
package com.stuypulse.robot.commands.launcher;

import com.stuypulse.robot.subsystems.launcher.Launcher;

import edu.wpi.first.wpilibj2.command.InstantCommand;

public class LauncherStop extends InstantCommand{
Launcher launcher;

public LauncherStop() {
launcher = Launcher.getInstance();
addRequirements(launcher);
}

@Override
public void initialize() {
launcher.stop();
}

}
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
package com.stuypulse.robot.subsystems.launcher;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.stuypulse.robot.constants.Settings;
import com.stuypulse.robot.constants.Motors;
import com.stuypulse.robot.constants.Ports;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class Launcher extends SubsystemBase {

private static final Launcher instance;

static {
instance = new Launcher();
}

public static Launcher getInstance() {
return instance;
}

private final CANSparkMax feeder;
private final CANSparkMax launcher;

public Launcher() {
feeder = new CANSparkMax(20, MotorType.kBrushless);
launcher = new CANSparkMax(21, MotorType.kBrushless);

Motors.Shooter.LEFT_SHOOTER.configure(feeder);
Motors.Shooter.LEFT_SHOOTER.configure(launcher);

}

//********** SETTERS **********
public void setLaunchSpeed(Number speed) {
launcher.set(speed.doubleValue());
}

public void setFeederSpeed(Number speed) {
feeder.set(speed.doubleValue());
}

public void stop() {
setLaunchSpeed(0);
setFeederSpeed(0);
}

public void intake() {
launcher.set(-.8);
feeder.set(0);
}

public void launch(Number feederSpeed, Number launcherSpeed) {
launcher.set(launcherSpeed.doubleValue());
feeder.set(feederSpeed.doubleValue());
}

//********** GETTERS **********//
public double getLauncherVelocity() {
return launcher.getEncoder().getVelocity();
}

public double getFeederVelocity() {
return feeder.getEncoder().getVelocity();
}

public double getLauncherSpeed() {
return launcher.getAppliedOutput();
}

public double getFeederSpeed() {
return feeder.getAppliedOutput();
}

@Override
public void periodic() {
SmartDashboard.putNumber("Launcher/Launcher Velocity", getLauncherVelocity());
SmartDashboard.putNumber("Launcher/Feeder Velocity", getFeederVelocity());

SmartDashboard.putNumber("Launcher/Launcher Output Speed", getLauncherSpeed());
SmartDashboard.putNumber("Launcher/Feeder Output Speed", getFeederSpeed());

}
}

0 comments on commit d3e83d2

Please sign in to comment.