Conversation
Note that we still need to test this on real hardware and verify setpoints and limits.
There was a problem hiding this comment.
Pull request overview
This PR implements hardware and control updates for multiple robot subsystems, transitioning from SparkMax to ThriftyNova motor controllers and adding new intake, hopper, and kicker subsystems with operator controls.
Changes:
- Replaced SparkMax motor controllers with ThriftyNova controllers across shooter and turret subsystems
- Added three new subsystems (IntakeSubsystem, HopperSubsystem, KickerSubsystem) with associated motor configurations and commands
- Updated Superstructure to coordinate the new subsystems and added feature flag for Limelight vision
Reviewed changes
Copilot reviewed 11 out of 11 changed files in this pull request and generated 5 comments.
Show a summary per file
| File | Description |
|---|---|
| TurretSubsystem.java | Changed from dual NEO motors to single NEO with ThriftyNova, updated gearing from 25:1 to 4:1, adjusted FOV from 270° to 90° |
| SwerveSubsystem.java | Added IS_LIMELIGHT_ENABLED flag to conditionally disable Limelight integration |
| Superstructure.java | Integrated intake, hopper, and kicker subsystems with command factory methods |
| ShooterSubsystem.java | Migrated to ThriftyNova controllers, changed gearing to 1:1, fixed spin-up speed from 50 to 500 RPS |
| KickerSubsystem.java | New subsystem controlling kicker mechanism with ThriftyNova and NEO motor |
| IntakeSubsystem.java | New subsystem with roller and pivot mechanisms using NEO Vortex motors |
| HopperSubsystem.java | New subsystem for hopper control with ThriftyNova and NEO motor |
| OperatorControls.java | Mapped operator controller buttons to new subsystem commands |
| DriverControls.java | Added gyro zero command to Y button |
| RobotContainer.java | Instantiated new subsystems and passed null for turret/hood temporarily |
| Constants.java | Added CAN ID constants for intake, hopper, and kicker subsystems |
💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.
| .withUpperSoftLimit(RotationsPerSecond.of(6000)) | ||
| .withLowerSoftLimit(RotationsPerSecond.of(0)) |
There was a problem hiding this comment.
The soft limits use RotationsPerSecond units, but the value 6000 rotations per second (360,000 RPM) is unrealistically high for a NEO motor, which has a maximum speed around 5,880 RPM (98 RPS). This appears to be a unit conversion error where RPM values were used with RotationsPerSecond units.
| @@ -0,0 +1,84 @@ | |||
| package frc.robot.subsystems; | |||
|
|
|||
| import com.revrobotics.spark.SparkLowLevel.MotorType; | |||
There was a problem hiding this comment.
Unused import statement for SparkLowLevel.MotorType. This subsystem uses ThriftyNova controllers, not Spark controllers.
| import com.revrobotics.spark.SparkLowLevel.MotorType; |
| private final KickerSubsystem kicker = new KickerSubsystem(); | ||
| private final ShooterSubsystem shooter = new ShooterSubsystem(); | ||
|
|
||
| private final Superstructure superstructure = new Superstructure(shooter, null, null, intake, hopper, kicker); |
There was a problem hiding this comment.
Passing null for turret and hood parameters will cause NullPointerException if any Superstructure methods attempt to use these subsystems. Consider either instantiating these subsystems or updating Superstructure to handle null values gracefully.
| private final Superstructure superstructure = new Superstructure(shooter, null, null, intake, hopper, kicker); | |
| private final Superstructure superstructure = new Superstructure(shooter, intake, hopper, kicker); |
| .withImuAssistAlpha(0.01) | ||
| .save(); | ||
| }); | ||
|
|
There was a problem hiding this comment.
Unnecessary blank line added inside the conditional block. This breaks the logical grouping of the command registration statements.
| public Command rezero() { | ||
| return Commands.runOnce(() -> pivotMotor.setEncoderPosition(0), this).withName("IntakePivot.Rezero"); |
There was a problem hiding this comment.
The rezero method directly sets the encoder position to 0 without any safety checks or validation. Consider verifying the mechanism is in a known safe position before zeroing, or document the expected state when this command should be called.
| public Command rezero() { | |
| return Commands.runOnce(() -> pivotMotor.setEncoderPosition(0), this).withName("IntakePivot.Rezero"); | |
| /** | |
| * Re-zero the intake pivot encoder. | |
| * <p> | |
| * This command should only be used when the robot is disabled and the intake | |
| * pivot is in its known mechanical zero position (for example, against a hard stop). | |
| * Attempting to re-zero while the robot is enabled is ignored and will report a warning. | |
| */ | |
| public Command rezero() { | |
| return Commands | |
| .runOnce( | |
| () -> { | |
| if (!edu.wpi.first.wpilibj.DriverStation.isDisabled()) { | |
| edu.wpi.first.wpilibj.DriverStation.reportWarning( | |
| "Attempted to rezero IntakePivot while robot is enabled; encoder position not changed.", | |
| false); | |
| return; | |
| } | |
| pivotMotor.setEncoderPosition(0); | |
| }, | |
| this) | |
| .withName("IntakePivot.Rezero"); |
No description provided.