Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
35 changes: 20 additions & 15 deletions src/main/java/frc/robot/Schematic.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,10 @@ public class Schematic {
public static final int backRightAbsoluteEncoderCanId;

// shooter subsystem
public static final int shooterBottomMotorCanId;
public static final int shooterTopMotorCanId;
public static final int shooterMiddleMotorCanId;
public static final int shooterTopLeftMotorCanId;
public static final int shooterTopRightMotorCanId;
public static final int shooterBottomLeftMotorCanId;
public static final int shooterBottomRightMotorCanId;
// magic carpet sub-system
public static final int magicCarpetCanId;

Expand Down Expand Up @@ -60,9 +61,10 @@ public class Schematic {
backLeftAbsoluteEncoderCanId = 20;

// Shooter (CAN Ids)
shooterBottomMotorCanId = 0;
shooterTopMotorCanId = 0;
shooterMiddleMotorCanId = 0;
shooterTopLeftMotorCanId = 0;
shooterTopRightMotorCanId = 0;
shooterBottomLeftMotorCanId = 0;
shooterBottomRightMotorCanId = 0;

// Magic Carpet (CAN Ids)
magicCarpetCanId = 0;
Expand Down Expand Up @@ -99,9 +101,10 @@ public class Schematic {
backLeftAbsoluteEncoderCanId = 21;

// Shooter (CAN Ids)
shooterTopMotorCanId = 11;
shooterMiddleMotorCanId = 12;
shooterBottomMotorCanId = 13;
shooterTopLeftMotorCanId = 11;
shooterTopRightMotorCanId = 12;
shooterBottomLeftMotorCanId = 13;
shooterBottomRightMotorCanId = 14;

// Hopper (CAN Ids)
magicCarpetCanId = 15;
Expand Down Expand Up @@ -137,9 +140,10 @@ public class Schematic {
backRightAbsoluteEncoderCanId = 0;

// Shooter (CAN Ids)
shooterBottomMotorCanId = 0;
shooterTopMotorCanId = 0;
shooterMiddleMotorCanId = 0;
shooterTopLeftMotorCanId = 0;
shooterTopRightMotorCanId = 0;
shooterBottomLeftMotorCanId = 0;
shooterBottomRightMotorCanId = 0;

// Magic Carpet (CAN Ids)
magicCarpetCanId = 0;
Expand Down Expand Up @@ -175,9 +179,10 @@ public class Schematic {
backRightAbsoluteEncoderCanId = 0;

// Shooter (CAN Ids)
shooterBottomMotorCanId = 0;
shooterTopMotorCanId = 0;
shooterMiddleMotorCanId = 0;
shooterTopLeftMotorCanId = 0;
shooterTopRightMotorCanId = 0;
shooterBottomLeftMotorCanId = 0;
shooterBottomRightMotorCanId = 0;

// Magic Carpet (CAN Ids)
magicCarpetCanId = 0;
Expand Down
22 changes: 13 additions & 9 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,17 +6,21 @@ public interface ShooterIO {

@AutoLog
class ShooterIOInputs {
public double middleMotorVelocityRadPerSec;
public double middleMotorAppliedVolts;
public double middleMotorCurrentAmps;
public double topLeftMotorVelocityRadPerSec;
public double topLeftMotorAppliedVolts;
public double topLeftMotorCurrentAmps;

public double bottomMotorVelocityRadPerSec;
public double bottomMotorAppliedVolts;
public double bottomMotorCurrentAmps;
public double topRightMotorVelocityRadPerSec;
public double topRightMotorAppliedVolts;
public double topRightMotorCurrentAmps;

public double topMotorVelocityRadPerSec;
public double topMotorAppliedVolts;
public double topMotorCurrentAmps;
public double bottomLeftMotorVelocityRadPerSec;
public double bottomLeftMotorAppliedVolts;
public double bottomLeftMotorCurrentAmps;

public double bottomRightMotorVelocityRadPerSec;
public double bottomRightMotorAppliedVolts;
public double bottomRightMotorCurrentAmps;

public boolean atSetpoint = false;
public double setpointRPM = 0;
Expand Down
142 changes: 84 additions & 58 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIOSparkMax.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,9 @@
package frc.robot.subsystems.shooter;

import static frc.robot.Schematic.shooterBottomMotorCanId;
import static frc.robot.Schematic.shooterMiddleMotorCanId;
import static frc.robot.Schematic.shooterTopMotorCanId;
import static frc.robot.Schematic.shooterBottomLeftMotorCanId;
import static frc.robot.Schematic.shooterBottomRightMotorCanId;
import static frc.robot.Schematic.shooterTopLeftMotorCanId;
import static frc.robot.Schematic.shooterTopRightMotorCanId;
import static frc.robot.subsystems.shooter.ShooterConstants.*;

import com.revrobotics.RelativeEncoder;
Expand All @@ -15,94 +16,119 @@

public class ShooterIOSparkMax implements ShooterIO {

private final SparkMax middleMotor;
private final SparkMax bottomMotor;
private final SparkMax topMotor;
private final RelativeEncoder middleMotorEncoder;
private final RelativeEncoder bottomMotorEncoder;
private final RelativeEncoder topMotorEncoder;
private final SparkMax topLeftMotor;
private final SparkMax topRightMotor;
private final SparkMax bottomLeftMotor;
private final SparkMax bottomRightMotor;
private final RelativeEncoder topLeftMotorEncoder;
private final RelativeEncoder topRightMotorEncoder;
private final RelativeEncoder bottomLeftMotorEncoder;
private final RelativeEncoder bottomRightMotorEncoder;

public ShooterIOSparkMax() {
middleMotor = new SparkMax(shooterMiddleMotorCanId, MotorType.kBrushless);
bottomMotor = new SparkMax(shooterBottomMotorCanId, MotorType.kBrushless);
topMotor = new SparkMax(shooterTopMotorCanId, MotorType.kBrushless);
topLeftMotor = new SparkMax(shooterTopLeftMotorCanId, MotorType.kBrushless);
topRightMotor = new SparkMax(shooterTopRightMotorCanId, MotorType.kBrushless);
bottomLeftMotor = new SparkMax(shooterBottomLeftMotorCanId, MotorType.kBrushless);
bottomRightMotor = new SparkMax(shooterBottomRightMotorCanId, MotorType.kBrushless);

var middleMotorConfig = new SparkMaxConfig();
middleMotorConfig
EncoderConfig enc = new EncoderConfig();
enc.positionConversionFactor(ENCODER_POSITION_CONVERSION);
enc.velocityConversionFactor(ENCODER_VELOCITY_CONVERSION);

var bottomLeftMotorConfig = new SparkMaxConfig();
bottomLeftMotorConfig
.inverted(false)
.idleMode(IDLE_MODE)
.voltageCompensation(VOLTAGE_COMPENSATION)
.smartCurrentLimit(CURRENT_LIMIT);
bottomLeftMotorConfig.apply(enc);

var bottomMotorConfig = new SparkMaxConfig();
bottomMotorConfig
.inverted(true)
var topLeftMotorConfig = new SparkMaxConfig();
topLeftMotorConfig
.inverted(false)
.idleMode(IDLE_MODE)
.voltageCompensation(VOLTAGE_COMPENSATION)
.smartCurrentLimit(CURRENT_LIMIT);
topLeftMotorConfig.follow(bottomLeftMotor.getDeviceId(), false);
topLeftMotorConfig.apply(enc);

var topMotorConfig = new SparkMaxConfig();
topMotorConfig
.inverted(false)
var bottomRightMotorConfig = new SparkMaxConfig();
bottomRightMotorConfig
.inverted(true)
.idleMode(IDLE_MODE)
.voltageCompensation(VOLTAGE_COMPENSATION)
.smartCurrentLimit(CURRENT_LIMIT);
bottomRightMotorConfig.follow(bottomLeftMotor.getDeviceId(), true);
bottomRightMotorConfig.apply(enc);

topMotorConfig.follow(bottomMotor.getDeviceId(), false);
middleMotorConfig.follow(bottomMotor.getDeviceId(), true);

EncoderConfig enc = new EncoderConfig();
enc.positionConversionFactor(ENCODER_POSITION_CONVERSION);
enc.velocityConversionFactor(ENCODER_VELOCITY_CONVERSION);
middleMotorConfig.apply(enc);
bottomMotorConfig.apply(enc);
topMotorConfig.apply(enc);

middleMotor.configure(
middleMotorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
bottomMotor.configure(
bottomMotorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
topMotor.configure(
topMotorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);

middleMotorEncoder = middleMotor.getEncoder();
bottomMotorEncoder = bottomMotor.getEncoder();
topMotorEncoder = topMotor.getEncoder();
var topRightMotorConfig = new SparkMaxConfig();
topRightMotorConfig
.inverted(true)
.idleMode(IDLE_MODE)
.voltageCompensation(VOLTAGE_COMPENSATION)
.smartCurrentLimit(CURRENT_LIMIT);
topRightMotorConfig.follow(bottomLeftMotor.getDeviceId(), true);
topRightMotorConfig.apply(enc);

bottomLeftMotor.configure(
bottomLeftMotorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
topLeftMotor.configure(
topLeftMotorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
bottomRightMotor.configure(
bottomRightMotorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
topRightMotor.configure(
topRightMotorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);

topLeftMotorEncoder = topLeftMotor.getEncoder();
topRightMotorEncoder = topRightMotor.getEncoder();
bottomLeftMotorEncoder = bottomLeftMotor.getEncoder();
bottomRightMotorEncoder = bottomRightMotor.getEncoder();
}

@Override
public void updateInputs(ShooterIOInputs inputs) {
inputs.middleMotorCurrentAmps = middleMotor.getOutputCurrent();
inputs.middleMotorAppliedVolts = middleMotor.getBusVoltage() * middleMotor.getAppliedOutput();
inputs.middleMotorVelocityRadPerSec = middleMotorEncoder.getVelocity();

inputs.bottomMotorCurrentAmps = bottomMotor.getOutputCurrent();
inputs.bottomMotorAppliedVolts = bottomMotor.getBusVoltage() * bottomMotor.getAppliedOutput();
inputs.bottomMotorVelocityRadPerSec = bottomMotorEncoder.getVelocity();

inputs.topMotorCurrentAmps = topMotor.getOutputCurrent();
inputs.topMotorAppliedVolts = topMotor.getBusVoltage() * topMotor.getAppliedOutput();
inputs.topMotorVelocityRadPerSec = topMotorEncoder.getVelocity();
inputs.topLeftMotorCurrentAmps = topLeftMotor.getOutputCurrent();
inputs.topLeftMotorAppliedVolts =
topLeftMotor.getBusVoltage() * topLeftMotor.getAppliedOutput();
inputs.topLeftMotorVelocityRadPerSec = topLeftMotorEncoder.getVelocity();

inputs.topRightMotorCurrentAmps = topRightMotor.getOutputCurrent();
inputs.topRightMotorAppliedVolts =
topRightMotor.getBusVoltage() * topRightMotor.getAppliedOutput();
inputs.topRightMotorVelocityRadPerSec = topRightMotorEncoder.getVelocity();

inputs.bottomLeftMotorCurrentAmps = bottomLeftMotor.getOutputCurrent();
inputs.bottomLeftMotorAppliedVolts =
bottomLeftMotor.getBusVoltage() * bottomLeftMotor.getAppliedOutput();
inputs.bottomLeftMotorVelocityRadPerSec = bottomLeftMotorEncoder.getVelocity();

inputs.bottomRightMotorCurrentAmps = bottomRightMotor.getOutputCurrent();
inputs.bottomRightMotorAppliedVolts =
bottomRightMotor.getBusVoltage() * bottomRightMotor.getAppliedOutput();
inputs.bottomRightMotorVelocityRadPerSec = bottomRightMotorEncoder.getVelocity();

inputs.totalAmps =
inputs.middleMotorCurrentAmps + inputs.bottomMotorCurrentAmps + inputs.topMotorCurrentAmps;
inputs.topLeftMotorCurrentAmps
+ inputs.topRightMotorCurrentAmps
+ inputs.bottomLeftMotorCurrentAmps
+ inputs.bottomRightMotorCurrentAmps;

inputs.shooterWheelVelocityRadPerSec =
inputs.bottomMotorVelocityRadPerSec / SHOOTER_WHEEL_GEAR_RATIO;
inputs.shooterWheelPosition = bottomMotorEncoder.getPosition() / SHOOTER_WHEEL_GEAR_RATIO;
inputs.bottomLeftMotorVelocityRadPerSec / SHOOTER_WHEEL_GEAR_RATIO;
inputs.shooterWheelPosition = bottomLeftMotorEncoder.getPosition() / SHOOTER_WHEEL_GEAR_RATIO;

inputs.setpointRPM = bottomMotor.getClosedLoopController().getSetpoint();
inputs.atSetpoint = bottomMotor.getClosedLoopController().isAtSetpoint();
inputs.setpointRPM = bottomLeftMotor.getClosedLoopController().getSetpoint();
inputs.atSetpoint = bottomLeftMotor.getClosedLoopController().isAtSetpoint();
}

@Override
public void setVoltage(double volts) {
bottomMotor.setVoltage(volts);
bottomLeftMotor.setVoltage(volts);
}

@Override
public void stop() {
bottomMotor.set(0);
bottomLeftMotor.set(0);
}

private double distanceToRPM(double distanceMeters) {
Expand Down
Loading