Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/controls/OperatorControls.java
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ public static void configure(int port, SwerveSubsystem drivetrain, Superstructur
// }

// REAL CONTROLS
controller.start().onTrue(superstructure.rezeroIntakePivotCommand().ignoringDisable(true));
controller.start().onTrue(superstructure.rezeroIntakePivotAndTurretCommand().ignoringDisable(true));

controller.rightBumper()
.whileTrue(superstructure.setIntakeDeployAndRoll().withName("OperatorControls.intakeDeployed"));
Expand Down
25 changes: 17 additions & 8 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,12 @@
package frc.robot.subsystems;

import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkLowLevel.MotorType;

import com.thethriftybot.ThriftyNova;

import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.system.plant.DCMotor;
import static edu.wpi.first.units.Units.Amps;
import static edu.wpi.first.units.Units.Degrees;
Expand Down Expand Up @@ -30,6 +34,7 @@
import yams.motorcontrollers.SmartMotorControllerConfig.MotorMode;
import yams.motorcontrollers.SmartMotorControllerConfig.TelemetryVerbosity;
import yams.motorcontrollers.local.NovaWrapper;
import yams.motorcontrollers.local.SparkWrapper;

public class IntakeSubsystem extends SubsystemBase {

Expand Down Expand Up @@ -60,18 +65,22 @@ public class IntakeSubsystem extends SubsystemBase {
// 5:1, 5:1, 60/18 reduction
private SmartMotorControllerConfig intakePivotSmartMotorConfig = new SmartMotorControllerConfig(this)
.withControlMode(ControlMode.CLOSED_LOOP)
.withClosedLoopController(10, 0, 0, DegreesPerSecond.of(1080), DegreesPerSecondPerSecond.of(1080))
.withFeedforward(new ArmFeedforward(0, 0, 1.3))
.withClosedLoopController(25, 0, 0, DegreesPerSecond.of(360), DegreesPerSecondPerSecond.of(360))
.withFeedforward(new SimpleMotorFeedforward(0, 10, 0))
.withTelemetry("IntakePivotMotor", TelemetryVerbosity.HIGH)
.withGearing(new MechanismGearing(GearBox.fromReductionStages(5, 5, 60.0 / 18.0, 42)))
.withGearing(new MechanismGearing(GearBox.fromReductionStages(5, 5, 60.0 / 18.0)))
// .withGearing(new MechanismGearing(GearBox.fromReductionStages(5, 5, 60.0 /
// 18.0, 42)))
Comment on lines +72 to +73
Copy link

Copilot AI Jan 28, 2026

Choose a reason for hiding this comment

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

The commented-out gearing configuration on lines 72-73 appears to be an old version. Remove this commented code to improve clarity, as the active configuration is already defined on line 71.

Suggested change
// .withGearing(new MechanismGearing(GearBox.fromReductionStages(5, 5, 60.0 /
// 18.0, 42)))

Copilot uses AI. Check for mistakes.
.withMotorInverted(false)
.withIdleMode(MotorMode.COAST)
.withSoftLimit(Degrees.of(0), Degrees.of(150))
.withStatorCurrentLimit(Amps.of(10))
.withClosedLoopRampRate(Seconds.of(0.1));
.withClosedLoopRampRate(Seconds.of(0.1))
.withOpenLoopRampRate(Seconds.of(0.1));

private ThriftyNova pivotMotor = new ThriftyNova(Constants.IntakeConstants.kPivotMotorId);
private SparkMax pivotMotor = new SparkMax(Constants.IntakeConstants.kPivotMotorId, MotorType.kBrushless);

private SmartMotorController intakePivotController = new NovaWrapper(pivotMotor, DCMotor.getNeoVortex(1),
private SmartMotorController intakePivotController = new SparkWrapper(pivotMotor, DCMotor.getNeoVortex(1),
intakePivotSmartMotorConfig);

private final ArmConfig intakePivotConfig = new ArmConfig(intakePivotController)
Expand All @@ -85,7 +94,7 @@ public class IntakeSubsystem extends SubsystemBase {
private Arm intakePivot = new Arm(intakePivotConfig);

public IntakeSubsystem() {
pivotMotor.factoryReset();
// pivotMotor.factoryReset();
}

/**
Expand All @@ -107,7 +116,7 @@ public Command setPivotAngle(Angle angle) {
}

public Command rezero() {
return Commands.runOnce(() -> pivotMotor.setEncoderPosition(0), this).withName("IntakePivot.Rezero");
return Commands.runOnce(() -> pivotMotor.getEncoder().setPosition(0), this).withName("IntakePivot.Rezero");
}

/**
Expand Down
11 changes: 7 additions & 4 deletions src/main/java/frc/robot/subsystems/Superstructure.java
Original file line number Diff line number Diff line change
Expand Up @@ -240,8 +240,8 @@ public Command kickerStopCommand() {
public Command feedAllCommand() {
return Commands.parallel(
hopper.feedCommand().asProxy(),
kicker.feedCommand().asProxy(),
intake.setPivotAngle(Degrees.of(46)).asProxy()).withName("Superstructure.feedAll");
kicker.feedCommand().asProxy()).withName("Superstructure.feedAll");
// intake.setPivotAngle(Degrees.of(46)).asProxy()).withName("Superstructure.feedAll");
Copy link

Copilot AI Jan 28, 2026

Choose a reason for hiding this comment

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

The commented-out code duplicates the withName call from line 243. If this code needs to be re-enabled, remove the withName call from the commented portion to avoid confusion.

Suggested change
// intake.setPivotAngle(Degrees.of(46)).asProxy()).withName("Superstructure.feedAll");
// intake.setPivotAngle(Degrees.of(46)).asProxy());

Copilot uses AI. Check for mistakes.
}

public Command backFeedAllCommand() {
Expand Down Expand Up @@ -295,8 +295,11 @@ public Command stopShootingCommand() {
}

// Re-zero intake pivot if needed
public Command rezeroIntakePivotCommand() {
return intake.rezero().withName("Superstructure.rezeroIntakePivot");
public Command rezeroIntakePivotAndTurretCommand() {
return Commands.parallel(
turret.rezero().withName("Superstructure.rezeroTurret"),
intake.rezero().withName("Superstructure.rezeroIntakePivot"))
.withName("Superstructure.rezeroIntakePivotAndTurret");
}

@Override
Expand Down
11 changes: 8 additions & 3 deletions src/main/java/frc/robot/subsystems/TurretSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.SparkMax;

import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Translation3d;
Expand All @@ -22,6 +22,7 @@
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import yams.gearing.GearBox;
Expand Down Expand Up @@ -53,8 +54,8 @@ public class TurretSubsystem extends SubsystemBase {

private SmartMotorControllerConfig smcConfig = new SmartMotorControllerConfig(this)
.withControlMode(ControlMode.CLOSED_LOOP)
.withClosedLoopController(60.0, 0, 0, DegreesPerSecond.of(10800), DegreesPerSecondPerSecond.of(10800))
.withFeedforward(new ArmFeedforward(0, 0, 0))
.withClosedLoopController(15.0, 0, 0, DegreesPerSecond.of(2440), DegreesPerSecondPerSecond.of(2440))
.withFeedforward(new SimpleMotorFeedforward(0, 7.5, 0))
.withTelemetry("TurretMotor", TelemetryVerbosity.HIGH)
.withGearing(new MechanismGearing(GearBox.fromReductionStages(4, 10)))
.withMotorInverted(true)
Expand Down Expand Up @@ -105,6 +106,10 @@ public Command set(double dutyCycle) {
return turret.set(dutyCycle);
}

public Command rezero() {
return Commands.runOnce(() -> spark.getEncoder().setPosition(0), this).withName("Turret.Rezero");
}

public Command sysId() {
return turret.sysId(Volts.of(7), Volts.of(2).per(Second), Seconds.of(10));
}
Expand Down