Skip to content

Commit

Permalink
Code review w/ Oscar
Browse files Browse the repository at this point in the history
  • Loading branch information
ozziexyz committed Oct 16, 2024
1 parent 78831cb commit 497ae2a
Show file tree
Hide file tree
Showing 6 changed files with 14 additions and 24 deletions.
Empty file modified gradlew
100644 → 100755
Empty file.
15 changes: 5 additions & 10 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,15 +29,11 @@
import frc.robot.subsystems.drive.ModuleIO;
import frc.robot.subsystems.drive.ModuleIOSim;
import frc.robot.subsystems.drive.ModuleIOSparkMax;
import frc.robot.subsystems.pivot.Pivot;
import frc.robot.subsystems.pivot.PivotIOSim;
import frc.robot.subsystems.flywheel.Flywheel;
import frc.robot.subsystems.flywheel.FlywheelIO;
import frc.robot.subsystems.flywheel.FlywheelIOSim;
import frc.robot.subsystems.flywheel.FlywheelIOSparkMax;
import frc.robot.subsystems.intake.Intake;
import frc.robot.subsystems.intake.IntakeIOReal;
import frc.robot.subsystems.intake.IntakeIOSim;
import frc.robot.subsystems.pivot.Pivot;
import frc.robot.subsystems.pivot.PivotIOSim;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;

Expand Down Expand Up @@ -74,7 +70,6 @@ public RobotContainer() {
new ModuleIOSparkMax(3));
// change perchance
pivot = Pivot.initialize(new PivotIOSim());
flywheel = new Flywheel(new FlywheelIOSparkMax());
Intake.initialize(new IntakeIOReal());
// drive = new Drive(
// new GyroIOPigeon2(),
Expand All @@ -95,7 +90,6 @@ public RobotContainer() {
new ModuleIOSim(),
new ModuleIOSim());
pivot = Pivot.initialize(new PivotIOSim());
flywheel = new Flywheel(new FlywheelIOSim());
Intake.initialize(new IntakeIOSim());

break;
Expand Down Expand Up @@ -166,10 +160,11 @@ private void configureButtonBindings() {

controller
.y()
.whileTrue(Commands.runEnd(() -> pivot.setGoal(Math.PI / 4), () -> pivot.setGoal(0), pivot));
.whileTrue(
Commands.runEnd(() -> pivot.setGoal(Math.PI / 4), () -> pivot.setGoal(0), pivot));
}

/**
/**
* Use this to pass the autonomous command to the main {@link Robot} class.
*
* @return the command to run in autonomous
Expand Down
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/subsystems/intake/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -57,11 +57,11 @@ public Command intake() {
// setIntakeSpeed(0)).onlyIf(() -> noteNotInIntake() == true).onlyWhile(() -> noteNotInIntake()
// == true));
}
/*
public Command spike() {
return startEnd(() -> testamps = 150, () -> testamps = 0);
}
*/
/*
public Command spike() {
return startEnd(() -> testamps = 150, () -> testamps = 0);
}
*/
public Command reverse() {
return startEnd(() -> setIntakeSpeed(-1), () -> setIntakeSpeed(0));
}
Expand Down
4 changes: 1 addition & 3 deletions src/main/java/frc/robot/subsystems/pivot/Pivot.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,11 +22,9 @@ private Pivot(PivotIO io) {
case REAL:
case REPLAY:
ffModel = new SimpleMotorFeedforward(0.0, 0.0);
io.configurePID(1.0, 0.0, 0.0);
break;
case SIM:
ffModel = new SimpleMotorFeedforward(0.0, 0.0);
io.configurePID(1.0, 0.0, 0.0);
break;
default:
ffModel = new SimpleMotorFeedforward(0.0, 0.0);
Expand All @@ -39,7 +37,7 @@ public static Pivot getInstance() {
}

public static Pivot initialize(PivotIO io) {
if (Pivot.pivotInstance == null) {
if (Pivot.pivotInstance == null) {
pivotInstance = new Pivot(io);
}
return pivotInstance;
Expand Down
3 changes: 0 additions & 3 deletions src/main/java/frc/robot/subsystems/pivot/PivotIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,4 @@ public default void setAngle(double positionRad) {}

/** Stop in open loop. */
public default void stop() {}

/** Set velocity PID constants. */
public default void configurePID(double kP, double kI, double kD) {}
}
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/subsystems/pivot/PivotIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@

public class PivotIOSim implements PivotIO {
private SingleJointedArmSim sim =
new SingleJointedArmSim(DCMotor.getNEO(1), 1.5, 0.004, 0.2, 0, Math.PI, false, 0);
new SingleJointedArmSim(DCMotor.getNEO(1), 1.5, 0.004, 0.2, 0, Math.PI, false, 0);
private PIDController pid = new PIDController(0.2, 0.0, 0.0);

private boolean closedLoop = true;
Expand All @@ -20,7 +20,7 @@ public void updateInputs(PivotIOInputs inputs) {

appliedVolts = MathUtil.clamp(pid.calculate(sim.getAngleRads()) + ffVolts, -12.0, 12.0);
sim.setInputVoltage(appliedVolts);

inputs.positionRad = sim.getAngleRads();
inputs.appliedVolts = appliedVolts;
inputs.velocityRadPerSec = sim.getVelocityRadPerSec();
Expand All @@ -30,7 +30,7 @@ public void updateInputs(PivotIOInputs inputs) {
public void setAngle(double targetAngle) {
pid.setSetpoint(targetAngle);
}

@Override
public void setVoltage(double volts) {
sim.setInputVoltage(volts);
Expand Down

0 comments on commit 497ae2a

Please sign in to comment.