Skip to content

Commit

Permalink
removed LEDs from drive and readded the things i accidentally removed🦟™️
Browse files Browse the repository at this point in the history
  • Loading branch information
BrodyKarr committed Nov 23, 2024
1 parent 228a040 commit 99c75a4
Show file tree
Hide file tree
Showing 3 changed files with 19 additions and 34 deletions.
27 changes: 8 additions & 19 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
@@ -1,17 +1,11 @@
// 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;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.commands.Drive;
import frc.robot.commands.EjectGP;
import frc.robot.commands.EjectShooter;
import frc.robot.commands.HasGP;
import frc.robot.commands.IntakeGround;
import frc.robot.commands.PrepShooter;
import frc.robot.commands.Shoot;
Expand All @@ -26,16 +20,15 @@
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 LED subLED = new LED();
private final Drive com_Drive = new Drive(subDrivetrain, m_driverController.axis_RightX,
m_driverController.axis_LeftY, m_driverController.btn_LeftBumper, subLED);
private final IntakeGround com_IntakeGround = new IntakeGround(subIntake, subStager, subLED);;
m_driverController.axis_LeftY, m_driverController.btn_LeftBumper);
private final IntakeGround com_IntakeGround = new IntakeGround(subIntake, subStager, subLED);
private final PrepShooter com_PrepShooter = new PrepShooter(subShooter, subLED);
private final HasGP com_StageGP = new HasGP(subStager, 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);
Expand All @@ -48,15 +41,11 @@ public RobotContainer() {
}

private void configureBindings() {
m_driverController.btn_B.whileTrue(com_IntakeGround);
m_driverController.btn_LeftBumper.whileTrue(new intakeHopper(subHopper, subStager, subLED));
m_driverController.btn_X.whileTrue(com_PrepShooter);
m_driverController.btn_A.whileTrue(com_StageGP);
m_driverController.btn_LeftTrigger.whileTrue(com_IntakeHopper);
m_driverController.btn_RightBumper.whileTrue(new EjectGP(subIntake, subHopper, subLED));

m_driverController.btn_Y.onTrue(com_Shoot);
m_driverController.btn_RightBumper.whileTrue(com_EjectShooter);
m_driverController.btn_LeftTrigger.whileTrue(com_IntakeGround);
m_driverController.btn_A.whileTrue(com_PrepShooter);
m_driverController.btn_B.whileTrue(com_IntakeHopper);
m_driverController.btn_LeftBumper.whileTrue(com_EjectShooter);
m_driverController.btn_RightTrigger.onTrue(com_Shoot);

}

Expand Down
11 changes: 5 additions & 6 deletions src/main/java/frc/robot/commands/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,28 +5,27 @@
package frc.robot.commands;

import java.util.function.DoubleSupplier;
import frc.robot.subsystems.LED;

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

import frc.robot.subsystems.Drivetrain;

public class Drive extends Command {
/** Creates a new Drive. */
LED globalLED;

Drivetrain globalDrivetrain;
DoubleSupplier globalForwardSpeed;
DoubleSupplier globalRotationSpeed;
Trigger globalSlowMode;

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

Expand All @@ -40,7 +39,7 @@ public void initialize() {
public void execute() {
globalDrivetrain.setDrivetrainSpeed(globalForwardSpeed.getAsDouble(), globalRotationSpeed.getAsDouble(),
globalSlowMode.getAsBoolean());
globalLED.setLEDs(constLED.LED_DRIVE);

}

// Called once the command ends or is interrupted.
Expand Down
15 changes: 6 additions & 9 deletions src/main/java/frc/robot/commands/Shoot.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,16 +27,13 @@ public Shoot(Stager passedStager, Shooter passedShooter, LED shootLED) {
// Called when the command is initially scheduled.
@Override
public void initialize() {
if ((globalShooter.getPropelMotorVelocity() >= 0.6) && (globalShooter.getSpiralMotorVelocity() >= 0.8)) {
globalStager.setStagerMotorVelocity(0.3);
if ((globalShooter.getPropelMotorVelocity() >= Constants.constShooter.PROPEL_MOTOR_VELOCITY)
&& (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);
if ((globalShooter.getPropelMotorVelocity() >= Constants.constShooter.PROPEL_MOTOR_VELOCITY)
&& (globalShooter.getSpiralMotorVelocity() >= Constants.constShooter.SPIRAL_MOTOR_VELOCITY)) {
globalStager.setStagerMotorVelocity(Constants.constStager.STAGER_MOTOR_VELOCITY);
globalStager.setTopStagerMotorVelocity(Constants.constStager.TOP_STAGER_MOTOR_VELOCITY);
} else {
globalStager.setStagerMotorVelocityNuetralOutput();
}
} else {
globalStager.setStagerMotorVelocityNuetralOutput();
}
}

Expand Down

0 comments on commit 99c75a4

Please sign in to comment.