Skip to content

Commit

Permalink
refactor: minor cleanup (whitespace, annotations, naming, etc.)
Browse files Browse the repository at this point in the history
  • Loading branch information
mimizh2418 committed Feb 13, 2024
1 parent e6fc7ae commit 58ab9fe
Show file tree
Hide file tree
Showing 19 changed files with 76 additions and 73 deletions.
14 changes: 7 additions & 7 deletions src/main/java/org/team1540/robot2024/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -175,10 +175,10 @@ public static class Pivot {

public static class Elevator {
public static final double CHAIN_HEIGHT_METERS = Units.inchesToMeters(28.25);
public static final double ELEVATOR_MINIMUM_HEIGHT = Units.inchesToMeters(6.0);
public static final double MINIMUM_HEIGHT = Units.inchesToMeters(6.0);
public static final double CLIMBING_HOOKS_MINIMUM_HEIGHT = Units.inchesToMeters(12.0);
public static final double ELEVATOR_MAX_HEIGHT = ELEVATOR_MINIMUM_HEIGHT + Units.inchesToMeters(21.0); //TODO: Fix these constants to be more accurate
public static final double CLIMBING_HOOKS_MAX_HEIGHT = CLIMBING_HOOKS_MINIMUM_HEIGHT + ELEVATOR_MAX_HEIGHT - ELEVATOR_MINIMUM_HEIGHT;
public static final double MAX_HEIGHT = MINIMUM_HEIGHT + Units.inchesToMeters(21.0); //TODO: Fix these constants to be more accurate
public static final double CLIMBING_HOOKS_MAX_HEIGHT = CLIMBING_HOOKS_MINIMUM_HEIGHT + MAX_HEIGHT - MINIMUM_HEIGHT;

public static final double GEAR_RATIO = 2.0; //TODO: Get constants right sometime
public static final int LEADER_ID = -1;
Expand All @@ -203,15 +203,15 @@ public enum ElevatorState {
/**
* At max height :D
*/
TOP(ELEVATOR_MAX_HEIGHT),
TOP(MAX_HEIGHT),
/**
* At minimum height :D
*/
BOTTOM(ELEVATOR_MINIMUM_HEIGHT),
BOTTOM(MINIMUM_HEIGHT),
/**
* At height for top of initial climb :D
*/
CLIMB(CHAIN_HEIGHT_METERS + 0.1 - (CLIMBING_HOOKS_MINIMUM_HEIGHT - ELEVATOR_MINIMUM_HEIGHT)), //TODO: Find these values :D
CLIMB(CHAIN_HEIGHT_METERS + 0.1 - (CLIMBING_HOOKS_MINIMUM_HEIGHT - MINIMUM_HEIGHT)), //TODO: Find these values :D
/**
* At height for trap doing :D
*/
Expand All @@ -230,7 +230,7 @@ public enum ElevatorState {
}

public static class Tramp {
public static final int TRAMP_BEAM_BREAK_CHANNEL = 1;
public static final int BEAM_BREAK_CHANNEL = 1;
public static final double GEAR_RATIO = 3.0;
public static final double TRAP_SCORING_TIME_SECONDS = 1.114; //TODO: Find these values :D
public static final int MOTOR_ID = -1; //TODO: Configure this later
Expand Down
20 changes: 7 additions & 13 deletions src/main/java/org/team1540/robot2024/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;
import org.team1540.robot2024.Constants.Elevator.ElevatorState;
import org.team1540.robot2024.commands.FeedForwardCharacterization;
import org.team1540.robot2024.commands.DriveWithSpeakerTargetingCommand;
Expand Down Expand Up @@ -72,8 +71,6 @@ public class RobotContainer {

public final PhoenixTimeSyncSignalRefresher odometrySignalRefresher = new PhoenixTimeSyncSignalRefresher(SwerveConfig.CAN_BUS);

// TODO: testing dashboard inputs, remove for comp

/**
* The container for the robot. Contains subsystems, IO devices, and commands.
*/
Expand Down Expand Up @@ -102,16 +99,14 @@ public RobotContainer() {
() -> 0.0, // TODO: ACTUALLY GET ELEVATOR HEIGHT HERE
new VisionPoseAcceptor(drivetrain::getChassisSpeeds, () -> 0.0)); // TODO: ACTUALLY GET ELEVATOR VELOCITY HERE

PathPlannerLogging.setLogCurrentPoseCallback((pose) -> {
Logger.recordOutput("PathPlanner/Position", pose);
});
PathPlannerLogging.setLogTargetPoseCallback((pose) -> {
Logger.recordOutput("PathPlanner/TargetPosition", pose);
});
PathPlannerLogging.setLogCurrentPoseCallback(
(pose) -> Logger.recordOutput("PathPlanner/Position", pose));
PathPlannerLogging.setLogTargetPoseCallback(
(pose) -> Logger.recordOutput("PathPlanner/TargetPosition", pose));
PathPlannerLogging.setLogActivePathCallback((path) -> {
if(path.hashCode() != currentPathHash){
if(path.hashCode() != currentPathHash) {
currentPathHash = path.hashCode();
currentPathTrajectory = path.size() > 0 ? TrajectoryGenerator.generateTrajectory(path, Constants.Drivetrain.trajectoryConfig) : new Trajectory();
currentPathTrajectory = !path.isEmpty() ? TrajectoryGenerator.generateTrajectory(path, Constants.Drivetrain.trajectoryConfig) : new Trajectory();
Logger.recordOutput("PathPlanner/PathHash", currentPathHash);
Logger.recordOutput("PathPlanner/ActivePath", currentPathTrajectory);
}
Expand Down Expand Up @@ -149,11 +144,10 @@ public RobotContainer() {
PathPlannerLogging.setLogActivePathCallback((path) -> {
if(path.hashCode() != currentPathHash){
currentPathHash = path.hashCode();
currentPathTrajectory = path.size() > 0 ? TrajectoryGenerator.generateTrajectory(path, Constants.Drivetrain.trajectoryConfig) : new Trajectory();
currentPathTrajectory = !path.isEmpty() ? TrajectoryGenerator.generateTrajectory(path, Constants.Drivetrain.trajectoryConfig) : new Trajectory();
Logger.recordOutput("PathPlanner/PathHash", currentPathHash);
Logger.recordOutput("PathPlanner/ActivePath", currentPathTrajectory);
}

});
break;
default:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ public TrampShoot(Tramp tramp) {
),
Commands.startEnd(
() -> tramp.setPercent(0.5), //TODO: tune this
() -> tramp.stop(),
tramp::stop,
tramp
)
);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
import org.team1540.robot2024.util.PathHelper;

public class AmpLanePABCSprint extends AutoCommand {

public AmpLanePABCSprint(Drivetrain drivetrain, Shooter shooter, Indexer indexer){
super("AmpLanePABCSprint");

Expand All @@ -17,6 +16,7 @@ public AmpLanePABCSprint(Drivetrain drivetrain, Shooter shooter, Indexer indexer
PathHelper.fromChoreoPath("AmpLanePABCSprint.3"),
PathHelper.fromChoreoPath("AmpLanePABCSprint.4")
);

addCommands(
// new ShootSequence(shooter, indexer),
getPath(0).getCommand(drivetrain),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,14 @@
public class SourceLanePHGFSprint extends AutoCommand {
public SourceLanePHGFSprint(Drivetrain drivetrain){
super("SourceLanePHGFSprint");

addPath(
PathHelper.fromChoreoPath("SourceLanePHGFSprint.1", true, true),
PathHelper.fromChoreoPath("SourceLanePHGFSprint.2"),
PathHelper.fromChoreoPath("SourceLanePHGFSprint.3"),
PathHelper.fromChoreoPath("SourceLanePHGFSprint.4")
);

addCommands(
getPath(0).getCommand(drivetrain),
new PrintCommand("Past 1"),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,11 @@ public ElevatorManualCommand(Elevator elevator, CommandXboxController copilot) {

@Override
public void execute() {
elevator.setElevatorPosition(elevator.getSetpoint() + Constants.Elevator.CRUISE_VELOCITY_MPS * Constants.LOOP_PERIOD_SECS * (copilot.getRightTriggerAxis() - copilot.getLeftTriggerAxis()));
elevator.setElevatorPosition(
elevator.getSetpoint()
+ Constants.Elevator.CRUISE_VELOCITY_MPS
* Constants.LOOP_PERIOD_SECS
* (copilot.getRightTriggerAxis() - copilot.getLeftTriggerAxis()));
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,11 +16,8 @@ public IntakeCommand(Indexer indexer, Tramp tramp) {

@Override
public void execute() {
if (indexer.isNoteStaged() || tramp.isNoteStaged()) {
indexer.stopIntake();
} else {
indexer.setIntakePercent(0.5);
}
if (indexer.isNoteStaged() || tramp.isNoteStaged()) indexer.stopIntake();
else indexer.setIntakePercent(0.5);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,14 @@ public TuneShooterCommand(Shooter shooter) {
addRequirements(shooter);
}

@Override
public void execute() {
shooter.setFlywheelSpeeds(leftFlywheelSetpoint.get(), rightFlywheelSetpoint.get());
shooter.setPivotPosition(Rotation2d.fromDegrees(angleSetpoint.get()));
}

public void end() {
@Override
public void end(boolean interrupted) {
shooter.stopFlywheels();
shooter.stopPivot();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,8 +86,8 @@ public void periodic() {
for (Module module : modules) module.stop();

// Log empty setpoint states when disabled
Logger.recordOutput("SwerveStates/Setpoints", new SwerveModuleState[]{});
Logger.recordOutput("SwerveStates/SetpointsOptimized", new SwerveModuleState[]{});
Logger.recordOutput("SwerveStates/Setpoints");
Logger.recordOutput("SwerveStates/SetpointsOptimized");
}

// Calculate module deltas
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,5 @@ class GyroIOInputs {
public double time = 0.0;
}

default void updateInputs(GyroIOInputs inputs) {
}
default void updateInputs(GyroIOInputs inputs) {}
}
Original file line number Diff line number Diff line change
Expand Up @@ -21,30 +21,25 @@ class ModuleIOInputs {
/**
* Updates the set of loggable inputs.
*/
default void updateInputs(ModuleIOInputs inputs) {
}
default void updateInputs(ModuleIOInputs inputs) {}

/**
* Run the drive motor at the specified voltage.
*/
default void setDriveVoltage(double volts) {
}
default void setDriveVoltage(double volts) {}

/**
* Run the turn motor at the specified voltage.
*/
default void setTurnVoltage(double volts) {
}
default void setTurnVoltage(double volts) {}

/**
* Enable or disable brake mode on the drive motor.
*/
default void setDriveBrakeMode(boolean enable) {
}
default void setDriveBrakeMode(boolean enable) {}

/**
* Enable or disable brake mode on the turn motor.
*/
default void setTurnBrakeMode(boolean enable) {
}
default void setTurnBrakeMode(boolean enable) {}
}
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,11 @@ public class Elevator extends SubsystemBase {
private final AverageFilter positionFilter = new AverageFilter(10);
private double setpointMeters;


public Elevator(ElevatorIO elevatorIO) {
this.io = elevatorIO;
}

// periodic
@Override
public void periodic() {
io.updateInputs(inputs);
Logger.processInputs("Elevator", inputs);
Expand All @@ -31,7 +30,7 @@ public void periodic() {
}

public void setElevatorPosition(double positionMeters) {
positionMeters = MathUtil.clamp(positionMeters, Constants.Elevator.ELEVATOR_MINIMUM_HEIGHT, Constants.Elevator.ELEVATOR_MAX_HEIGHT);
positionMeters = MathUtil.clamp(positionMeters, Constants.Elevator.MINIMUM_HEIGHT, Constants.Elevator.MAX_HEIGHT);
setpointMeters = positionMeters;
io.setSetpointMeters(setpointMeters);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,10 @@ public class ElevatorIOSim implements ElevatorIO {
new ElevatorSim(
DCMotor.getFalcon500Foc(2),
GEAR_RATIO, SIM_CARRIAGE_MASS_KG,
SPROCKET_RADIUS_M, ELEVATOR_MINIMUM_HEIGHT,
ELEVATOR_MAX_HEIGHT,
SPROCKET_RADIUS_M, MINIMUM_HEIGHT,
MAX_HEIGHT,
true,
ELEVATOR_MINIMUM_HEIGHT);
MINIMUM_HEIGHT);
private double elevatorAppliedVolts = 0.0;
private final ProfiledPIDController controller =
new ProfiledPIDController(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,11 @@ public class Indexer extends SubsystemBase {
private final LoggedTunableNumber kI = new LoggedTunableNumber("Indexer/kI", FEEDER_KI);
private final LoggedTunableNumber kD = new LoggedTunableNumber("Indexer/kD", FEEDER_KD);


public Indexer(IndexerIO io) {
this.io = io;
}

@Override
public void periodic() {
io.updateInputs(inputs);
Logger.processInputs("Indexer", inputs);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,9 @@ public class IndexerIOSim implements IndexerIO {
@Override
public void updateInputs(IndexerIOInputs inputs) {
if (isClosedLoop) {
feederVoltage = MathUtil.clamp(feederSimPID.calculate(feederSim.getAngularVelocityRPM() / 60, feederSetpointRPS), -12.0, 12.0);
feederVoltage = MathUtil.clamp(
feederSimPID.calculate(feederSim.getAngularVelocityRPM() / 60, feederSetpointRPS),
-12.0, 12.0);
}
intakeSim.setInputVoltage(intakeVoltage);
feederSim.setInputVoltage(feederVoltage);
Expand All @@ -50,12 +52,13 @@ public void configureFeederPID(double p, double i, double d) {
feederSimPID.setPID(p, i, d);
}

@Override
public void setFeederVoltage(double volts) {
isClosedLoop = false;
feederVoltage = MathUtil.clamp(volts, -12.0, 12.0);
}


@Override
public void setFeederVelocity(double velocity) {
isClosedLoop = true;
feederSimPID.reset();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,9 @@ public class ShooterPivotIOSim implements ShooterPivotIO {
MIN_ANGLE.getRadians());

private final ProfiledPIDController controller =
new ProfiledPIDController(SIM_KP, SIM_KI, SIM_KD, new TrapezoidProfile.Constraints(CRUISE_VELOCITY_RPS, MAX_ACCEL_RPS2));
new ProfiledPIDController(
SIM_KP, SIM_KI, SIM_KD,
new TrapezoidProfile.Constraints(CRUISE_VELOCITY_RPS, MAX_ACCEL_RPS2));
private final ArmFeedforward feedforward = new ArmFeedforward(SIM_KS, SIM_KG, SIM_KV);

private boolean isClosedLoop;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,12 @@
import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import edu.wpi.first.wpilibj.DigitalInput;
import org.team1540.robot2024.Constants.Tramp;

import static org.team1540.robot2024.Constants.Tramp.*;

public class TrampIOSparkMax implements TrampIO {
private final DigitalInput beamBreak = new DigitalInput(Tramp.TRAMP_BEAM_BREAK_CHANNEL);
//TODO: Potentially change name :D
private final CANSparkMax motor = new CANSparkMax(Tramp.MOTOR_ID, MotorType.kBrushless);
private final DigitalInput beamBreak = new DigitalInput(BEAM_BREAK_CHANNEL);
private final CANSparkMax motor = new CANSparkMax(MOTOR_ID, MotorType.kBrushless);
private final RelativeEncoder motorEncoder = motor.getEncoder();

public TrampIOSparkMax() {
Expand All @@ -24,6 +24,7 @@ public void setVoltage(double volts) {
motor.setVoltage(volts);
}

@Override
public void updateInputs(TrampIOInputs inputs) {
inputs.breamBreakTripped = !(beamBreak.get()); //I think returns false when broken... Returns true when broken now.
inputs.velocityRPM = motorEncoder.getVelocity();
Expand Down
Loading

0 comments on commit 58ab9fe

Please sign in to comment.