Skip to content

Commit

Permalink
made LEDs for the shoot command🦟™️ (#77)
Browse files Browse the repository at this point in the history
* made LEDs for the shoot command🦟™️

* made different LED colors for the different commands🦟™️

* hopefullt last conflict

* removed LEDs from drive and readded the things i accidentally removed🦟™️

* undid not needed changes

* forgot to delete this
  • Loading branch information
BrodyKarr authored Dec 7, 2024
1 parent b1dc55f commit 2749723
Show file tree
Hide file tree
Showing 14 changed files with 146 additions and 26 deletions.
18 changes: 18 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,29 @@

/** Add your docs here. */
public class Constants {

public static class constDrivetrain {
public static final double SLOW_MODE_MULTIPLIER = 0.5;
public static final double CONTROLLER_DEADZONE = 0.2;
}

public static class constLED {
public static final double LED_BRIGHTNESS = 1;
public static final int LED_NUMBER = 192;
public static final int LED_STRIP_START_INDEX = 8;
public static final int[] CLEAR_LEDS = { 0, 0, 0 };
public static final int[] LED_SHOOTING = { 105, 69, 9 };
public static final int[] LED_PREP_SHOOTING = { 254, 212, 6 };
public static final int[] LED_NONE = { 2, 157, 254 };
public static final int[] LED_INTAKE_HOPPER = { 133, 249, 1 };
public static final int[] LED_INTAKE_GROUND = { 187, 1, 249 };
public static final int[] LED_HASGP = { 249, 1, 109 };
public static final int[] LED_FULL_HOPPER = { 255, 255, 255 };
public static final int[] LED_EJECTGP = { 3, 242, 230 };
public static final int[] LED_DRIVE = { 109, 11, 140 };

}

public static class constIntake {
public static final double INTAKE_EJECT_VELOCITY = -0.5;
public static final double INTAKE_VELOCITY = 0.5;
Expand Down
16 changes: 7 additions & 9 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
@@ -1,7 +1,3 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot;

import com.frcteam3255.joystick.SN_XboxController;
Expand All @@ -17,23 +13,25 @@
import frc.robot.subsystems.Drivetrain;
import frc.robot.subsystems.Hopper;
import frc.robot.subsystems.Intake;
import frc.robot.subsystems.LED;
import frc.robot.subsystems.Shooter;
import frc.robot.subsystems.Stager;

public class RobotContainer {
private final SN_XboxController m_driverController = new SN_XboxController(RobotMap.mapControllers.DRIVER_USB);
private final Drivetrain subDrivetrain = new Drivetrain();
private final LED subLED = new LED();
private final Intake subIntake = new Intake();
private final Hopper subHopper = new Hopper();
private final Shooter subShooter = new Shooter();
private final Stager subStager = new Stager();
private final Drive com_Drive = new Drive(subDrivetrain, m_driverController.axis_RightX,
m_driverController.axis_LeftY, m_driverController.btn_LeftBumper);
private final IntakeGround com_IntakeGround = new IntakeGround(subIntake, subStager);
private final PrepShooter com_PrepShooter = new PrepShooter(subShooter);
private final Shoot com_Shoot = new Shoot(subStager, subShooter);
private final intakeHopper com_IntakeHopper = new intakeHopper(subHopper, subStager);
private final EjectShooter com_EjectShooter = new EjectShooter(subStager, subShooter);
private final IntakeGround com_IntakeGround = new IntakeGround(subIntake, subStager, subLED);
private final PrepShooter com_PrepShooter = new PrepShooter(subShooter, subLED);
private final Shoot com_Shoot = new Shoot(subStager, subShooter, subLED);
private final intakeHopper com_IntakeHopper = new intakeHopper(subHopper, subStager, subLED);
private final EjectShooter com_EjectShooter = new EjectShooter(subStager, subShooter, subLED);

public RobotContainer() {
subDrivetrain.setDefaultCommand(com_Drive);
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -41,4 +41,9 @@ public static class mapStager {

}

public static class mapLED {
public static final int LED_CAN = 0;

}

}
15 changes: 10 additions & 5 deletions src/main/java/frc/robot/commands/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@

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

import frc.robot.subsystems.Drivetrain;

public class Drive extends Command {
Expand All @@ -18,29 +19,33 @@ public class Drive extends Command {
DoubleSupplier globalRotationSpeed;
Trigger globalSlowMode;

public Drive(Drivetrain passedDrivetrain, DoubleSupplier passedForwardSpeed, DoubleSupplier passedRotationSpeed, Trigger passedSlowMode) {
public Drive(Drivetrain passedDrivetrain, DoubleSupplier passedForwardSpeed, DoubleSupplier passedRotationSpeed,
Trigger passedSlowMode) {
// Use addRequirements() here to declare subsystem dependencies.
globalDrivetrain = passedDrivetrain;
globalForwardSpeed = passedForwardSpeed;
globalRotationSpeed = passedRotationSpeed;
globalSlowMode = passedSlowMode;

addRequirements(globalDrivetrain);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {}
public void initialize() {
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
globalDrivetrain.setDrivetrainSpeed(globalForwardSpeed.getAsDouble(), globalRotationSpeed.getAsDouble(), globalSlowMode.getAsBoolean());
globalDrivetrain.setDrivetrainSpeed(globalForwardSpeed.getAsDouble(), globalRotationSpeed.getAsDouble(),
globalSlowMode.getAsBoolean());

}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}
public void end(boolean interrupted) {
}

// Returns true when the command should end.
@Override
Expand Down
10 changes: 8 additions & 2 deletions src/main/java/frc/robot/commands/EjectGP.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,22 +6,27 @@

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants;
import frc.robot.Constants.constLED;

import frc.robot.subsystems.Intake;
import frc.robot.subsystems.LED;

public class EjectGP extends Command {
/** Creates a new EjectGP. */

LED globalLED;
Intake globalIntake;

public EjectGP(Intake subIntake) {
public EjectGP(Intake subIntake, LED ejectLED) {
// Use addRequirements() here to declare subsystem dependencies.
this.globalIntake = subIntake;
globalLED = ejectLED;
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
globalIntake.setIntakeVelocity(Constants.constIntake.INTAKE_EJECT_VELOCITY);
globalLED.setLEDs(constLED.LED_EJECTGP);
}

// Called every time the scheduler runs while the command is scheduled.
Expand All @@ -32,6 +37,7 @@ public void execute() {
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {

globalIntake.setIntakeNuetralOutput();
}

Expand Down
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/commands/EjectShooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.LED;
import frc.robot.subsystems.Shooter;
import frc.robot.subsystems.Stager;
import frc.robot.Constants;
Expand All @@ -13,11 +14,13 @@ public class EjectShooter extends Command {
/** Creates a new EjectShooter. */
Stager globalStager;
Shooter globalShooter;
LED globalLED;

public EjectShooter(Stager passedStager, Shooter passedShooter) {
public EjectShooter(Stager passedStager, Shooter passedShooter, LED ejectLED) {
// Use addRequirements() here to declare subsystem dependencies.
globalStager = passedStager;
globalShooter = passedShooter;
globalLED = ejectLED;
}

// Called when the command is initially scheduled.
Expand Down
8 changes: 6 additions & 2 deletions src/main/java/frc/robot/commands/FullHopper.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,21 +5,25 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants.constLED;
import frc.robot.subsystems.Hopper;
import frc.robot.subsystems.LED;

public class FullHopper extends Command {
/** Creates a new FullHopper. */
Hopper subHopper;
LED subLED;

public FullHopper(Hopper subHopper) {
public FullHopper(Hopper subHopper, LED fullLED) {
// Use addRequirements() here to declare subsystem dependencies.
this.subHopper = subHopper;

subLED = fullLED;
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
subLED.setLEDs(constLED.LED_FULL_HOPPER);
}

// Called every time the scheduler runs while the command is scheduled.
Expand Down
7 changes: 6 additions & 1 deletion src/main/java/frc/robot/commands/HasGP.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,21 +7,26 @@
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Shooter;
import frc.robot.subsystems.Stager;
import frc.robot.Constants.constLED;
import frc.robot.subsystems.LED;

public class HasGP extends Command {
/** Creates a new StageGP. */
Stager globalStager;
LED globalLED;
Shooter globalShooter;

public HasGP(Stager passedStager, Shooter passedShooter) {
public HasGP(Stager passedStager, Shooter passedShooter, LED stagerLED) {
// Use addRequirements() here to declare subsystem dependencies.
globalStager = passedStager;
globalShooter = passedShooter;
globalLED = stagerLED;
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
globalLED.setLEDs(constLED.LED_HASGP);
globalShooter.setShooterNuetralOutput();
}

Expand Down
7 changes: 6 additions & 1 deletion src/main/java/frc/robot/commands/IntakeGround.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,23 +7,28 @@
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Stager;
import frc.robot.Constants;
import frc.robot.Constants.constLED;
import frc.robot.subsystems.Intake;
import frc.robot.subsystems.LED;

public class IntakeGround extends Command {
/** Creates a new IntakeGround. */
Intake globalIntake;
Stager globalStager;
LED globalLED;

public IntakeGround(Intake passedIntake, Stager passedStager) {
public IntakeGround(Intake passedIntake, Stager passedStager, LED groundIntakeLED) {
// Use addRequirements() here to declare subsystem dependencies.
globalIntake = passedIntake;
globalStager = passedStager;
globalLED = groundIntakeLED;
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
globalIntake.setIntakeNuetralOutput();
globalLED.setLEDs(constLED.LED_INTAKE_GROUND);
}

// Called every time the scheduler runs while the command is scheduled.
Expand Down
7 changes: 6 additions & 1 deletion src/main/java/frc/robot/commands/PrepShooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,22 +6,27 @@

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants;
import frc.robot.Constants.constLED;
import frc.robot.subsystems.LED;
import frc.robot.subsystems.Shooter;

public class PrepShooter extends Command {
/** Creates a new PrepShooter. */
Shooter globalShooter;
LED globalLED;

public PrepShooter(Shooter passedShooter) {
public PrepShooter(Shooter passedShooter, LED prepLED) {
// Use addRequirements() here to declare subsystem dependencies.
globalShooter = passedShooter;
globalLED = prepLED;
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
globalShooter.setPropelMotorVelocity(Constants.constShooter.PROPEL_MOTOR_VELOCITY);
globalShooter.setSpiralMotorVelocity(Constants.constShooter.SPIRAL_MOTOR_VELOCITY);
globalLED.setLEDs(constLED.LED_PREP_SHOOTING);
}

// Called every time the scheduler runs while the command is scheduled.
Expand Down
7 changes: 6 additions & 1 deletion src/main/java/frc/robot/commands/Shoot.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,18 +6,22 @@

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Stager;
import frc.robot.Constants.constLED;
import frc.robot.subsystems.LED;
import frc.robot.Constants;
import frc.robot.subsystems.Shooter;

public class Shoot extends Command {
/** Creates a new Shoot. */
Stager globalStager;
Shooter globalShooter;
LED globalLED;

public Shoot(Stager passedStager, Shooter passedShooter) {
public Shoot(Stager passedStager, Shooter passedShooter, LED shootLED) {
// Use addRequirements() here to declare subsystem dependencies.
globalStager = passedStager;
globalShooter = passedShooter;
globalLED = shootLED;
}

// Called when the command is initially scheduled.
Expand All @@ -29,6 +33,7 @@ public void initialize() {
&& (globalShooter.getSpiralMotorVelocity() >= Constants.constShooter.SPIRAL_MOTOR_VELOCITY)) {
globalStager.setStagerMotorVelocity(Constants.constStager.STAGER_MOTOR_VELOCITY);
globalStager.setTopStagerMotorVelocity(Constants.constStager.TOP_STAGER_MOTOR_VELOCITY);
globalLED.setLEDs(constLED.LED_SHOOTING);
} else {
globalStager.setStagerMotorVelocityNuetralOutput();
}
Expand Down
9 changes: 7 additions & 2 deletions src/main/java/frc/robot/commands/intakeHopper.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,25 +6,30 @@

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants;
import frc.robot.Constants.constLED;
import frc.robot.subsystems.Hopper;
import frc.robot.subsystems.LED;
import frc.robot.subsystems.Stager;

public class intakeHopper extends Command {

Hopper subHopper;
Stager subStager;
LED subLED;

/** Creates a new intakeHopper. */
public intakeHopper(Hopper subHopper, Stager subStager) {
public intakeHopper(Hopper subHopper, Stager subStager, LED intakeHopperLED) {
// Use addRequirements() here to declare subsystem dependencies.
this.subHopper = subHopper;
this.subStager = subStager;

subLED = intakeHopperLED;
}

// Called when the command is initially scheduled.
@Override
public void initialize() {

subLED.setLEDs(constLED.LED_INTAKE_HOPPER);
subHopper.setOrientationMotorSpeed(Constants.constHopper.HOPPER_ORIENTATION_SPEED);
}

Expand Down
Loading

0 comments on commit 2749723

Please sign in to comment.