Skip to content
This repository has been archived by the owner on Jan 2, 2025. It is now read-only.

Commit

Permalink
Refactor FIles
Browse files Browse the repository at this point in the history
- Combined lifter subsystems into one
- Renamed shooter command & subsystems to Flywheel
  • Loading branch information
Iooob committed Jan 2, 2025
1 parent f1a0235 commit f96d9c5
Show file tree
Hide file tree
Showing 7 changed files with 41 additions and 138 deletions.
28 changes: 13 additions & 15 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,9 +26,8 @@
import frc.robot.commands.ArmCommand;
import frc.robot.commands.BalanceCommand;
import frc.robot.commands.DefaultDrive;
import frc.robot.commands.LeftLifterCommand;
import frc.robot.commands.RightLifterCommand;
import frc.robot.commands.ShooterCommand;
import frc.robot.commands.FlywheelCommand;
import frc.robot.commands.LifterCommand;
import frc.robot.commands.StraightCommand;
import frc.robot.commands.UltrasonicShooterCommand;
import frc.robot.commands.auto.AimAmpCommand;
Expand All @@ -38,9 +37,8 @@
import frc.robot.subsystems.CameraSubsystem;
import frc.robot.subsystems.DriveSubsystem;
import frc.robot.subsystems.DriverCameraSubsystem;
import frc.robot.subsystems.LeftLifterSubsystem;
import frc.robot.subsystems.RightLifterSubsystem;
import frc.robot.subsystems.ShooterSubsystem;
import frc.robot.subsystems.FlywheelSubsystem;
import frc.robot.subsystems.LifterSubsystem;
import frc.robot.subsystems.UltrasonicSubsystem;

/**
Expand Down Expand Up @@ -68,9 +66,11 @@ public class RobotContainer {
private final DriveSubsystem m_driveSubsystem = new DriveSubsystem();
private final CameraSubsystem m_cameraSubsystem = new CameraSubsystem(m_driveSubsystem);
private final ArmSubsystem m_armSubsystem = new ArmSubsystem(m_shooterState);
private final ShooterSubsystem m_shooterSubsytem = new ShooterSubsystem();
private final LeftLifterSubsystem m_leftLifterSubsystem = new LeftLifterSubsystem();
private final RightLifterSubsystem m_rightLifterSubsystem = new RightLifterSubsystem();
private final FlywheelSubsystem m_shooterSubsytem = new FlywheelSubsystem();
private final LifterSubsystem m_leftLifterSubsystem =
new LifterSubsystem(Constants.CANConstants.MOTORLIFTERLEFTID);
private final LifterSubsystem m_rightLifterSubsystem =
new LifterSubsystem(Constants.CANConstants.MOTORLIFTERRIGHTID);
private final DriverCameraSubsystem m_DriverCameraSubsystem = new DriverCameraSubsystem();
// The robots commands are defined here..
// private final ExampleCommand m_autoCommand = new ExampleCommand(m_exampleSubsystem);
Expand All @@ -85,12 +85,10 @@ public class RobotContainer {
new UltrasonicShooterCommand(m_ultrasonicShooterSubsystem, m_shooterState);
private final ArmCommand m_armCommand =
new ArmCommand(m_armSubsystem, m_shooterState, this::GetFlightStickY);
private final ShooterCommand m_shooterCommand =
new ShooterCommand(m_shooterSubsytem, m_shooterState);
private final LeftLifterCommand m_LeftLifterCommand =
new LeftLifterCommand(m_leftLifterSubsystem);
private final RightLifterCommand m_RightLifterCommand =
new RightLifterCommand(m_rightLifterSubsystem);
private final FlywheelCommand m_shooterCommand =
new FlywheelCommand(m_shooterSubsytem, m_shooterState);
private final LifterCommand m_LeftLifterCommand = new LifterCommand(m_leftLifterSubsystem);
private final LifterCommand m_RightLifterCommand = new LifterCommand(m_rightLifterSubsystem);

// these commands are used by autonomous only
private final AimAmpCommand m_AimAmpCommand = new AimAmpCommand(m_armSubsystem, m_shooterState);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,12 @@

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.ShooterState;
import frc.robot.subsystems.ShooterSubsystem;
import frc.robot.subsystems.FlywheelSubsystem;

/** A Shooter Command that uses an example subsystem. */
public class ShooterCommand extends Command {
public class FlywheelCommand extends Command {
@SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"})
private final ShooterSubsystem m_shooterSubsystem;
private final FlywheelSubsystem m_shooterSubsystem;

private final ShooterState m_shooterState;

Expand All @@ -20,7 +20,7 @@ public class ShooterCommand extends Command {
*
* @param subsystem The subsystem used by this command.
*/
public ShooterCommand(ShooterSubsystem s_subsystem, ShooterState shooterState) {
public FlywheelCommand(FlywheelSubsystem s_subsystem, ShooterState shooterState) {
m_shooterSubsystem = s_subsystem;
m_shooterState = shooterState;
// Use addRequirements() here to declare subsystem dependencies.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,19 +5,19 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.LeftLifterSubsystem;
import frc.robot.subsystems.LifterSubsystem;

/** Lifter Command using the Lifter Subsystem. */
public class LeftLifterCommand extends Command {
public class LifterCommand extends Command {
@SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"})
private final LeftLifterSubsystem m_lifterSubsystem;
private final LifterSubsystem m_lifterSubsystem;

/**
* Creates a new LifterDownCommand.
*
* @param subsystem The subsystem used by this command.
*/
public LeftLifterCommand(LeftLifterSubsystem l_subsystem) {
public LifterCommand(LifterSubsystem l_subsystem) {
m_lifterSubsystem = l_subsystem;
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(l_subsystem);
Expand All @@ -30,13 +30,13 @@ public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
m_lifterSubsystem.activateLeft();
m_lifterSubsystem.activate();
}

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

// Returns true when the command should end.
Expand Down
47 changes: 0 additions & 47 deletions src/main/java/frc/robot/commands/RightLifterCommand.java

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.Constants.CANConstants;

public class ShooterSubsystem extends SubsystemBase {
public class FlywheelSubsystem extends SubsystemBase {
private final CANSparkMax m_ShooterMotorMain;
private final CANSparkMax m_ShooterMotorSecondary;
private final SparkPIDController m_ShooterMainPIDController;
Expand Down Expand Up @@ -52,7 +52,7 @@ public class ShooterSubsystem extends SubsystemBase {
private final int k_CurrentLimit = 80;

/** Creates a new ShooterSubsystem. */
public ShooterSubsystem() {
public FlywheelSubsystem() {
// create the shooter motors
m_ShooterMotorMain =
new CANSparkMax(CANConstants.MOTORSHOOTERLEFTID, CANSparkMax.MotorType.kBrushless);
Expand Down
50 changes: 0 additions & 50 deletions src/main/java/frc/robot/subsystems/LeftLifterSubsystem.java

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -7,34 +7,36 @@
import com.revrobotics.CANSparkMax;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import frc.robot.Constants.CANConstants;

public class RightLifterSubsystem extends SubsystemBase {
private final CANSparkMax m_right; // Motor for right
public class LifterSubsystem extends SubsystemBase {
private final CANSparkMax m_motor; // Motor for
private double kCurrentSpeed = Constants.LIFTERSPEED;
private int motorID;

/** Creates a new LifterSubsystem. */
public RightLifterSubsystem() {
m_right = new CANSparkMax(CANConstants.MOTORLIFTERRIGHTID, CANSparkMax.MotorType.kBrushless);
m_right.setIdleMode(CANSparkMax.IdleMode.kBrake);
m_right.setSmartCurrentLimit(60);
m_right.burnFlash();
public LifterSubsystem(int motor_ID) {
motorID = motor_ID;
m_motor = new CANSparkMax(motorID, CANSparkMax.MotorType.kBrushless);
m_motor.setIdleMode(CANSparkMax.IdleMode.kBrake);
m_motor.setInverted(false);
m_motor.setSmartCurrentLimit(60);
m_motor.burnFlash();
}

public void rightMove(double speed) {
m_right.set(speed);
public void move(double speed) {
m_motor.set(speed);
}

public void activateRight() {
rightMove(kCurrentSpeed);
public void activate() {
move(kCurrentSpeed);
}

public void changeDirection() {
kCurrentSpeed = -kCurrentSpeed;
}

public void stopRight() {
m_right.set(0);
public void stop() {
m_motor.set(0);
}

@Override
Expand Down

0 comments on commit f96d9c5

Please sign in to comment.