Skip to content

Commit

Permalink
Merge branch 'shooter' into pivot
Browse files Browse the repository at this point in the history
  • Loading branch information
ozziexyz committed Oct 22, 2024
2 parents 92bf9fe + 88a16be commit c2f207f
Show file tree
Hide file tree
Showing 6 changed files with 99 additions and 4 deletions.
4 changes: 1 addition & 3 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,6 @@ public class Robot extends LoggedRobot {
*/
@Override
public void robotInit() {
// Record metadata
/*
Logger.recordMetadata("ProjectName", BuildConstants.MAVEN_NAME);
Logger.recordMetadata("BuildDate", BuildConstants.BUILD_DATE);
Logger.recordMetadata("GitSHA", BuildConstants.GIT_SHA);
Expand All @@ -56,7 +54,7 @@ public void robotInit() {
default:
Logger.recordMetadata("GitDirty", "Unknown");
break;
} */
}

// Set up data receivers & replay source
switch (Constants.currentMode) {
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/pivot/PivotIOReal.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ public PivotIOReal() {

pivotMotor.setCANTimeout(250);
pivotMotor.enableVoltageCompensation(12);
pivotMotor.setSmartCurrentLimit(80);
pivotMotor.setSmartCurrentLimit(30);
pivotMotor.setIdleMode(IdleMode.kBrake);

pivotMotor.burnFlash();
Expand Down
31 changes: 31 additions & 0 deletions src/main/java/frc/robot/subsystems/shooter/Shooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
package frc.robot.subsystems.shooter;

import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class Shooter extends SubsystemBase {
private ShooterIO io;
private ShooterIOInputsAutoLogged inputs = new ShooterIOInputsAutoLogged();

private static Shooter instance;

public static Shooter getInstance() {
return instance;
}

public static Shooter initialize(ShooterIO io) {
if (instance == null) {
instance = new Shooter(io);
}
return instance;
}

private Shooter(ShooterIO shooterIO) {
io = shooterIO;
io.updateInputs(inputs);
}

@Override
public void periodic() {
io.updateInputs(inputs);
}
}
18 changes: 18 additions & 0 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
package frc.robot.subsystems.shooter;

import frc.robot.subsystems.shooter.ShooterIO.ShooterIOInputs;
import org.littletonrobotics.junction.AutoLog;

public interface ShooterIO {
@AutoLog
public static class ShooterIOInputs {
public double leftMotorVelocity = 0.0;
public double rightMotorVelocity = 0.0;
}

public default void spinForwards() {}

public default void spinBackwards() {}

public default void updateInputs(ShooterIOInputs inputs) {}
}
45 changes: 45 additions & 0 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIOReal.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
package frc.robot.subsystems.shooter;

import com.revrobotics.CANSparkFlex;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.RelativeEncoder;

public class ShooterIOReal implements ShooterIO {
private CANSparkFlex leftShooterMotor =
new CANSparkFlex(0, MotorType.kBrushless); // Can IDs not accurate
private CANSparkFlex rightShooterMotor =
new CANSparkFlex(1, MotorType.kBrushless); // Can IDs not accurate
private RelativeEncoder leftShooterEncoder = leftShooterMotor.getEncoder();
private RelativeEncoder rightShooterEncoder = rightShooterMotor.getEncoder();

public ShooterIOReal() {
rightShooterMotor.follow(leftShooterMotor, true);

rightShooterMotor.burnFlash();
leftShooterMotor.burnFlash();
}

@Override
public void spinForwards() {
leftShooterMotor.set(1.0);
}

@Override
public void spinBackwards() {
leftShooterMotor.set(-1.0);
}

public double getLeftvelocity() {
return leftShooterEncoder.getVelocity();
}

public double getRightvelocity() {
return rightShooterEncoder.getVelocity();
}

@Override
public void updateInputs(ShooterIOInputs inputs) {
inputs.leftMotorVelocity = getLeftvelocity();
inputs.rightMotorVelocity = getRightvelocity();
}
}
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
package frc.robot.subsystems.shooter;

public class ShooterIOSim {}

0 comments on commit c2f207f

Please sign in to comment.