-
Notifications
You must be signed in to change notification settings - Fork 0
Added a shooter subsystem #44
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: main
Are you sure you want to change the base?
Changes from all commits
9dbe4c0
5e1c17c
a608619
81ebf3a
fec25d3
02b24de
32315f7
9bb5a4d
46fb858
8ca6d3e
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,41 @@ | ||
| package frc.robot.commands.shooter; | ||
|
|
||
| import edu.wpi.first.wpilibj.Timer; | ||
| import frc.robot.constants.Constants; | ||
| import frc.robot.subsystems.ShooterSubsystem; | ||
| import frc.robot.utils.logging.commands.LoggableCommand; | ||
|
|
||
| public class SpinShooter extends LoggableCommand{ | ||
|
|
||
| private final ShooterSubsystem subsystem; | ||
| private final double speed; | ||
| private final Timer timer; | ||
|
|
||
| public SpinShooter(ShooterSubsystem subsystem, double speed) { | ||
| this.subsystem = subsystem; | ||
| this.speed = speed; | ||
| timer = new Timer(); | ||
| addRequirements(subsystem); | ||
| } | ||
|
|
||
| @Override | ||
| public void initialize() { | ||
| timer.restart(); | ||
| } | ||
|
|
||
| @Override | ||
| public void execute() { | ||
| subsystem.setPidVelocity(speed); | ||
| } | ||
|
|
||
| @Override | ||
| public boolean isFinished() { | ||
| return timer.hasElapsed(Constants.SHOOTER_TIMEOUT); | ||
| } | ||
|
|
||
| @Override | ||
| public void end(boolean interrupted) { | ||
| subsystem.stopMotors(); | ||
| } | ||
|
|
||
| } | ||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -10,6 +10,8 @@ public class Constants2026 extends GameConstants { | |
| public static final int ANGLER_MOTOR_ID = 6; | ||
| public static final int HOPPER_MOTOR_ID = 4; | ||
| public static final int FEEDER_MOTOR_ID = 5; | ||
| public static final int SHOOTER_MOTOR_ID = 8; | ||
|
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I think we should add a similar pair of constants to the |
||
| public static final int SHOOTER_FOLLOWER_MOTOR_ID = 7; | ||
|
|
||
| public static final double DRIVE_BASE_WIDTH = 0.635; | ||
| public static final double DRIVE_BASE_LENGTH = 0.635; | ||
|
|
||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,80 @@ | ||
| package frc.robot.subsystems; | ||
|
|
||
|
|
||
|
|
||
| import com.ctre.phoenix6.controls.Follower; | ||
| import com.revrobotics.spark.SparkLowLevel; | ||
| import com.revrobotics.spark.SparkMax; | ||
| import com.revrobotics.spark.SparkBase.PersistMode; | ||
| import com.revrobotics.spark.SparkBase.ResetMode; | ||
| import com.revrobotics.spark.config.SparkBaseConfig; | ||
| import com.revrobotics.spark.config.SparkMaxConfig; | ||
|
|
||
| import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||
| import frc.robot.constants.Constants; | ||
| import frc.robot.utils.logging.input.MotorLoggableInputs; | ||
| import frc.robot.utils.logging.io.motor.SparkMaxIo; | ||
| import frc.robot.utils.logging.io.pidmotor.MockSparkMaxPidMotorIo; | ||
| import frc.robot.utils.logging.io.pidmotor.RealSparkMaxPidMotorIo; | ||
| import frc.robot.utils.logging.io.pidmotor.SimSparkMaxPidMotorIo; | ||
| import frc.robot.utils.logging.io.pidmotor.SparkMaxPidConfig; | ||
| import frc.robot.utils.logging.io.pidmotor.SparkMaxPidMotor; | ||
| import frc.robot.utils.logging.io.pidmotor.SparkMaxPidMotorIo; | ||
| import frc.robot.utils.simulation.MotorSimulator; | ||
| import frc.robot.utils.simulation.RobotVisualizer; | ||
|
|
||
| public class ShooterSubsystem extends SubsystemBase { | ||
|
|
||
| public static final String LOGGING_NAME = "ShooterSubsystem"; | ||
|
|
||
| private final SparkMaxPidMotorIo io; | ||
| private final SparkMax followerMotor; | ||
| private final SparkMaxConfig followerConfig; | ||
|
|
||
| public ShooterSubsystem(SparkMaxPidMotorIo io) { | ||
| this.io = io; | ||
| io.setPid(0.0000002, 0.000015, 0.000015); // Pid needs tuning | ||
| followerMotor = new SparkMax(Constants.SHOOTER_FOLLOWER_MOTOR_ID, SparkLowLevel.MotorType.kBrushless); | ||
| followerConfig = new SparkMaxConfig(); | ||
| followerConfig.follow(Constants.SHOOTER_MOTOR_ID, true); | ||
| followerMotor.configure(followerConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters); | ||
|
|
||
| } | ||
|
|
||
| // setSpeed expects a power value from -1 to 1 | ||
| public void setSpeed(double speed) { | ||
|
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Add a comment on the units the method expects (this actually takes power value in -1 to +1)
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Fixed. |
||
| io.set(speed); | ||
| } | ||
|
|
||
| public void stopMotors() { | ||
| io.stopMotor(); | ||
| } | ||
|
|
||
| // setPidVelocity expects a speed in RPM | ||
| public void setPidVelocity(double velocity) { | ||
|
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Add a comment that explains the expected units (this is speed in RPM)
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Fixed. |
||
| io.setPidVelocity(velocity); | ||
| } | ||
|
|
||
| @Override | ||
| public void periodic() { | ||
| io.periodic(); | ||
| } | ||
|
|
||
| public static SparkMaxPidMotorIo createMockIo() { | ||
| return new MockSparkMaxPidMotorIo(LOGGING_NAME, MotorLoggableInputs.allMetrics()); | ||
| } | ||
|
|
||
| public static SparkMaxPidMotorIo createRealIo() { | ||
| return new RealSparkMaxPidMotorIo(LOGGING_NAME, createMotor(), MotorLoggableInputs.allMetrics()); | ||
| } | ||
|
|
||
| public static SparkMaxPidMotorIo createSimIo(RobotVisualizer visualizer) { | ||
| SparkMaxPidMotor motor = createMotor(); | ||
| return new SimSparkMaxPidMotorIo(LOGGING_NAME, motor, MotorLoggableInputs.allMetrics(), new MotorSimulator(motor.getNeoMotor(), visualizer.getShooterLigament())); | ||
| } | ||
|
|
||
| public static SparkMaxPidMotor createMotor() { | ||
| return new SparkMaxPidMotor(Constants.SHOOTER_MOTOR_ID, true); | ||
| } | ||
|
|
||
| } | ||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Two comments on the command:
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Fixed.