Skip to content

Commit

Permalink
changed LED states to be in intake and shooter subsystems
Browse files Browse the repository at this point in the history
  • Loading branch information
SturrockPeter committed Jun 23, 2024
1 parent d776edb commit f6c5cc0
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 10 deletions.
11 changes: 2 additions & 9 deletions src/main/java/frc/robot/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.Constants;
import java.util.function.DoubleSupplier;
import edu.wpi.first.wpilibj.PWM;

/** Our Arm Subsystem */
public class Arm extends SubsystemBase {
Expand All @@ -43,8 +42,6 @@ public enum Setpoint {
private DoubleLogEntry log_ff_output = new DoubleLogEntry(m_log, "/arm/ff/output");
private StringLogEntry log_setpoint = new StringLogEntry(m_log, "/arm/setpoint");

PWM lEDPwm = new PWM(0);

/**
* Creates a new {@link Arm} {@link edu.wpi.first.wpilibj2.command.Subsystem}.
*
Expand Down Expand Up @@ -132,22 +129,18 @@ public Command goToSetpoint(Setpoint setpoint) {
switch (setpoint) {
case kAmp:
position = 5.34;
lEDPwm.setSpeed(0.67);
break;

case kSpeaker:
case kIntake:
position = 3.7;
lEDPwm.setSpeed(0.73);
break;

case kIntake:
case kSpeaker:
position = 3.7;
lEDPwm.setSpeed(0.57);
break;

case kStowed:
position = 3.7;
lEDPwm.setSpeed(0.99);
break;
}

Expand Down
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/subsystems/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,17 +11,21 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj.PWM;

public class Intake extends SubsystemBase {
private CANSparkMax m_motor;
private DataLog log = DataLogManager.getLog();
private DoubleLogEntry log_output = new DoubleLogEntry(log, "/intake/output");

PWM lEDPwm = new PWM(0);

public Intake(CANSparkMax motor) {
m_motor = motor;
}

public Command intake() {
lEDPwm.setSpeed(0.59); // dark red //
return Commands.run(
() -> {
log_output.append(4);
Expand All @@ -36,6 +40,7 @@ public Command stop() {
}

public Command outake() {
lEDPwm.setSpeed(0.63); // red orange, 0.65 for normal orange //
return Commands.run(
() -> {
log_output.append(-4);
Expand Down
7 changes: 6 additions & 1 deletion src/main/java/frc/robot/subsystems/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.Constants;
import edu.wpi.first.wpilibj.PWM;

/** Our Crescendo shooter Subsystem */
public class Shooter extends SubsystemBase {
Expand All @@ -24,7 +25,8 @@ public class Shooter extends SubsystemBase {
private RelativeEncoder m_encoder;
private DataLog m_log = DataLogManager.getLog();
private DoubleLogEntry log_pid_output = new DoubleLogEntry(m_log, "/shooter/pid/output");


PWM lEDPwm = new PWM(0);
/**
* Creates a new {@link Shooter} {@link edu.wpi.first.wpilibj2.command.Subsystem}.
*
Expand Down Expand Up @@ -57,10 +59,12 @@ private Command achieveSpeeds(double speed) {
* @return a {@link Command} to get to the desired speed.
*/
public Command spinup(double speed) {
lEDPwm.setSpeed(0.69); // yellow //
return achieveSpeeds(speed).until(m_pid::atSetpoint);
}

public Command stop() {
lEDPwm.setSpeed(0.73); // lime //
return runOnce(() -> m_motor.set(0));
}

Expand All @@ -70,6 +74,7 @@ public Command stop() {
* @return A {@link Command} to hold the speed at the setpoint.
*/
public Command maintain() {
lEDPwm.setSpeed(0.57); // hot pink //
return achieveSpeeds(m_pid.getSetpoint());
}

Expand Down

0 comments on commit f6c5cc0

Please sign in to comment.