Skip to content

Conversation

@GrumpyBud
Copy link
Collaborator

Add a new Intake subsystem (TalonFX pair with follower, voltage/duty control, periodic updates) and wire it into the DEVBOT RobotContainer.

Update hardware mappings and behavior:

  • FlywheelIOTalonFX: change leader/follower CAN IDs (14/13 -> 18/19) and reset initial PID/ff fields to 0.0.
  • Hood: raise min angle from 0.0 to 0.1 deg and change REAL/REPLAY default tunable kP/kD values.
  • HoodIOTalonFX: replace external CANcoder usage with on-talon feedback, switch to MotionMagic control, add motion magic configs, change Talon ID to 17, set motor inversion and overall sensor-to-mechanism ratio (152.0), remove remote sensor config.

RobotContainer changes:

  • Import and instantiate Intake and HoodIOTalonFX for DEVBOT; comment out DEVBOT drive construction.
  • Add controller Y button bindings to set hood angles (single press -> 15°, double press -> 25°) and stow on release.

These changes reflect updated wiring/CAN IDs, introduce the intake subsystem, and move the hood to motion-magic on the Talon with the new reduction and sensor configuration.

Add a new Intake subsystem (TalonFX pair with follower, voltage/duty control, periodic updates) and wire it into the DEVBOT RobotContainer.

Update hardware mappings and behavior:
- FlywheelIOTalonFX: change leader/follower CAN IDs (14/13 -> 18/19) and reset initial PID/ff fields to 0.0.
- Hood: raise min angle from 0.0 to 0.1 deg and change REAL/REPLAY default tunable kP/kD values.
- HoodIOTalonFX: replace external CANcoder usage with on-talon feedback, switch to MotionMagic control, add motion magic configs, change Talon ID to 17, set motor inversion and overall sensor-to-mechanism ratio (152.0), remove remote sensor config.

RobotContainer changes:
- Import and instantiate Intake and HoodIOTalonFX for DEVBOT; comment out DEVBOT drive construction.
- Add controller Y button bindings to set hood angles (single press -> 15°, double press -> 25°) and stow on release.

These changes reflect updated wiring/CAN IDs, introduce the intake subsystem, and move the hood to motion-magic on the Talon with the new reduction and sensor configuration.
Copilot AI review requested due to automatic review settings February 9, 2026 22:17
@GrumpyBud GrumpyBud merged commit 0c08885 into main Feb 9, 2026
1 check failed
@GrumpyBud GrumpyBud deleted the ShooterSubsystem branch February 9, 2026 22:19
Copy link

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

Adds a new Intake subsystem and updates hood/flywheel TalonFX hardware configuration to match updated CAN wiring and control approach (hood moves from remote CANcoder feedback to on-Talon Motion Magic). RobotContainer is updated to instantiate these on DEVBOT and adds new hood angle button bindings.

Changes:

  • Introduce Intake subsystem controlling a TalonFX leader/follower pair with voltage or duty-cycle control.
  • Update hood TalonFX IO to use on-motor feedback and Motion Magic, with updated device ID, inversion, and gear ratio.
  • Update flywheel TalonFX CAN IDs and hood tuning defaults / min angle, plus RobotContainer bindings and DEVBOT wiring changes.

Reviewed changes

Copilot reviewed 5 out of 5 changed files in this pull request and generated 3 comments.

Show a summary per file
File Description
src/main/java/frc/robot/subsystems/shooter/hood/HoodIOTalonFX.java Switch hood to on-Talon feedback + Motion Magic, update device ID and gearing configuration.
src/main/java/frc/robot/subsystems/shooter/hood/Hood.java Adjust hood min angle and REAL/REPLAY default tunables.
src/main/java/frc/robot/subsystems/shooter/flywheel/FlywheelIOTalonFX.java Update flywheel leader/follower CAN IDs and initial cached gain fields.
src/main/java/frc/robot/subsystems/intake/Intake.java Add new intake subsystem controlling two TalonFX motors with follower setup.
src/main/java/frc/robot/RobotContainer.java Wire Intake + HoodIOTalonFX into DEVBOT and add Y-button hood angle bindings.
src/main/java/frc/robot/Constants.java Change default robot selection to DEVBOT and enable tuningMode.
Comments suppressed due to low confidence (2)

src/main/java/frc/robot/RobotContainer.java:307

  • This Y-button binding schedules Commands.run(...), which never ends and has no subsystem requirements. That means it can continue running after the button is released and/or fight with the double-press binding. Use a terminating command (e.g., runOnce) or a whileTrue/startEnd style binding that requires the hood subsystem so it cancels cleanly on release.
        .y()
        .onTrue(
            Commands.runOnce(
                    () -> {

src/main/java/frc/robot/RobotContainer.java:312

  • The double-press Y binding has the same issue as the single-press binding: Commands.run(...) is non-terminating and does not require hood, so it can remain scheduled and conflict with other hood commands. Prefer runOnce or startEnd/whileTrue and include the hood requirement so only one hood-control command runs at a time.
                      var calc = ShotCalculator.getInstance();
                      calc.setUseDefaults(!calc.isUseDefaults());
                    })
                .withName("ToggleShotCalcDefaults")
                .ignoringDisable(true));

public Intake() {
MotorOutputConfigs currentConfigs = new MotorOutputConfigs();

// The left motor is CCW+
Copy link

Copilot AI Feb 9, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The comment says "The left motor is CCW+" but the inversion is set to InvertedValue.Clockwise_Positive, which is the opposite. Either fix the comment or change the inversion so the code matches the documented motor direction.

Suggested change
// The left motor is CCW+
// The left motor is CW+

Copilot uses AI. Check for mistakes.
Comment on lines +15 to +17
public class Intake extends SubsystemBase {
private TalonFX intakeMotor1 = new TalonFX(15);
private TalonFX intakeMotor2 = new TalonFX(16);
Copy link

Copilot AI Feb 9, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This new hardware subsystem bypasses the project’s established AdvantageKit IO layering/logging pattern (e.g., FlywheelIO + FlywheelIOTalonFX + Flywheel in subsystems/shooter/flywheel/, and HoodIO + HoodIOTalonFX + Hood in subsystems/shooter/hood/). Consider introducing an IntakeIO interface with @AutoLog inputs plus an IntakeIOTalonFX implementation (and optionally IntakeIOSim) so the intake’s inputs/outputs are logged consistently and SIM/REPLAY are easier to support.

Copilot uses AI. Check for mistakes.
Comment on lines +30 to 33
private final MotionMagicVoltage request = new MotionMagicVoltage(0).withSlot(0);
private final MotionMagicConfigs motionMagicConfigs =
new MotionMagicConfigs().withMotionMagicAcceleration(120).withMotionMagicCruiseVelocity(120);
private final VoltageOut voltageRequest = new VoltageOut(0);
Copy link

Copilot AI Feb 9, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

motionMagicConfigs is defined but never applied to the Talon. As written, Motion Magic will run with whatever defaults are on the controller (often 0 cruise velocity/accel), which can prevent CLOSED_LOOP moves from happening as expected. Apply these settings via config.MotionMagic... before applying the config, or apply motionMagicConfigs with the configurator (and consider removing the unused field if not needed).

Copilot uses AI. Check for mistakes.
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

1 participant