Skip to content

Commit

Permalink
Add Prototype shooter test base
Browse files Browse the repository at this point in the history
  • Loading branch information
suryatho committed Jan 20, 2024
1 parent 7b5e646 commit 98a55c5
Show file tree
Hide file tree
Showing 10 changed files with 514 additions and 60 deletions.
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,9 @@
*/
public final class Constants {
public static final int loopPeriodMs = 20;
private static RobotType robotType = RobotType.SIMBOT;
public static final boolean tuningMode = false;
public static final boolean characterizationMode = false;
private static RobotType robotType = RobotType.RAINBOWT;
public static final boolean tuningMode = true;
public static final boolean characterizationMode = true;

private static boolean invalidRobotAlertSent = false;

Expand Down
47 changes: 26 additions & 21 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,10 @@
import frc.robot.commands.FeedForwardCharacterization;
import frc.robot.subsystems.drive.*;
import frc.robot.subsystems.kitbotshooter.*;
import frc.robot.subsystems.shooter.Shooter;
import frc.robot.subsystems.shooter.ShooterIO;
import frc.robot.subsystems.shooter.ShooterIOSim;
import frc.robot.subsystems.shooter.ShooterIOSparkMax;
import frc.robot.util.AllianceFlipUtil;
import frc.robot.util.trajectory.ChoreoTrajectoryReader;
import frc.robot.util.trajectory.Trajectory;
Expand All @@ -34,7 +38,6 @@
import java.util.Optional;
import java.util.function.Function;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;

/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
Expand All @@ -48,15 +51,13 @@ public class RobotContainer {

// Subsystems
private final Drive drive;
private final KitbotShooter shooter;
private final Shooter shooter;

// Controller
private final CommandXboxController controller = new CommandXboxController(0);

// Dashboard inputs
private final LoggedDashboardChooser<Command> autoChooser;
private final LoggedDashboardNumber flywheelSpeedInput =
new LoggedDashboardNumber("Flywheel Speed", 1500.0);

/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
Expand All @@ -72,7 +73,7 @@ public RobotContainer() {
new ModuleIOSparkMax(DriveConstants.moduleConfigs[1]),
new ModuleIOSparkMax(DriveConstants.moduleConfigs[2]),
new ModuleIOSparkMax(DriveConstants.moduleConfigs[3]));
shooter = new KitbotShooter(new KitbotFlywheelIO() {}, new KitbotFeederIO() {});
shooter = new Shooter(new ShooterIOSparkMax());
}
}
}
Expand All @@ -85,7 +86,7 @@ public RobotContainer() {
new ModuleIOSim(DriveConstants.moduleConfigs[1]),
new ModuleIOSim(DriveConstants.moduleConfigs[2]),
new ModuleIOSim(DriveConstants.moduleConfigs[3]));
shooter = new KitbotShooter(new KitbotFlywheelIOSim(), new KitbotFeederIOSim());
shooter = new Shooter(new ShooterIOSim());
}
default -> {
// Replayed robot, disable IO implementations
Expand All @@ -96,7 +97,7 @@ public RobotContainer() {
new ModuleIO() {},
new ModuleIO() {},
new ModuleIO() {});
shooter = new KitbotShooter(new KitbotFlywheelIO() {}, new KitbotFeederIO() {});
shooter = new Shooter(new ShooterIO() {});
}
}

Expand All @@ -108,13 +109,21 @@ public RobotContainer() {
new FeedForwardCharacterization(
drive, drive::runCharacterizationVolts, drive::getCharacterizationVelocity));
autoChooser.addOption(
"Flywheel FF Characterization",
Commands.sequence(
Commands.runOnce(
() -> shooter.setCurrentMode(KitbotShooter.Mode.CHARACTERIZING), shooter),
new FeedForwardCharacterization(
shooter, shooter::runFlywheelVolts, shooter::getFlywheelVelocityRadPerSec),
Commands.runOnce(() -> shooter.setCurrentMode(null))));
"Left Flywheels FF Characterization",
new FeedForwardCharacterization(
shooter,
shooter::runLeftCharacterizationVolts,
shooter::getLeftCharacterizationVelocity)
.beforeStarting(() -> shooter.setCharacterizing(true))
.finallyDo(() -> shooter.setCharacterizing(false)));
autoChooser.addOption(
"Right Flywheels FF Characterization",
new FeedForwardCharacterization(
shooter,
shooter::runRightCharacterizationVolts,
shooter::getRightCharacterizationVelocity)
.beforeStarting(() -> shooter.setCharacterizing(true))
.finallyDo(() -> shooter.setCharacterizing(false)));

// Testing autos paths
Function<File, Optional<Command>> trajectoryCommandFactory =
Expand Down Expand Up @@ -143,7 +152,8 @@ public RobotContainer() {
}

// Configure the button bindings
configureButtonBindings();
// TODO: uncomment (done to disable drive movement)
// configureButtonBindings();
}

/**
Expand Down Expand Up @@ -175,17 +185,12 @@ private void configureButtonBindings() {
drive)
.ignoringDisable(true));
controller
.button(8)
.y()
.onTrue(
Commands.runOnce(
() ->
RobotState.getInstance()
.resetPose(new Pose2d(), drive.getWheelPositions(), drive.getGyroYaw())));
controller
.a()
.whileTrue(
Commands.run(() -> shooter.runFlywheelVelocity(flywheelSpeedInput.get()), shooter))
.whileFalse(Commands.run(() -> shooter.runFlywheelVelocity(0.0), shooter));
}

/**
Expand Down
1 change: 0 additions & 1 deletion src/main/java/frc/robot/subsystems/drive/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@

package frc.robot.subsystems.drive;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.*;
Expand Down
67 changes: 32 additions & 35 deletions src/main/java/frc/robot/subsystems/drive/ModuleIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
import static frc.robot.subsystems.drive.DriveConstants.*;

import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel;
import com.revrobotics.CANSparkLowLevel.PeriodicFrame;
import com.revrobotics.CANSparkMax;
import com.revrobotics.REVLibError;
Expand All @@ -34,8 +33,8 @@ public class ModuleIOSparkMax implements ModuleIO {
// Every 100 times through periodic (2 secs) we reset relative encoder to absolute encoder
private static final int reSeedIterations = 100;

private final CANSparkMax driveSparkMax;
private final CANSparkMax turnSparkMax;
private final CANSparkMax driveMotor;
private final CANSparkMax turnMotor;
private final RelativeEncoder driveEncoder;
private final RelativeEncoder turnRelativeEncoder;
private final AnalogInput turnAbsoluteEncoder;
Expand All @@ -56,24 +55,24 @@ public class ModuleIOSparkMax implements ModuleIO {

public ModuleIOSparkMax(ModuleConfig config) {
// Init motor & encoder objects
driveSparkMax = new CANSparkMax(config.driveID(), CANSparkLowLevel.MotorType.kBrushless);
turnSparkMax = new CANSparkMax(config.turnID(), CANSparkLowLevel.MotorType.kBrushless);
driveMotor = new CANSparkMax(config.driveID(), CANSparkMax.MotorType.kBrushless);
turnMotor = new CANSparkMax(config.turnID(), CANSparkMax.MotorType.kBrushless);
turnAbsoluteEncoder = new AnalogInput(config.absoluteEncoderChannel());
absoluteEncoderOffset = config.absoluteEncoderOffset();
driveEncoder = driveSparkMax.getEncoder();
turnRelativeEncoder = turnSparkMax.getEncoder();
driveEncoder = driveMotor.getEncoder();
turnRelativeEncoder = turnMotor.getEncoder();

driveSparkMax.restoreFactoryDefaults();
turnSparkMax.restoreFactoryDefaults();
driveSparkMax.setCANTimeout(250);
turnSparkMax.setCANTimeout(250);
driveMotor.restoreFactoryDefaults();
turnMotor.restoreFactoryDefaults();
driveMotor.setCANTimeout(250);
turnMotor.setCANTimeout(250);

for (int i = 0; i < 4; i++) {
turnSparkMax.setInverted(config.turnMotorInverted());
driveSparkMax.setSmartCurrentLimit(40);
turnSparkMax.setSmartCurrentLimit(30);
driveSparkMax.enableVoltageCompensation(12.0);
turnSparkMax.enableVoltageCompensation(12.0);
turnMotor.setInverted(config.turnMotorInverted());
driveMotor.setSmartCurrentLimit(40);
turnMotor.setSmartCurrentLimit(30);
driveMotor.enableVoltageCompensation(12.0);
turnMotor.enableVoltageCompensation(12.0);

driveEncoder.setPosition(0.0);
driveEncoder.setMeasurementPeriod(10);
Expand All @@ -90,16 +89,14 @@ public ModuleIOSparkMax(ModuleConfig config) {
turnRelativeEncoder.setVelocityConversionFactor(
2 * Math.PI / (60.0 * moduleConstants.turnReduction()));

driveSparkMax.setCANTimeout(0);
turnSparkMax.setCANTimeout(0);
driveMotor.setCANTimeout(0);
turnMotor.setCANTimeout(0);

driveSparkMax.setPeriodicFramePeriod(
PeriodicFrame.kStatus2, (int) (1000.0 / odometryFrequency));
turnSparkMax.setPeriodicFramePeriod(
PeriodicFrame.kStatus2, (int) (1000.0 / odometryFrequency));
driveMotor.setPeriodicFramePeriod(PeriodicFrame.kStatus2, (int) (1000.0 / odometryFrequency));
turnMotor.setPeriodicFramePeriod(PeriodicFrame.kStatus2, (int) (1000.0 / odometryFrequency));

if (driveSparkMax.burnFlash().equals(REVLibError.kOk)
&& turnSparkMax.burnFlash().equals(REVLibError.kOk)) break;
if (driveMotor.burnFlash().equals(REVLibError.kOk)
&& turnMotor.burnFlash().equals(REVLibError.kOk)) break;
}

absoluteEncoderValue =
Expand Down Expand Up @@ -127,14 +124,14 @@ public ModuleIOSparkMax(ModuleConfig config) {
public void updateInputs(ModuleIOInputs inputs) {
inputs.drivePositionRad = driveEncoder.getPosition();
inputs.driveVelocityRadPerSec = driveEncoder.getVelocity();
inputs.driveAppliedVolts = driveSparkMax.getAppliedOutput() * driveSparkMax.getBusVoltage();
inputs.driveCurrentAmps = new double[] {driveSparkMax.getOutputCurrent()};
inputs.driveAppliedVolts = driveMotor.getAppliedOutput() * driveMotor.getBusVoltage();
inputs.driveCurrentAmps = new double[] {driveMotor.getOutputCurrent()};

inputs.turnAbsolutePosition = absoluteEncoderValue.get();
inputs.turnPosition = Rotation2d.fromRadians(turnRelativeEncoder.getPosition());
inputs.turnVelocityRadPerSec = turnRelativeEncoder.getVelocity();
inputs.turnAppliedVolts = turnSparkMax.getAppliedOutput() * turnSparkMax.getBusVoltage();
inputs.turnCurrentAmps = new double[] {turnSparkMax.getOutputCurrent()};
inputs.turnAppliedVolts = turnMotor.getAppliedOutput() * turnMotor.getBusVoltage();
inputs.turnCurrentAmps = new double[] {turnMotor.getOutputCurrent()};

inputs.odometryDrivePositionsMeters =
drivePositionQueue.stream().mapToDouble(rads -> rads * wheelRadius).toArray();
Expand All @@ -158,15 +155,15 @@ public void periodic() {

// Run closed loop turn control
if (angleSetpoint != null) {
turnSparkMax.setVoltage(
turnMotor.setVoltage(
turnFeedback.calculate(
absoluteEncoderValue.get().getRadians(), angleSetpoint.getRadians()));
// Run closed loop drive control
if (speedSetpoint != null) {
// Scale velocity based on turn error
double adjustSpeedSetpoint = speedSetpoint * Math.cos(turnFeedback.getPositionError());
double velocityRadPerSec = adjustSpeedSetpoint / wheelRadius;
driveSparkMax.setVoltage(
driveMotor.setVoltage(
driveFeedforward.calculate(velocityRadPerSec)
+ driveFeedback.calculate(driveEncoder.getVelocity(), velocityRadPerSec));
}
Expand All @@ -184,23 +181,23 @@ public void runCharacterization(double volts) {
angleSetpoint = new Rotation2d();
speedSetpoint = null;

driveSparkMax.setVoltage(volts);
driveMotor.setVoltage(volts);
}

@Override
public void setDriveBrakeMode(boolean enable) {
driveSparkMax.setIdleMode(enable ? IdleMode.kBrake : IdleMode.kCoast);
driveMotor.setIdleMode(enable ? IdleMode.kBrake : IdleMode.kCoast);
}

@Override
public void setTurnBrakeMode(boolean enable) {
turnSparkMax.setIdleMode(enable ? IdleMode.kBrake : IdleMode.kCoast);
turnMotor.setIdleMode(enable ? IdleMode.kBrake : IdleMode.kCoast);
}

@Override
public void stop() {
driveSparkMax.setVoltage(0.0);
turnSparkMax.setVoltage(0.0);
driveMotor.setVoltage(0.0);
turnMotor.setVoltage(0.0);

speedSetpoint = null;
angleSetpoint = null;
Expand Down
105 changes: 105 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,105 @@
package frc.robot.subsystems.shooter;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.util.LoggedTunableNumber;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;

public class Shooter extends SubsystemBase {
private static LoggedTunableNumber feedVolts = new LoggedTunableNumber("Shooter/FeedVolts", 6.0);
private static LoggedTunableNumber kP = new LoggedTunableNumber("Shooter/kP");
private static LoggedTunableNumber kI = new LoggedTunableNumber("Shooter/kI");
private static LoggedTunableNumber kD = new LoggedTunableNumber("Shooter/kD");
private static LoggedTunableNumber kS = new LoggedTunableNumber("Shooter/kS");
private static LoggedTunableNumber kV = new LoggedTunableNumber("Shooter/kV");
private static LoggedTunableNumber kA = new LoggedTunableNumber("Shooter/kA");
private static LoggedTunableNumber shooterTolerance =
new LoggedTunableNumber("Shooter/ToleranceRPM");

private final LoggedDashboardNumber leftSpeedRpm =
new LoggedDashboardNumber("Left Speed RPM", 1500.0);
private final LoggedDashboardNumber rightSpeedRpm =
new LoggedDashboardNumber("Right Speed RPM", 1500.0);

static {
kP.initDefault(ShooterConstants.kP);
kI.initDefault(ShooterConstants.kI);
kD.initDefault(ShooterConstants.kD);
kS.initDefault(ShooterConstants.kS);
kV.initDefault(ShooterConstants.kV);
kA.initDefault(ShooterConstants.kA);
shooterTolerance.initDefault(ShooterConstants.shooterToleranceRPM);
}

private ShooterIO shooterIO;
private ShooterIOInputsAutoLogged shooterInputs = new ShooterIOInputsAutoLogged();
private double feederSetpointVolts = 0.0;

private boolean characterizing = false;

public Shooter(ShooterIO io) {
shooterIO = io;
shooterIO.setPID(kP.get(), kI.get(), kD.get());
shooterIO.setFF(kS.get(), kV.get(), kA.get());
}

@Override
public void periodic() {
// check controllers
if (kP.hasChanged(hashCode()) || kI.hasChanged(hashCode()) || kD.hasChanged(hashCode()))
shooterIO.setPID(kP.get(), kI.get(), kD.get());
if (kS.hasChanged(hashCode()) || kV.hasChanged(hashCode()) || kA.hasChanged(hashCode()))
shooterIO.setFF(kS.get(), kV.get(), kA.get());

shooterIO.updateInputs(shooterInputs);
Logger.processInputs("Shooter", shooterInputs);

if (DriverStation.isDisabled()) {
shooterIO.stop();
} else {
if (!characterizing) {
shooterIO.setRPM(leftSpeedRpm.get(), rightSpeedRpm.get());
if (leftSpeedRpm.get() > 0 && rightSpeedRpm.get() > 0 && atSetpoint()) {
feederSetpointVolts = feedVolts.get();
} else {
feederSetpointVolts = 0;
}
shooterIO.setFeederVoltage(feederSetpointVolts);
}
}

Logger.recordOutput("Shooter/LeftRPM", shooterInputs.leftFlywheelVelocityRPM);
Logger.recordOutput("Shooter/RightRPM", shooterInputs.rightFlywheelVelocityRPM);
Logger.recordOutput("Shooter/FeederRPM", shooterInputs.feederVelocityRPM);
}

public void runLeftCharacterizationVolts(double volts) {
shooterIO.setLeftCharacterizationVoltage(volts);
}

public void runRightCharacterizationVolts(double volts) {
shooterIO.setRightCharacterizationVoltage(volts);
}

public double getLeftCharacterizationVelocity() {
return shooterInputs.leftFlywheelVelocityRPM;
}

public void setCharacterizing(boolean characterizing) {
this.characterizing = characterizing;
}

public double getRightCharacterizationVelocity() {
return shooterInputs.rightFlywheelVelocityRPM;
}

@AutoLogOutput(key = "Shooter/AtSetpoint")
public boolean atSetpoint() {
return Math.abs(shooterInputs.leftFlywheelVelocityRPM - leftSpeedRpm.get())
<= shooterTolerance.get()
&& Math.abs(shooterInputs.rightFlywheelVelocityRPM - rightSpeedRpm.get())
<= shooterTolerance.get();
}
}
Loading

0 comments on commit 98a55c5

Please sign in to comment.