Skip to content

Commit

Permalink
Merge pull request #15 from Team1810Robotics/cleaning
Browse files Browse the repository at this point in the history
fix me fixes
  • Loading branch information
gaultpay000 committed Feb 29, 2024
2 parents ca8a42c + ad4994c commit ddb7592
Show file tree
Hide file tree
Showing 11 changed files with 52 additions and 87 deletions.
17 changes: 2 additions & 15 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
package frc.robot;

import com.pathplanner.lib.util.PIDConstants;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.apriltag.AprilTagFields;
import edu.wpi.first.math.util.Units;
import swervelib.math.SwerveMath;

Expand Down Expand Up @@ -102,18 +100,7 @@ public static final class IOConstants {
public static final double DEADBAND = 0.3;
}

public static final class VisionConstants {
public static final double CAMERA_HEIGHT = 0.0;
public static final double APRILTAG_RED_SHOOTER_HEIGHT = 0.0;
public static final double CAMERA_PITCH = 0.0;
public static final String CAMERA_NAME = "photonvision";

public static final AprilTagFieldLayout APRIL_TAG_FIELD_LAYOUT =
AprilTagFields.k2024Crescendo.loadAprilTagLayoutField();
}

public static final class TrapConstants {
// FIXME: should say ID instead of PORT because it's a CAN ID
public static final int VICTOR_MOTOR_PORT = 0;
public static final int VICTOR_MOTOR_ID = 0;
}
}
}
5 changes: 2 additions & 3 deletions src/main/java/frc/robot/commands/ArmCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,8 @@

public class ArmCommand extends Command {

// FIXME: both member variables should be private and final (if possible)
private ArmSubsystem armSubsystem;
private double armSetpoint;
private final ArmSubsystem armSubsystem;
private final double armSetpoint;

public ArmCommand(ArmSubsystem armSubsystem, double armSetpoint) {
this.armSetpoint = armSetpoint;
Expand Down
30 changes: 12 additions & 18 deletions src/main/java/frc/robot/commands/ClimbCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,8 @@

public class ClimbCommand extends Command {

// FIXME: both member variables should be private and final (if possible)
private ClimbSubsystem climbSubsystem;
private double climbSpeed;
private final ClimbSubsystem climbSubsystem;
private final double climbSpeed;

public ClimbCommand(ClimbSubsystem climbSubsystem, double climbSpeed) {
this.climbSpeed = climbSpeed;
Expand All @@ -18,25 +17,20 @@ public ClimbCommand(ClimbSubsystem climbSubsystem, double climbSpeed) {

@Override
public void execute() {
climbSubsystem.setMotorSpeed(climbSpeed);
climbSubsystem.setSpeed(climbSpeed);
boolean rightBottom = climbSubsystem.getRightBottomlimit();
boolean leftBottom = climbSubsystem.getRightBottomlimit();
boolean rightTop = climbSubsystem.getRightBottomlimit();
boolean leftTop = climbSubsystem.getRightBottomlimit();

// FIXME: This is an infinate loop in an infinite loop, which is not good.
while (climbSpeed != 0) {

// FIXME: these are assignments, not comparisons. Use == instead of =
if (rightBottom = true) {
climbSubsystem.setMotorSpeed(0);
} else if (leftBottom = true) {
climbSubsystem.setMotorSpeed(0);
} else if (rightTop = true) {
climbSubsystem.setMotorSpeed(0);
} else if (leftTop = true) {
climbSubsystem.setMotorSpeed(0);

if (rightBottom == true && climbSpeed != 0) {
climbSubsystem.setSpeed(0);
} else if (leftBottom == true && climbSpeed != 0) {
climbSubsystem.setSpeed(0);
} else if (rightTop == true && climbSpeed != 0) {
climbSubsystem.setSpeed(0);
} else if (leftTop == true && climbSpeed != 0) {
climbSubsystem.setSpeed(0);
}
}
}
}
11 changes: 4 additions & 7 deletions src/main/java/frc/robot/commands/IntakeCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,8 @@

public class IntakeCommand extends Command {

// FIXME: both member variables should be private and final (if possible)
private IntakeSubsystem intakeSubsystem;
private double intakeSpeed;
private final IntakeSubsystem intakeSubsystem;
private final double intakeSpeed;

public IntakeCommand(IntakeSubsystem intakeSubsystem, double intakeSpeed) {
this.intakeSpeed = intakeSpeed;
Expand All @@ -20,16 +19,14 @@ public void execute() {
intakeSubsystem.setSpeed(intakeSpeed);
boolean beam = intakeSubsystem.getBeamBreak();

// FIXME: this is an assignment, not a comparison. Use == instead of =
if (beam = true) {
if (beam == true) {
intakeSubsystem.setSpeed(0);
}
}

@Override
public void end(boolean interrupted) {
// FIXME: use stop() instead of setSpeed(0) because it's more clear
intakeSubsystem.setSpeed(0);
intakeSubsystem.stop();
}

/* @Override
Expand Down
8 changes: 3 additions & 5 deletions src/main/java/frc/robot/commands/ManualCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,8 @@

public class ManualCommand extends Command {

// FIXME: both member variables should be private and final (if possible)
private ArmSubsystem armSubsystem;
private double armSpeed;
private final ArmSubsystem armSubsystem;
private final double armSpeed;

public ManualCommand(ArmSubsystem armSubsystem, double armSpeed) {
this.armSpeed = armSpeed;
Expand All @@ -23,7 +22,6 @@ public void execute() {

@Override
public void end(boolean interrupted) {
// FIXME: use stop() instead of setSpeed(0) because it's more clear
armSubsystem.setSpeed(0);
armSubsystem.stop();
}
}
11 changes: 5 additions & 6 deletions src/main/java/frc/robot/commands/ShooterCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,9 @@
import frc.robot.subsystems.ShooterSubsystem;

public class ShooterCommand extends Command {
// FIXME: both member variables should be private and final (if possible)
private ShooterSubsystem shooterSubsystem;
private double shooterSpeed;

private final ShooterSubsystem shooterSubsystem;
private final double shooterSpeed;

public ShooterCommand(ShooterSubsystem shooterSubsystem, double shooterSpeed) {
this.shooterSpeed = shooterSpeed;
Expand All @@ -17,12 +17,11 @@ public ShooterCommand(ShooterSubsystem shooterSubsystem, double shooterSpeed) {

@Override
public void execute() {
shooterSubsystem.setBothSpeed(shooterSpeed);
shooterSubsystem.setSpeed(shooterSpeed);
}

@Override
public void end(boolean interupted) {
// FIXME: should use stop() instead of setBothSpeed(0) because it's more clear
shooterSubsystem.setBothSpeed(0);
shooterSubsystem.stop();
}
}
12 changes: 5 additions & 7 deletions src/main/java/frc/robot/commands/TrapCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,24 +5,22 @@

public class TrapCommand extends Command {

// FIXME: both member variables should be private and final (if possible)
TrapSubsystem trapsubsystem;
private final TrapSubsystem trapsubsystem;

// FIXME: this name is not descriptive, would recommend using something like "trapSpeed"
double trap;
private final double trapSpeed;

public TrapCommand(TrapSubsystem trapSubsystem, double trap) {
this.trap = trap;
this.trapSpeed = trap;
this.trapsubsystem = trapSubsystem;

addRequirements(trapSubsystem);
}

public void execute() {
trapsubsystem.motorOn(trap);
trapsubsystem.setSpeed(trapSpeed);
}

public void end() {
trapsubsystem.motorOff();
trapsubsystem.stop();
}
}
8 changes: 3 additions & 5 deletions src/main/java/frc/robot/subsystems/ClimbSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,9 @@

public class ClimbSubsystem extends SubsystemBase {

// FIXME: all should be private
CANSparkMax leftMotor =
private CANSparkMax leftMotor =
new CANSparkMax(Constants.ClimbConstants.LEFT_MOTOR_ID, MotorType.kBrushless);
CANSparkMax rightMotor =
private CANSparkMax rightMotor =
new CANSparkMax(Constants.ClimbConstants.RIGHT_MOTOR_ID, MotorType.kBrushless);

DigitalInput leftBottom = new DigitalInput(Constants.ClimbConstants.LEFT_BOTTOM_LS);
Expand All @@ -20,8 +19,7 @@ public class ClimbSubsystem extends SubsystemBase {
DigitalInput leftTop = new DigitalInput(Constants.ClimbConstants.LEFT_TOP_LS);
DigitalInput rightTop = new DigitalInput(Constants.ClimbConstants.RIGHT_TOP_LS);

// FIXME: rename to setSpeed() to keep consistent with other subsystems
public void setMotorSpeed(double motorSpeed) {
public void setSpeed(double motorSpeed) {
leftMotor.set(motorSpeed);
rightMotor.set(motorSpeed);
}
Expand Down
8 changes: 2 additions & 6 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,8 @@

public class IntakeSubsystem extends SubsystemBase {

// FIXME: should be private
CANSparkMax motor = new CANSparkMax(Constants.IntakeConstants.MOTOR_ID, MotorType.kBrushless);
DigitalInput beam = new DigitalInput(Constants.IntakeConstants.BEAM_BREAK_PORT);
private CANSparkMax motor = new CANSparkMax(Constants.IntakeConstants.MOTOR_ID, MotorType.kBrushless);
private DigitalInput beam = new DigitalInput(Constants.IntakeConstants.BEAM_BREAK_PORT);

public void setSpeed(double motorSpeed) {
motor.set(motorSpeed);
Expand All @@ -23,7 +22,4 @@ public void stop() {
public boolean getBeamBreak() {
return beam.get();
}

// FIXME: doesn't need to be defined if its empty
public IntakeSubsystem() {}
}
9 changes: 6 additions & 3 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,12 @@ public void setTopSpeed(double topSpeed) {
topMotor.set(topSpeed);
}

// FIXME: doesn't set both speeds?
// FIXME: rename to setSpeed() to keep consistent with other subsystems
public void setBothSpeed(double motorSpeed) {
public void setSpeed(double motorSpeed) {
topMotor.set(motorSpeed);
}

public void stop() {
topMotor.set(0);
bottomMotor.set(0);
}
}
20 changes: 8 additions & 12 deletions src/main/java/frc/robot/subsystems/TrapSubsystem.java
Original file line number Diff line number Diff line change
@@ -1,24 +1,20 @@
package frc.robot.subsystems;

import edu.wpi.first.wpilibj.motorcontrol.VictorSP;
import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.can.VictorSPX;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

public class TrapSubsystem extends SubsystemBase {

/**
* FIXME: should be private, should be a {@link com.ctre.phoenix.motorcontrol.can.VictorSPX} not
* a {@link edu.wpi.first.wpilibj.motorcontrol.VictorSP}
*/
VictorSP victor = new VictorSP(Constants.TrapConstants.VICTOR_MOTOR_PORT);
VictorSPX victor = new VictorSPX(Constants.TrapConstants.VICTOR_MOTOR_ID);

// FIXME: rename to setSpeed() to keep consistent with other subsystems
public void motorOn(double victorSpeed) {
victor.set(victorSpeed);

public void setSpeed(double victorSpeed) {
victor.set(ControlMode.PercentOutput, victorSpeed);
}

// FIXME: remane to stop() to keep consistent with other subsystems
public void motorOff() {
victor.set(0);
public void stop() {
victor.set(ControlMode.PercentOutput, 0);
}
}

0 comments on commit ddb7592

Please sign in to comment.