Skip to content

Commit

Permalink
changed feeder speed based on action, commented camera streams
Browse files Browse the repository at this point in the history
  • Loading branch information
Tmanxyz committed Jul 17, 2024
1 parent b1fc6f2 commit 74b346c
Show file tree
Hide file tree
Showing 13 changed files with 84 additions and 32 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ public ShooterAcquireFromIntake() {
@Override
public void initialize() {
intake.acquire();
shooter.runFeederForwards();
shooter.feederIntake();
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,18 @@

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

public class ShooterFeederAcquireForever extends InstantCommand {
public class ShooterFeederAcquire extends InstantCommand {

private final Shooter shooter;

public ShooterFeederAcquireForever() {
public ShooterFeederAcquire() {
shooter = Shooter.getInstance();
addRequirements(shooter);
}

@Override
public void initialize() {
shooter.runFeederForwards();
shooter.feederIntake();
}

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

import com.stuypulse.robot.subsystems.shooter.Shooter;

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

public class ShooterFeederDeacquire extends InstantCommand {

private final Shooter shooter;

public ShooterFeederDeacquire() {
shooter = Shooter.getInstance();
addRequirements(shooter);
}

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

import com.stuypulse.robot.subsystems.shooter.Shooter;

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

public class ShooterFeederShoot extends InstantCommand {

private final Shooter shooter;

public ShooterFeederShoot() {
shooter = Shooter.getInstance();
addRequirements(shooter);
}

@Override
public void initialize() {
shooter.feederShoot();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ public ShooterFerry() {
addCommands(
new ShooterSetRPM(Settings.Shooter.FERRY),
new ShooterWaitForTarget().withTimeout((Settings.Shooter.MAX_WAIT_TO_REACH_TARGET))
.andThen(new ShooterFeederAcquireForever())
.andThen(new ShooterFeederShoot())
);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,18 +3,17 @@
import com.stuypulse.robot.subsystems.shooter.Shooter;

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

public class ShooterScoreAmp extends InstantCommand{

private final Shooter shooter;
public class ShooterScoreAmp extends SequentialCommandGroup {

public ShooterScoreAmp() {
shooter = Shooter.getInstance();
addRequirements(shooter);
}

@Override
public void initialize() {
shooter.runFeederBackwards();
addCommands(
new ShooterFeederDeacquire(),
new WaitUntilCommand(() -> !Shooter.getInstance().hasNote()),
new WaitUntilCommand(1),
new InstantCommand(() -> Shooter.getInstance().stopFeeder())
);
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ public ShooterScoreSpeaker() {
addCommands(
new ShooterSetRPM(Settings.Shooter.SPEAKER),
new ShooterWaitForTarget().withTimeout(Settings.Shooter.MAX_WAIT_TO_REACH_TARGET)
.andThen(new ShooterFeederAcquireForever())
.andThen(new ShooterFeederShoot())
);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ private double getAngleTolerance() {
public void execute() {
super.execute();
if (canShoot.get()) {
shooter.runFeederForwards();
shooter.feederShoot();
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ private double getAngleTolerance() {
public void execute() {
super.execute();
if (canShoot.get()) {
shooter.runFeederForwards();
shooter.feederShoot();
}
}

Expand Down
5 changes: 5 additions & 0 deletions src/main/java/com/stuypulse/robot/constants/Cameras.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,11 @@ public interface Limelight {
int[] PORTS = {5800, 5801, 5802, 5803, 5804, 5805};
}

//192.168.1.83:5802
//192.168.1.71.5802

//192.168.1.ip.defaultport

public CameraConfig[] APRILTAG_CAMERAS = new CameraConfig[] {
// TO DO: find positions
new CameraConfig(
Expand Down
10 changes: 6 additions & 4 deletions src/main/java/com/stuypulse/robot/constants/Settings.java
Original file line number Diff line number Diff line change
Expand Up @@ -61,12 +61,12 @@ public interface Arm {

SmartNumber MAX_ANGLE = new SmartNumber("Arm/Max Angle (deg)", 100);
SmartNumber MIN_ANGLE = new SmartNumber("Arm/Min Angle (deg)", -90 + 12.25);
SmartNumber MAX_ANGLE_ERROR = new SmartNumber("Arm/Max Angle Error", 1);
SmartNumber MAX_ANGLE_ERROR = new SmartNumber("Arm/Max Angle Error", 2);

SmartNumber AMP_ANGLE = new SmartNumber("Arm/Amp Angle", 70);
SmartNumber FERRY_ANGLE = new SmartNumber("Arm/Lob Ferry Angle", -60);
SmartNumber PRE_CLIMB_ANGLE = new SmartNumber("Arm/Pre climb angle", 80);
SmartNumber FEED_ANGLE = new SmartNumber("Arm/Feed Angle", MIN_ANGLE.getAsDouble() + 0);
SmartNumber FEED_ANGLE = new SmartNumber("Arm/Feed Angle", MIN_ANGLE.getAsDouble() + 17); //0
SmartNumber PODIUM_SHOT_ANGLE = new SmartNumber("Arm/Podium Shot Angle", -60);

SmartNumber BUMP_SWITCH_DEBOUNCE_TIME = new SmartNumber("Arm/Bump Switch Debounce Time", 0.02);
Expand Down Expand Up @@ -94,15 +94,17 @@ public interface Encoder {
}

public interface Intake {
double INTAKE_ACQUIRE_SPEED = 0.82;
double INTAKE_ACQUIRE_SPEED = 0.75;
double INTAKE_DEACQUIRE_SPEED = 1.0;
double FUNNEL_ACQUIRE = 1.0;
double FUNNEL_DEACQUIRE = 1.0;
double IR_DEBOUNCE = .005;
}

public interface Shooter {
double FEEDER_SPEED = 0.23;
double FEEDER_INTAKE_SPEED = 0.24;
double FEEDER_DEAQUIRE_SPEED = 0.5;
double FEEDER_SHOOT_SPEED = 1.0;

double TARGET_RPM_THRESHOLD = 300;
double MAX_WAIT_TO_REACH_TARGET = 2;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,16 +40,17 @@ public double getRightTargetRPM() {
}

public void stop() {
stopFeeder();
feederStop();
leftTargetRPM.set(0);
rightTargetRPM.set(0);
}

public abstract boolean atTargetSpeeds();

public abstract void runFeederForwards();
public abstract void runFeederBackwards();
public abstract void stopFeeder();
public abstract void feederIntake();
public abstract void feederDeacquire();
public abstract void feederShoot();
public abstract void feederStop();

public abstract boolean hasNote();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,17 +93,22 @@ private void setRightShooterRPM(double rpm) {
}

@Override
public void runFeederForwards() {
feederMotor.set(+Settings.Shooter.FEEDER_SPEED);
public void feederIntake() {
feederMotor.set(+Settings.Shooter.FEEDER_INTAKE_SPEED);
}

@Override
public void runFeederBackwards() {
feederMotor.set(-Settings.Shooter.FEEDER_SPEED);
public void feederDeacquire() {
feederMotor.set(-Settings.Shooter.FEEDER_DEAQUIRE_SPEED);
}

@Override
public void stopFeeder() {
public void feederShoot() {
feederMotor.set(Settings.Shooter.FEEDER_SHOOT_SPEED);
}

@Override
public void feederStop() {
feederMotor.stopMotor();
}

Expand Down

0 comments on commit 74b346c

Please sign in to comment.