Skip to content

Commit

Permalink
initial tuned values for shooter
Browse files Browse the repository at this point in the history
  • Loading branch information
GearBoxFox committed Feb 3, 2024
1 parent 9a8a1ba commit b8f7b5d
Show file tree
Hide file tree
Showing 6 changed files with 81 additions and 45 deletions.
7 changes: 4 additions & 3 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -111,14 +111,15 @@ private ShooterConstants() {
public static final int BOTTOM_RIGHT_ID = 16;
public static final int KICKER_ID = 17;

public static final double SHOOTER_KP = 0.0;
public static final double SHOOTER_KP = 0.000061;
public static final double SHOOTER_KI = 0.0;
public static final double SHOOTER_KD = 0.0;
public static final double SHOOTER_KD = 0.005;
public static final double SHOOTER_KF = 0.000152;

public static final boolean TOP_LEFT_INVERTED = false;
public static final boolean TOP_RIGHT_INVERTED = true;
public static final boolean BOTTOM_LEFT_INVERTED = true;
public static final boolean BOTTOM_RIGHT_INVERTED = true;
public static final boolean BOTTOM_RIGHT_INVERTED = false;
public static final boolean KICKER_INVERTED = true;
}
}
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@

package frc.robot;

import com.gos.lib.properties.PropertyManager;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import org.littletonrobotics.junction.LogFileUtil;
Expand All @@ -38,6 +39,8 @@ public class Robot extends LoggedRobot {
*/
@Override
public void robotInit() {
// Clear dead properties
PropertyManager.purgeExtraKeys();
// Record metadata
Logger.recordMetadata("ProjectName", BuildConstants.MAVEN_NAME);
Logger.recordMetadata("BuildDate", BuildConstants.BUILD_DATE);
Expand All @@ -59,6 +62,7 @@ public void robotInit() {

// Set up data receivers & replay source
switch (Constants.currentMode) {
case PROTO_SHOOTER:
case REAL:
// Running on a real robot, log to a USB stick ("/U/logs")
Logger.addDataReceiver(new WPILOGWriter());
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -157,9 +157,9 @@ private void configureButtonBindings() {
m_driveSubsystem)
.ignoringDisable(true));

controller.a().whileTrue(m_shooter.setShooterPowerFactory(leftPower.get(), rightPower.get()))
.whileFalse(m_shooter.setShooterPowerFactory(0.0, 0.0));
controller.b().whileTrue(Commands.run(m_shooter::runShooterVelocity))
// controller.a().whileTrue(m_shooter.setShooterPowerFactory(leftPower.get(), rightPower.get()))
// .whileFalse(m_shooter.setShooterPowerFactory(0.0, 0.0));
controller.a().whileTrue(Commands.run(m_shooter::runShooterVelocity))
.whileFalse(m_shooter.setShooterPowerFactory(0.0, 0.0));
}

Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,10 @@
public interface ShooterIO {
@AutoLog
class ShooterIOInputs {
public double tlVelocityRads = 0.0;
public double trVelocityRads = 0.0;
public double blVelocityRads = 0.0;
public double brVelocityRads = 0.0;
public double tlVelocityRots = 0.0;
public double trVelocityRots = 0.0;
public double blVelocityRots = 0.0;
public double brVelocityRots = 0.0;
public double tlAppliedVolts = 0.0;
public double trAppliedVolts = 0.0;
public double blAppliedVolts = 0.0;
Expand Down
93 changes: 62 additions & 31 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIOPrototype.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
import com.gos.lib.rev.properties.pid.RevPidPropertyBuilder;
import com.revrobotics.*;
import frc.robot.Constants.ShooterConstants;
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;

public class ShooterIOPrototype implements ShooterIO {
private final CANSparkFlex m_topLeftMotor;
Expand All @@ -13,10 +12,16 @@ public class ShooterIOPrototype implements ShooterIO {
private final CANSparkFlex m_bottomRightMotor;
private final CANSparkMax m_kickerMotor;

private final SparkPIDController m_leftPid;
private final PidProperty m_leftPidProperty;
private final SparkPIDController m_rightPid;
private final PidProperty m_rightPidProperty;
private final SparkPIDController m_topLeftPid;
private final PidProperty m_topLeftPidProperty;
private final SparkPIDController m_topRightPid;
private final PidProperty m_topRightPidProperty;

private final SparkPIDController m_bottomLeftPid;
private final PidProperty m_bottomLeftPidProperty;
private final SparkPIDController m_bottomRightPid;
private final PidProperty m_bottomRightPidProperty;


public ShooterIOPrototype() {
m_topLeftMotor = new CANSparkFlex(ShooterConstants.TOP_LEFT_ID, CANSparkLowLevel.MotorType.kBrushless);
Expand All @@ -25,6 +30,11 @@ public ShooterIOPrototype() {
m_bottomRightMotor = new CANSparkFlex(ShooterConstants.BOTTOM_RIGHT_ID, CANSparkLowLevel.MotorType.kBrushless);
m_kickerMotor = new CANSparkMax(ShooterConstants.KICKER_ID, CANSparkLowLevel.MotorType.kBrushless);

m_topLeftMotor.restoreFactoryDefaults();
m_topRightMotor.restoreFactoryDefaults();
m_bottomLeftMotor.restoreFactoryDefaults();
m_bottomRightMotor.restoreFactoryDefaults();

m_topLeftMotor.setInverted(ShooterConstants.TOP_LEFT_INVERTED);
m_topRightMotor.setInverted(ShooterConstants.TOP_RIGHT_INVERTED);
m_bottomLeftMotor.setInverted(ShooterConstants.BOTTOM_LEFT_INVERTED);
Expand All @@ -36,23 +46,40 @@ public ShooterIOPrototype() {
m_bottomLeftMotor.enableVoltageCompensation(12);
m_bottomRightMotor.enableVoltageCompensation(12);

m_bottomLeftMotor.follow(m_topLeftMotor);
m_bottomRightMotor.follow(m_topRightMotor);

m_leftPid = m_topLeftMotor.getPIDController();
m_leftPidProperty = new RevPidPropertyBuilder("Shooter/Left Shooter", false, m_leftPid, 0)
.addP(ShooterConstants.SHOOTER_KP)
.addI(ShooterConstants.SHOOTER_KI)
.addD(ShooterConstants.SHOOTER_KD)
.addFF(0.0)
.build();
m_rightPid = m_topLeftMotor.getPIDController();
m_rightPidProperty = new RevPidPropertyBuilder("Shooter/Left Shooter", false, m_leftPid, 0)
.addP(ShooterConstants.SHOOTER_KP)
.addI(ShooterConstants.SHOOTER_KI)
.addD(ShooterConstants.SHOOTER_KD)
.addFF(0.0)
.build();
// m_bottomLeftMotor.follow(m_topLeftMotor, ShooterConstants.BOTTOM_LEFT_INVERTED);
// m_bottomRightMotor.follow(m_topRightMotor, ShooterConstants.BOTTOM_RIGHT_INVERTED);

m_topLeftPid = m_topLeftMotor.getPIDController();
m_topLeftPidProperty = new RevPidPropertyBuilder("Shooter/Top Left Shooter", false, m_topLeftPid, 0)
.addP(ShooterConstants.SHOOTER_KP)
.addI(ShooterConstants.SHOOTER_KI)
.addD(ShooterConstants.SHOOTER_KD)
.addFF(ShooterConstants.SHOOTER_KF)
.build();

m_topRightPid = m_topRightMotor.getPIDController();
m_topRightPidProperty = new RevPidPropertyBuilder("Shooter/Top Right Shooter", false, m_topRightPid, 0)
.addP(ShooterConstants.SHOOTER_KP)
.addI(ShooterConstants.SHOOTER_KI)
.addD(ShooterConstants.SHOOTER_KD)
.addFF(ShooterConstants.SHOOTER_KF)
.build();

m_bottomLeftPid = m_bottomLeftMotor.getPIDController();
m_bottomLeftPidProperty = new RevPidPropertyBuilder("Shooter/Bottom Left Shooter", false, m_bottomLeftPid, 0)
.addP(ShooterConstants.SHOOTER_KP)
.addI(ShooterConstants.SHOOTER_KI)
.addD(ShooterConstants.SHOOTER_KD)
.addFF(ShooterConstants.SHOOTER_KF)
.build();

m_bottomRightPid = m_bottomRightMotor.getPIDController();
m_bottomRightPidProperty = new RevPidPropertyBuilder("Shooter/Bottom Right Shooter", false, m_bottomRightPid, 0)
.addP(ShooterConstants.SHOOTER_KP)
.addI(ShooterConstants.SHOOTER_KI)
.addD(ShooterConstants.SHOOTER_KD)
.addFF(ShooterConstants.SHOOTER_KF)
.build();

m_topLeftMotor.burnFlash();
m_topRightMotor.burnFlash();
Expand Down Expand Up @@ -88,23 +115,27 @@ public void setKickerVoltage(double voltage) {

@Override
public void setLeftVelocityRpm(double rpm) {
m_leftPid.setReference(rpm, CANSparkBase.ControlType.kVelocity);
m_topLeftPid.setReference(rpm, CANSparkBase.ControlType.kVelocity);
m_bottomLeftPid.setReference(rpm, CANSparkBase.ControlType.kVelocity);
}

@Override
public void setRightVelocityRpm(double rpm) {
m_rightPid.setReference(rpm, CANSparkBase.ControlType.kVelocity);
m_topRightPid.setReference(rpm, CANSparkBase.ControlType.kVelocity);
m_bottomRightPid.setReference(rpm, CANSparkBase.ControlType.kVelocity);
}

@Override
public void updateInputs(ShooterIOInputs inputs) {
m_leftPidProperty.updateIfChanged();
m_rightPidProperty.updateIfChanged();

inputs.tlVelocityRads = m_topLeftMotor.getEncoder().getVelocity() * Math.PI * 2.0;
inputs.trVelocityRads = m_topRightMotor.getEncoder().getVelocity() * Math.PI * 2.0;
inputs.blVelocityRads = m_bottomLeftMotor.getEncoder().getVelocity() * Math.PI * 2.0;
inputs.brVelocityRads = m_bottomRightMotor.getEncoder().getVelocity() * Math.PI * 2.0;
m_topLeftPidProperty.updateIfChanged();
m_topRightPidProperty.updateIfChanged();
m_bottomLeftPidProperty.updateIfChanged();
m_bottomRightPidProperty.updateIfChanged();

inputs.tlVelocityRots = m_topLeftMotor.getEncoder().getVelocity();
inputs.trVelocityRots = m_topRightMotor.getEncoder().getVelocity();
inputs.blVelocityRots = m_bottomLeftMotor.getEncoder().getVelocity();
inputs.brVelocityRots = m_bottomRightMotor.getEncoder().getVelocity();

inputs.tlAppliedVolts = m_topLeftMotor.getAppliedOutput() * m_topLeftMotor.getBusVoltage();
inputs.trAppliedVolts = m_topRightMotor.getAppliedOutput() * m_topRightMotor.getBusVoltage();
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,10 @@ public void updateInputs(ShooterIOInputs inputs) {
m_simLeft.update(LOOP_PERIOD_SECS);
m_simRight.update(LOOP_PERIOD_SECS);

inputs.tlVelocityRads = m_simLeft.getAngularVelocityRadPerSec();
inputs.trVelocityRads = m_simRight.getAngularVelocityRadPerSec();
inputs.blVelocityRads = m_simLeft.getAngularVelocityRadPerSec();
inputs.brVelocityRads = m_simRight.getAngularVelocityRadPerSec();
inputs.tlVelocityRots = m_simLeft.getAngularVelocityRadPerSec();
inputs.trVelocityRots = m_simRight.getAngularVelocityRadPerSec();
inputs.blVelocityRots = m_simLeft.getAngularVelocityRadPerSec();
inputs.brVelocityRots = m_simRight.getAngularVelocityRadPerSec();

inputs.tlAppliedVolts = leftAppliedVolts;
inputs.trAppliedVolts = rightAppliedVolts;
Expand Down

0 comments on commit b8f7b5d

Please sign in to comment.