Skip to content

Commit

Permalink
Merge branch 'ShooterFinish' of https://github.com/TitaniumTitans/202…
Browse files Browse the repository at this point in the history
…4Crescendo into ShooterFinish
  • Loading branch information
Steggoo committed Jan 25, 2024
2 parents f014016 + 60ec913 commit 0992b03
Show file tree
Hide file tree
Showing 22 changed files with 122 additions and 40 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1"
id "edu.wpi.first.GradleRIO" version "2024.2.1"
id "com.peterabeles.gversion" version "1.10"
id "org.sonarqube" version "4.4.1.3373"
}
Expand Down
Binary file modified ctre_sim/CANCoder vers. H - 011 - 0 - ext.dat
Binary file not shown.
Binary file modified ctre_sim/CANCoder vers. H - 02 - 0 - ext.dat
Binary file not shown.
Binary file modified ctre_sim/CANCoder vers. H - 05 - 0 - ext.dat
Binary file not shown.
Binary file modified ctre_sim/CANCoder vers. H - 08 - 0 - ext.dat
Binary file not shown.
Binary file modified ctre_sim/Talon FX vers. C - 00 - 0 - ext.dat
Binary file not shown.
Binary file modified ctre_sim/Talon FX vers. C - 01 - 0 - ext.dat
Binary file not shown.
Binary file modified ctre_sim/Talon FX vers. C - 010 - 0 - ext.dat
Binary file not shown.
Binary file added ctre_sim/Talon FX vers. C - 018 - 0 - ext.dat
Binary file not shown.
Binary file added ctre_sim/Talon FX vers. C - 019 - 0 - ext.dat
Binary file not shown.
Binary file modified ctre_sim/Talon FX vers. C - 03 - 0 - ext.dat
Binary file not shown.
Binary file modified ctre_sim/Talon FX vers. C - 04 - 0 - ext.dat
Binary file not shown.
Binary file modified ctre_sim/Talon FX vers. C - 06 - 0 - ext.dat
Binary file not shown.
Binary file modified ctre_sim/Talon FX vers. C - 07 - 0 - ext.dat
Binary file not shown.
Binary file modified ctre_sim/Talon FX vers. C - 09 - 0 - ext.dat
Binary file not shown.
Binary file added logs/Log_24-01-23_11-04-06.wpilog
Binary file not shown.
22 changes: 21 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ public final class Constants {
private Constants() {
throw new IllegalStateException("Constants class should not be constructed");
}
public static final Mode currentMode = Mode.REAL;
public static final Mode currentMode = Mode.SIM;

public enum Mode {
/** Running on a real robot. */
Expand Down Expand Up @@ -99,4 +99,24 @@ private DriveConstants() {
ModuleConstants.GearRatios.L3
);
}

public static class ShooterConstants {
private ShooterConstants() {}

public static final int TL_SHOOTER_ID = 13;
public static final int TR_SHOOTER_ID = 14;
public static final int BL_SHOOTER_ID = 15;
public static final int BR_SHOOTER_ID = 16;
public static final int KICKER_ID = 17;
public static final int INTAKE_LEFT_ID = 20;
public static final int INTAKE_RIGHT_ID = 21;

public static final double SHOOTER_KP = 0.05;
public static final double SHOOTER_KI = 0.0;
public static final double SHOOTER_KD = 0.0;

public static final double SHOOTER_KV = 0.0;
public static final double SHOOTER_KS = 0.0;
public static final double SHOOTER_KA = 0.0;
}
}
6 changes: 4 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
import frc.robot.subsystems.shooter.ShooterIOPrototype;
import frc.robot.subsystems.shooter.ShooterSubsystem;
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 @@ -55,6 +56,7 @@ public class RobotContainer {

// Dashboard inputs
private final LoggedDashboardChooser<Command> autoChooser;
private final LoggedDashboardNumber intakeSpeed = new LoggedDashboardNumber("Intake Speed", 0.25);

/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
Expand Down Expand Up @@ -141,9 +143,9 @@ private void configureButtonBindings() {
m_driveSubsystem)
.ignoringDisable(true));

controller.a().whileTrue(m_shooter.setShooterPowerFactory(0.6, 0.6))
controller.a().whileTrue(m_shooter.setShooterPowerFactory(0.625, 0.6))
.whileFalse(m_shooter.setShooterPowerFactory(0.0, 0.0));
controller.b().whileTrue(m_shooter.setIntakePowerFactory(0.75))
controller.b().whileTrue(m_shooter.setIntakePowerFactory(intakeSpeed.get()))
.whileFalse(m_shooter.setIntakePowerFactory(0.0));

controller.leftBumper().whileTrue(m_climber.setClimberPowerFactory(-0.25))
Expand Down
7 changes: 7 additions & 0 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,17 @@ public class ShooterIOInputs {
}

public default void updateInputs(ShooterIOInputs inputs){}

default void setMotorVoltageTL(double voltage) {}
default void setMotorVoltageTR(double voltage) {}
default void setMotorVoltageBL(double voltage) {}
default void setMotorVoltageBR(double voltage) {}


default void setVelocityTL(double rpm) {}
default void setVelocityTR(double rpm) {}
default void setVelocityBL(double rpm) {}
default void setVelocityBR(double rpm) {}
default void setKickerVoltage(double voltage) {}
default void setIntakeVoltage(double voltage) {}

Expand Down
105 changes: 79 additions & 26 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIOPrototype.java
Original file line number Diff line number Diff line change
@@ -1,36 +1,85 @@
package frc.robot.subsystems.shooter;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkFlex;
import com.revrobotics.CANSparkLowLevel;
import com.gos.lib.properties.feedforward.SimpleMotorFeedForwardProperty;
import com.gos.lib.properties.pid.PidProperty;
import com.gos.lib.rev.properties.pid.RevPidPropertyBuilder;
import com.revrobotics.*;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import frc.robot.Constants.ShooterConstants;

public class ShooterIOPrototype implements ShooterIO {
private final CANSparkFlex m_topLeftMotor;
private final CANSparkFlex m_topRightMotor;
private final CANSparkMax m_bottomLeftMotor;
private final CANSparkMax m_bottomRightMotor;
private final CANSparkMax m_kickekMotor;
private final CANSparkMax m_kickerMotor;
private final CANSparkMax m_intakeLeft;
private final CANSparkMax m_intakeRight;

private final SparkPIDController m_tlController;
private final PidProperty m_tlPid;
private final SparkPIDController m_trController;
private final PidProperty m_trPid;
private final SparkPIDController m_blController;
private final PidProperty m_blPid;
private final SparkPIDController m_brController;
private final PidProperty m_brPid;

private final SimpleMotorFeedforward m_shooterFF;
private final SimpleMotorFeedForwardProperty m_shooterFFProperty;

public ShooterIOPrototype() {
m_topLeftMotor = new CANSparkFlex(13, CANSparkLowLevel.MotorType.kBrushless);
m_topRightMotor = new CANSparkFlex(14, CANSparkLowLevel.MotorType.kBrushless);
m_bottomLeftMotor = new CANSparkMax(15, CANSparkLowLevel.MotorType.kBrushless);
m_bottomRightMotor = new CANSparkMax(16, CANSparkLowLevel.MotorType.kBrushless);
m_kickekMotor = new CANSparkMax(17, CANSparkLowLevel.MotorType.kBrushless);
m_intakeLeft = new CANSparkMax(20, CANSparkLowLevel.MotorType.kBrushless);
m_intakeRight = new CANSparkMax(21, CANSparkLowLevel.MotorType.kBrushless);
m_topLeftMotor = new CANSparkFlex(ShooterConstants.TL_SHOOTER_ID, CANSparkLowLevel.MotorType.kBrushless);
m_topRightMotor = new CANSparkFlex(ShooterConstants.TR_SHOOTER_ID, CANSparkLowLevel.MotorType.kBrushless);
m_bottomLeftMotor = new CANSparkMax(ShooterConstants.BL_SHOOTER_ID, CANSparkLowLevel.MotorType.kBrushless);
m_bottomRightMotor = new CANSparkMax(ShooterConstants.BR_SHOOTER_ID, CANSparkLowLevel.MotorType.kBrushless);
m_kickerMotor = new CANSparkMax(ShooterConstants.KICKER_ID, CANSparkLowLevel.MotorType.kBrushless);
m_intakeLeft = new CANSparkMax(ShooterConstants.INTAKE_LEFT_ID, CANSparkLowLevel.MotorType.kBrushless);
m_intakeRight = new CANSparkMax(ShooterConstants.INTAKE_RIGHT_ID, CANSparkLowLevel.MotorType.kBrushless);

m_topLeftMotor.setInverted(false);
m_bottomLeftMotor.setInverted(true);
m_bottomLeftMotor.setInverted(false);

m_intakeRight.setInverted(true);
m_intakeLeft.setInverted(false);
m_intakeLeft.setInverted(true);
m_kickerMotor.setInverted(true);

m_tlController = m_topLeftMotor.getPIDController();
m_tlPid = new RevPidPropertyBuilder("Shooter/TL PID", false, m_tlController, 0)
.addP(ShooterConstants.SHOOTER_KP)
.addI(ShooterConstants.SHOOTER_KI)
.addD(ShooterConstants.SHOOTER_KD)
.build();

m_trController = m_topLeftMotor.getPIDController();
m_trPid = new RevPidPropertyBuilder("Shooter/TR PID", false, m_trController, 0)
.addP(ShooterConstants.SHOOTER_KP)
.addI(ShooterConstants.SHOOTER_KI)
.addD(ShooterConstants.SHOOTER_KD)
.build();

m_blController = m_topLeftMotor.getPIDController();
m_blPid = new RevPidPropertyBuilder("Shooter/BL PID", false, m_blController, 0)
.addP(ShooterConstants.SHOOTER_KP)
.addI(ShooterConstants.SHOOTER_KI)
.addD(ShooterConstants.SHOOTER_KD)
.build();

m_brController = m_topLeftMotor.getPIDController();
m_brPid = new RevPidPropertyBuilder("Shooter/BR PID", false, m_brController, 0)
.addP(ShooterConstants.SHOOTER_KP)
.addI(ShooterConstants.SHOOTER_KI)
.addD(ShooterConstants.SHOOTER_KD)
.build();

m_shooterFF = new SimpleMotorFeedforward(ShooterConstants.SHOOTER_KS, ShooterConstants.SHOOTER_KV);
m_shooterFFProperty = new SimpleMotorFeedForwardProperty("Shooter FF", false, m_shooterFF);

m_topLeftMotor.burnFlash();
m_topRightMotor.burnFlash();
m_intakeLeft.burnFlash();
m_intakeRight.burnFlash();
m_kickerMotor.burnFlash();
}

@Override
Expand All @@ -39,38 +88,42 @@ public void updateInputs(ShooterIOInputs inputs) {
inputs.tRAngularVelocity = m_topRightMotor.getEncoder().getVelocity() * Math.PI;
inputs.bLAngularVelocity = m_bottomLeftMotor.getEncoder().getVelocity() * Math.PI;
inputs.bRAngularVelocity = m_bottomRightMotor.getEncoder().getVelocity() * Math.PI;
inputs.kickerAngularVelocity = m_kickekMotor.getEncoder().getVelocity() * Math.PI;
inputs.kickerAngularVelocity = m_kickerMotor.getEncoder().getVelocity() * Math.PI;

inputs.tLAppliedInputs = m_topLeftMotor.getAppliedOutput();
inputs.tRAppliedInputs = m_topRightMotor.getAppliedOutput();
inputs.bLAppliedInputs = m_bottomLeftMotor.getAppliedOutput();
inputs.bRAppliedInputs = m_bottomRightMotor.getAppliedOutput();
inputs.kickerAppliedInputs = m_kickekMotor.getAppliedOutput();
inputs.kickerAppliedInputs = m_kickerMotor.getAppliedOutput();
}

@Override
public void setMotorVoltageTL(double voltage) {
m_topLeftMotor.setVoltage(voltage);
}
@Override
public void setVelocityTL(double rpm) {
m_tlController.setReference(rpm,
CANSparkBase.ControlType.kVelocity,
0,
m_shooterFFProperty.calculate(rpm),
SparkPIDController.ArbFFUnits.kVoltage);
}

@Override
public void setMotorVoltageTR(double voltage) {
m_topRightMotor.setVoltage(voltage);
public void setVelocityTR(double rpm) {
m_topRightMotor.setVoltage(rpm);
}

@Override
public void setMotorVoltageBL(double voltage) {
m_bottomLeftMotor.setVoltage(voltage);
public void setVelocityBL(double rpm) {
m_bottomLeftMotor.setVoltage(rpm);
}

@Override
public void setMotorVoltageBR(double voltage) {
m_bottomRightMotor.setVoltage(voltage);
public void setVelocityBR(double rpm) {
m_bottomRightMotor.setVoltage(rpm);
}

@Override
public void setKickerVoltage(double voltage) {
m_kickekMotor.setVoltage(voltage);
m_kickerMotor.setVoltage(voltage);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,13 @@ public ShooterSubsystem(ShooterIO io) {
}

public void setShooterPowerLeft(double power) {
m_io.setMotorVoltageTL((power * 12.0) * SmartDashboard.getNumber(TOP_WHEEL_RATIO, 0.85));
m_io.setMotorVoltageBL(power * 12.0);
m_io.setVelocityTL((power * 12.0) * SmartDashboard.getNumber(TOP_WHEEL_RATIO, 0.85));
m_io.setVelocityBL(power * 12.0);
}

public void setShooterPowerRight(double power) {
m_io.setMotorVoltageTR((power * 12.0) * SmartDashboard.getNumber(TOP_WHEEL_RATIO, 0.85));
m_io.setMotorVoltageBR(power * 12.0);
m_io.setVelocityTR((power * 12.0) * SmartDashboard.getNumber(TOP_WHEEL_RATIO, 0.85));
m_io.setVelocityBR(power * 12.0);
}

public void setKickerPower(double power) {
Expand Down
12 changes: 6 additions & 6 deletions vendordeps/AdvantageKit.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "AdvantageKit.json",
"name": "AdvantageKit",
"version": "3.0.0",
"version": "3.0.2",
"uuid": "d820cc26-74e3-11ec-90d6-0242ac120003",
"frcYear": "2024",
"mavenUrls": [],
Expand All @@ -10,24 +10,24 @@
{
"groupId": "org.littletonrobotics.akit.junction",
"artifactId": "wpilib-shim",
"version": "3.0.0"
"version": "3.0.2"
},
{
"groupId": "org.littletonrobotics.akit.junction",
"artifactId": "junction-core",
"version": "3.0.0"
"version": "3.0.2"
},
{
"groupId": "org.littletonrobotics.akit.conduit",
"artifactId": "conduit-api",
"version": "3.0.0"
"version": "3.0.2"
}
],
"jniDependencies": [
{
"groupId": "org.littletonrobotics.akit.conduit",
"artifactId": "conduit-wpilibio",
"version": "3.0.0",
"version": "3.0.2",
"skipInvalidPlatforms": false,
"isJar": false,
"validPlatforms": [
Expand All @@ -39,4 +39,4 @@
}
],
"cppDependencies": []
}
}

0 comments on commit 0992b03

Please sign in to comment.