Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add conveyor commands #14

Merged
merged 3 commits into from
Jan 28, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
package com.stuypulse.robot.commands.conveyor;

import com.stuypulse.robot.subsystems.conveyor.Conveyor;

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

public class ConveyorShoot extends Command{

private final Conveyor conveyor;

public ConveyorShoot() {
conveyor = Conveyor.getInstance();

addRequirements(conveyor);
}

@Override
public void initialize() {
conveyor.toShooter();
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
package com.stuypulse.robot.commands.conveyor;

import com.stuypulse.robot.subsystems.conveyor.Conveyor;

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

public class ConveyorStop extends Command{

private Conveyor conveyor;

public ConveyorStop() {
conveyor = Conveyor.getInstance();

addRequirements(conveyor);
}

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

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

import com.stuypulse.robot.subsystems.conveyor.Conveyor;

import com.stuypulse.robot.subsystems.intake.Intake;

import com.stuypulse.robot.subsystems.amper.Amper;

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

public class ConveyorToAmp extends Command{

private final Conveyor conveyor;
private final Intake intake;
private final Amper amper;

public ConveyorToAmp() {
conveyor = Conveyor.getInstance();
intake = Intake.getInstance();
amper = Amper.getInstance();

addRequirements(conveyor, intake, amper);
}

@Override
public void execute() {
conveyor.toAmp();
intake.acquire();
}

@Override
public void end(boolean interrupted) {
conveyor.stop();
intake.stop();
amper.stopRoller();
}

@Override
public boolean isFinished() {
return amper.hasNote();
}
}


Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
package com.stuypulse.robot.commands.conveyor;

import com.stuypulse.robot.subsystems.conveyor.Conveyor;

import com.stuypulse.robot.subsystems.intake.Intake;

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

public class ConveyorToShooter extends Command{

private final Conveyor conveyor;
private final Intake intake;

public ConveyorToShooter() {
conveyor = Conveyor.getInstance();
intake = Intake.getInstance();

addRequirements(conveyor, intake);
}

@Override
public void execute() {
conveyor.toShooter();
intake.acquire();
}

@Override
public void end(boolean interrupted) {
conveyor.stop();
intake.stop();
}

@Override
public boolean isFinished() {
return conveyor.isNoteAtShooter();
}

}
5 changes: 3 additions & 2 deletions src/main/java/com/stuypulse/robot/constants/Settings.java
Original file line number Diff line number Diff line change
Expand Up @@ -224,8 +224,9 @@ public interface Detection {

public interface Conveyor {
SmartNumber GANDALF_SHOOTER_SPEED = new SmartNumber("Conveyor/Gandalf Shooter Speed", 1);
SmartNumber GANDALF_AMP_SPEED = new SmartNumber("Conveyor/Gandalf Amp Speed", -1);
SmartNumber SHOOTER_FEEDER_SPEED = new SmartNumber("Conveyor/Shooter Feeder Speed", 1);
SmartNumber GANDALF_AMP_SPEED = new SmartNumber("Conveyor/Gandalf Amp Speed", 1);
SmartNumber FEEDER_SHOOTER_SPEED = new SmartNumber("Conveyor/Shooter Feeder Speed", 1);
SmartNumber FEEDER_AMP_SPEED = new SmartNumber("Conveyor/Shooter Feeder Speed", 1);

SmartNumber DEBOUNCE_TIME = new SmartNumber("Conveyor/Debounce Time", 0.2);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,14 +26,10 @@ public static Conveyor getInstance(){
return instance;
};


public abstract void toShooter();

public abstract void toAmp();

public abstract boolean isNoteAtShooter();

public abstract void stop();

public abstract boolean isNoteAtShooter();
}

Original file line number Diff line number Diff line change
Expand Up @@ -11,15 +11,13 @@
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;



public class ConveyorImpl extends Conveyor {

private final CANSparkMax gandalfMotor;
private final CANSparkMax shooterFeederMotor;
private final DigitalInput irSensor;

private BStream isAtShooter;
private final BStream isAtShooter;

protected ConveyorImpl() {
gandalfMotor = new CANSparkMax(Ports.Conveyor.GANDALF, MotorType.kBrushless);
Expand All @@ -43,13 +41,13 @@ public boolean isNoteAtShooter() {
@Override
public void toShooter() {
gandalfMotor.set(Settings.Conveyor.GANDALF_SHOOTER_SPEED.get());
shooterFeederMotor.set(Settings.Conveyor.SHOOTER_FEEDER_SPEED.get());
shooterFeederMotor.set(Settings.Conveyor.FEEDER_SHOOTER_SPEED.get());
}

@Override
public void toAmp() {
gandalfMotor.set(Settings.Conveyor.GANDALF_AMP_SPEED.get());

gandalfMotor.set(-Settings.Conveyor.GANDALF_AMP_SPEED.get());
shooterFeederMotor.set(Settings.Conveyor.FEEDER_AMP_SPEED.get());
}

public void stop() {
Expand All @@ -59,15 +57,11 @@ public void stop() {

@Override
public void periodic() {

//logging
SmartDashboard.putNumber("Conveyor/Gandalf Motor Current", gandalfMotor.getOutputCurrent());
SmartDashboard.putNumber("Conveyor/Shooter Feeder Motor Current", shooterFeederMotor.getOutputCurrent());

SmartDashboard.putNumber("Conveyor/Gandalf Motor Speed", gandalfMotor.get());
SmartDashboard.putNumber("Conveyor/Shooter Feeder Motor Spped", shooterFeederMotor.get());

}


}
Loading