Merge pull request #9 from Team4388/New-Intake

New intake
This commit is contained in:
Michael Mikovsky
2026-04-04 11:16:46 -06:00
committed by GitHub
8 changed files with 52 additions and 51 deletions
@@ -377,7 +377,7 @@ public class RobotContainer {
new JoystickButton(getDeadbandedOperatorController(), XboxController.Y_BUTTON) new JoystickButton(getDeadbandedOperatorController(), XboxController.Y_BUTTON)
.onTrue(new InstantCommand(() -> { .onTrue(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Retracting); m_robotIntake.setMode(IntakeMode.RectractTorque);
})) }))
.onFalse(new InstantCommand(() -> { .onFalse(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Idle); m_robotIntake.setMode(IntakeMode.Idle);
@@ -410,6 +410,14 @@ public class RobotContainer {
m_robotIntake.setMode(IntakeMode.Idle); m_robotIntake.setMode(IntakeMode.Idle);
})); }));
new Trigger(() -> getDeadbandedOperatorController().getPOV() == 180)
.onTrue(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.ExpelBalls);
}))
.onFalse(new InstantCommand(() -> {
m_robotIntake.setMode(IntakeMode.Idle);
}));
// .onFalse(new InstantCommand(() -> { // .onFalse(new InstantCommand(() -> {
// m_robotIntake.setMode(IntakeMode.Idle); // m_robotIntake.setMode(IntakeMode.Idle);
+1 -1
View File
@@ -101,7 +101,7 @@ public class RobotMap {
//Configure Intake 20,21 //Configure Intake 20,21
SparkMax arm = new SparkMax(IntakeConstants.ARM_ID.id, com.revrobotics.spark.SparkLowLevel.MotorType.kBrushless); SparkMax arm = new SparkMax(IntakeConstants.ARM_ID.id, com.revrobotics.spark.SparkLowLevel.MotorType.kBrushless);
TalonFX roller = new TalonFX(IntakeConstants.ROLLER_ID.id, Constants.CANIVORE_CANBUS); TalonFX roller = new TalonFX(IntakeConstants.ROLLER_ID.id, Constants.RIO_CANBUS);
// DigitalInput armLimitSwitch = new DigitalInput(IntakeConstants.ARM_LIMIT_SWITCH_CHANNEL); // DigitalInput armLimitSwitch = new DigitalInput(IntakeConstants.ARM_LIMIT_SWITCH_CHANNEL);
// DigitalInput basinLimitSwitch = new DigitalInput(ElevatorConstants.BASIN_LIMIT_SWITCH); // DigitalInput basinLimitSwitch = new DigitalInput(ElevatorConstants.BASIN_LIMIT_SWITCH);
// DigitalInput endeffectorLimitSwitch = new DigitalInput(ElevatorConstants.ENDEFFECTOR_LIMIT_SWITCH); // DigitalInput endeffectorLimitSwitch = new DigitalInput(ElevatorConstants.ENDEFFECTOR_LIMIT_SWITCH);
@@ -7,12 +7,12 @@ public final class BuildConstants {
public static final String MAVEN_GROUP = ""; public static final String MAVEN_GROUP = "";
public static final String MAVEN_NAME = "2026KPopRobotHunters"; public static final String MAVEN_NAME = "2026KPopRobotHunters";
public static final String VERSION = "unspecified"; public static final String VERSION = "unspecified";
public static final int GIT_REVISION = 198; public static final int GIT_REVISION = 200;
public static final String GIT_SHA = "958bdc46fd90b8388750f8bf1a95b62ff91b2092"; public static final String GIT_SHA = "3750a97424bfa4c90fc68b8db323029cdbb55452";
public static final String GIT_DATE = "2026-03-31 20:51:47 MDT"; public static final String GIT_DATE = "2026-04-02 18:27:51 MDT";
public static final String GIT_BRANCH = "New-Intake"; public static final String GIT_BRANCH = "New-Intake";
public static final String BUILD_DATE = "2026-04-01 17:29:06 MDT"; public static final String BUILD_DATE = "2026-04-03 20:54:00 MDT";
public static final long BUILD_UNIX_TIME = 1775086146983L; public static final long BUILD_UNIX_TIME = 1775271240963L;
public static final int DIRTY = 1; public static final int DIRTY = 1;
private BuildConstants(){} private BuildConstants(){}
@@ -44,6 +44,6 @@ public class ClimberConstants {
).withMotorOutput( ).withMotorOutput(
new MotorOutputConfigs() new MotorOutputConfigs()
.withNeutralMode(NeutralModeValue.Brake) // Must be break because this has to be accurate .withNeutralMode(NeutralModeValue.Brake) // Must be break because this has to be accurate
.withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means .withDutyCycleNeutralDeadband(0.04) // This sets the minimum output of motor so if its less than 4% it wont move
); );
} }
@@ -41,7 +41,8 @@ public class Intake extends SubsystemBase {
Idle, Idle,
RectractTorque, RectractTorque,
Bouncing Bouncing,
ExpelBalls
} }
private boolean overCompressed = false; private boolean overCompressed = false;
@@ -104,11 +105,9 @@ public class Intake extends SubsystemBase {
io.updateInputs(state); io.updateInputs(state);
if (state.armMotorCurrent.in(Amps) < IntakeConstants.INTAKE_SQUEEZE_CURRENT_LOWER_THRESHOLD.get()){ overCompressed =
overCompressed = false; Math.abs(state.armMotorCurrent.in(Amps)) > IntakeConstants.INTAKE_BOUNCE_CURRENT_LIMIT.get();
} else if (state.armMotorCurrent.in(Amps) > IntakeConstants.INTAKE_SQUEEZE_CURRENT_UPPER_THRESHOLD.get()) { // Math.abs(state.armMotorVelocity.in(RotationsPerSecond)) < IntakeConstants.INTAKE_BOUNCE_VELOCITY_LIMIT.get();
overCompressed = true;
}
Logger.recordOutput("overCompressed", overCompressed); Logger.recordOutput("overCompressed", overCompressed);
@@ -137,11 +136,11 @@ public class Intake extends SubsystemBase {
case Retracting: case Retracting:
io.armOutput(IntakeConstants.ARM_RETRACT_PERCENT_OUTPUT.get()); io.armOutput(IntakeConstants.ARM_RETRACT_PERCENT_OUTPUT.get());
if(state.intakeEncoder.in(Rotations) > IntakeConstants.ARM_REVERSE_ROLLER_RANGE.get()) { // if(state.intakeEncoder.in(Rotations) > IntakeConstants.ARM_REVERSE_ROLLER_RANGE.get()) {
io.setRollerOutput(state, IntakeConstants.ROLLER_RETRACT_PERCENT_OUTPUT.get()); io.setRollerOutput(state, IntakeConstants.ROLLER_RETRACT_PERCENT_OUTPUT.get());
} else { // } else {
io.setRollerOutput(state, 0); // io.setRollerOutput(state, 0);
} // }
break; break;
case Bouncing: case Bouncing:
@@ -151,7 +150,7 @@ public class Intake extends SubsystemBase {
state.armMotorCurrent.in(Amps) > IntakeConstants.INTAKE_BOUNCE_CURRENT_LIMIT.get() state.armMotorCurrent.in(Amps) > IntakeConstants.INTAKE_BOUNCE_CURRENT_LIMIT.get()
// Math.abs(state.armMotorVelocity.in(RotationsPerSecond)) < IntakeConstants.INTAKE_BOUNCE_VELOCITY_LIMIT.get() // Math.abs(state.armMotorVelocity.in(RotationsPerSecond)) < IntakeConstants.INTAKE_BOUNCE_VELOCITY_LIMIT.get()
) { ) {
System.out.println("RESET BOUNCE"); // System.out.println("RESET BOUNCE");
this.state.currentBounceTime = Utils.getSystemTimeSeconds() + IntakeConstants.INTAKE_BOUNCE_HALF_PERIOD.get(); this.state.currentBounceTime = Utils.getSystemTimeSeconds() + IntakeConstants.INTAKE_BOUNCE_HALF_PERIOD.get();
} }
@@ -174,19 +173,25 @@ public class Intake extends SubsystemBase {
io.setRollerOutput(state, IntakeConstants.ROLLER_RETRACT_PERCENT_OUTPUT.get()); io.setRollerOutput(state, IntakeConstants.ROLLER_RETRACT_PERCENT_OUTPUT.get());
if (!overCompressed){ if (!overCompressed){
io.armOutput(IntakeConstants.ARM_SQUEEZE_PERCENT_OUTPUT.get()); io.armOutput(IntakeConstants.ARM_SQUEEZE_PERCENT_OUTPUT.get());
} else if (overCompressed) { } else {
io.armOutput(IntakeConstants.ARM_REDUCED_SQUEEZE_PERCENT_OUTPUT.get()); io.armOutput(IntakeConstants.ARM_REDUCED_SQUEEZE_PERCENT_OUTPUT.get());
} }
if(state.intakeEncoder.in(Rotations) > IntakeConstants.ARM_REVERSE_ROLLER_RANGE.get()) {
io.setRollerOutput(state, IntakeConstants.ROLLER_RETRACT_PERCENT_OUTPUT.get()); // if(state.intakeEncoder.in(Rotations) > IntakeConstants.ARM_REVERSE_ROLLER_RANGE.get()) {
} else { // io.setRollerOutput(state, IntakeConstants.ROLLER_RETRACT_PERCENT_OUTPUT.get());
io.setRollerOutput(state, 0); // } else {
} // io.setRollerOutput(state, 0);
// }
break; break;
case Idle: case Idle:
io.armOutput(0); io.armOutput(0);
io.setRollerOutput(state, 0); io.setRollerOutput(state, 0);
break; break;
case ExpelBalls:
io.armOutput(0);
io.setRollerOutput(state, -0.2);
break;
} }
// if (state.retractedLimit){ // if (state.retractedLimit){
// this.mode = IntakeMode.Retracted; // this.mode = IntakeMode.Retracted;
@@ -28,15 +28,15 @@ public class IntakeConstants {
public static final ConfigurableDouble INTAKE_BOUNCE_HALF_PERIOD = new ConfigurableDouble("Bounce Half Period", 5.); public static final ConfigurableDouble INTAKE_BOUNCE_HALF_PERIOD = new ConfigurableDouble("Bounce Half Period", 5.);
public static final ConfigurableDouble INTAKE_BOUNCE_OUTPUT = new ConfigurableDouble("Bounce Output", 0.1); public static final ConfigurableDouble INTAKE_BOUNCE_OUTPUT = new ConfigurableDouble("Bounce Output", 0.1);
public static final ConfigurableDouble INTAKE_BOUNCE_MAX_OUTPUT = new ConfigurableDouble("Bounce Max Output", 0.2); public static final ConfigurableDouble INTAKE_BOUNCE_MAX_OUTPUT = new ConfigurableDouble("Bounce Max Output", 0.2);
public static final ConfigurableDouble INTAKE_BOUNCE_CURRENT_LIMIT = new ConfigurableDouble("Intake Bounce Current Limit", 16); public static final ConfigurableDouble INTAKE_BOUNCE_CURRENT_LIMIT = new ConfigurableDouble("Intake Bounce Current Limit", 30);
public static final ConfigurableDouble INTAKE_BOUNCE_VELOCITY_LIMIT = new ConfigurableDouble("Intake Bounce Velocity Limit", 4); public static final ConfigurableDouble INTAKE_BOUNCE_VELOCITY_LIMIT = new ConfigurableDouble("Intake Bounce Velocity Limit", 4);
//squeeze constants //squeeze constants
public static final ConfigurableDouble INTAKE_SQUEEZE_CURRENT_LOWER_THRESHOLD = new ConfigurableDouble("Intake Squeeze Current LOWER THRESHOLD", 20); // public static final ConfigurableDouble INTAKE_SQUEEZE_CURRENT_LOWER_THRESHOLD = new ConfigurableDouble("Intake Squeeze Current LOWER THRESHOLD", 20);
public static final ConfigurableDouble INTAKE_SQUEEZE_CURRENT_UPPER_THRESHOLD = new ConfigurableDouble("Intake Squeeze Current UPPER THRESHOLD", 25); // public static final ConfigurableDouble INTAKE_SQUEEZE_CURRENT_UPPER_THRESHOLD = new ConfigurableDouble("Intake Squeeze Current UPPER THRESHOLD", 25);
public static final ConfigurableDouble ARM_SQUEEZE_PERCENT_OUTPUT = new ConfigurableDouble("Arm squeeze % output", -0.1); public static final ConfigurableDouble ARM_SQUEEZE_PERCENT_OUTPUT = new ConfigurableDouble("Arm squeeze % output", -0.2);
public static final ConfigurableDouble ARM_REDUCED_SQUEEZE_PERCENT_OUTPUT = new ConfigurableDouble("Arm reduce squeeze % output", -0.02); public static final ConfigurableDouble ARM_REDUCED_SQUEEZE_PERCENT_OUTPUT = new ConfigurableDouble("Arm reduce squeeze % output", 0.02);
//IDs //IDs
@@ -57,7 +57,7 @@ public class IntakeConstants {
public static final ConfigurableDouble ARM_LIMIT_RETRACTED = new ConfigurableDouble("Arm angle retracted", 0.); public static final ConfigurableDouble ARM_LIMIT_RETRACTED = new ConfigurableDouble("Arm angle retracted", 0.);
public static final ConfigurableDouble ARM_LIMIT_EXTENDED = new ConfigurableDouble("Arm angle extended", 1.75); public static final ConfigurableDouble ARM_LIMIT_EXTENDED = new ConfigurableDouble("Arm angle extended", 1.75);
public static final ConfigurableDouble ARM_EXTEND_PERCENT_OUTPUT = new ConfigurableDouble("Arm extend % output", 0.2); public static final ConfigurableDouble ARM_EXTEND_PERCENT_OUTPUT = new ConfigurableDouble("Arm extend % output", 0.4);
public static final ConfigurableDouble ARM_RETRACT_PERCENT_OUTPUT = new ConfigurableDouble("Arm retract % output", -0.2); public static final ConfigurableDouble ARM_RETRACT_PERCENT_OUTPUT = new ConfigurableDouble("Arm retract % output", -0.2);
public static final ConfigurableDouble ARM_REVERSE_ROLLER_RANGE = new ConfigurableDouble("Arm reverse roller range", 1.17); public static final ConfigurableDouble ARM_REVERSE_ROLLER_RANGE = new ConfigurableDouble("Arm reverse roller range", 1.17);
@@ -122,7 +122,7 @@ public class IntakeConstants {
// ).withMotorOutput( // ).withMotorOutput(
// new MotorOutputConfigs() // new MotorOutputConfigs()
// .withNeutralMode(NeutralModeValue.Brake) // Must be break because this has to be accurate // .withNeutralMode(NeutralModeValue.Brake) // Must be break because this has to be accurate
// .withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means // .withDutyCycleNeutralDeadband(0.04) // This sets the minimum output of motor so if its less than 4% it wont move
// ); // );
public static final TalonFXConfiguration ROLLER_MOTOR_CONFIG = new TalonFXConfiguration() public static final TalonFXConfiguration ROLLER_MOTOR_CONFIG = new TalonFXConfiguration()
@@ -133,6 +133,6 @@ public class IntakeConstants {
).withMotorOutput( ).withMotorOutput(
new MotorOutputConfigs() new MotorOutputConfigs()
.withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny .withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny
.withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means .withDutyCycleNeutralDeadband(0.04) // This sets the minimum output of motor so if its less than 4% it wont move
); );
} }
@@ -1,27 +1,15 @@
package frc4388.robot.subsystems.intake; package frc4388.robot.subsystems.intake;
import static edu.wpi.first.units.Units.Amps; import static edu.wpi.first.units.Units.Amps;
import static edu.wpi.first.units.Units.Rotation;
import static edu.wpi.first.units.Units.Rotations; import static edu.wpi.first.units.Units.Rotations;
import static edu.wpi.first.units.Units.RotationsPerSecond; import static edu.wpi.first.units.Units.RotationsPerSecond;
import static edu.wpi.first.units.Units.RotationsPerSecondPerSecond;
import com.ctre.phoenix6.controls.DutyCycleOut;
import com.ctre.phoenix6.controls.PositionDutyCycle;
import com.ctre.phoenix6.controls.PositionVoltage;
import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.hardware.TalonFX;
import com.revrobotics.PersistMode; import com.revrobotics.PersistMode;
import com.revrobotics.ResetMode; import com.revrobotics.ResetMode;
import com.revrobotics.spark.SparkMax; import com.revrobotics.spark.SparkMax;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.units.measure.Acceleration;
import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.units.measure.Velocity;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.DutyCycleEncoder;
import frc4388.robot.subsystems.shooter.ShooterConstants;
import frc4388.utility.compute.JankCoder; import frc4388.utility.compute.JankCoder;
public class IntakeReal implements IntakeIO { public class IntakeReal implements IntakeIO {
@@ -114,7 +102,7 @@ public class IntakeReal implements IntakeIO {
state.armMotorCurrent = Amps.of(m_armMotor.getOutputCurrent()); state.armMotorCurrent = Amps.of(m_armMotor.getOutputCurrent());
state.rollerOutput = m_rollerMotor.get(); state.rollerOutput = m_rollerMotor.get();
// state.rollerMotorCurrent = Amps.of(m_rollerMotor.getOutputCurrent()); state.rollerMotorCurrent = m_rollerMotor.getStatorCurrent().getValue();
state.retractedSoftLimit = retractedLimit(); state.retractedSoftLimit = retractedLimit();
state.extendedSoftLimit = extendedLimit(); state.extendedSoftLimit = extendedLimit();
@@ -16,7 +16,7 @@ public class ShooterConstants {
// Motor conversions // Motor conversions
public static final double SHOOTERMOTOR_GEAR_RATIO = 1.286; // TODO: supposed to be 9 rotations in to 7 out -- 0.77 or 1.29 public static final double SHOOTERMOTOR_GEAR_RATIO = 1.286; // TODO: supposed to be 9 rotations in to 7 out -- 0.77 or 1.29
public static final double INDEXER_GEAR_RATIO = 1.72; // TODO: change it is supposed to be 18 to 31 // public static final double INDEXER_GEAR_RATIO = 1.;
public static final double T_CONSTANT = 2; public static final double T_CONSTANT = 2;
public static final double SHOOTER_RADIUS = 2/39.37; public static final double SHOOTER_RADIUS = 2/39.37;
public static final double INDEXER_RADIUS = 0.625/39.37; public static final double INDEXER_RADIUS = 0.625/39.37;
@@ -116,7 +116,7 @@ public class ShooterConstants {
).withMotorOutput( ).withMotorOutput(
new MotorOutputConfigs() new MotorOutputConfigs()
.withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny .withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny
.withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means .withDutyCycleNeutralDeadband(0.04) // This sets the minimum output of motor so if its less than 4% it wont move
); );
public static final TalonFXConfiguration SHOOTER2_MOTOR_CONFIG = new TalonFXConfiguration() public static final TalonFXConfiguration SHOOTER2_MOTOR_CONFIG = new TalonFXConfiguration()
.withCurrentLimits( .withCurrentLimits(
@@ -126,7 +126,7 @@ public class ShooterConstants {
).withMotorOutput( ).withMotorOutput(
new MotorOutputConfigs() new MotorOutputConfigs()
.withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny .withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny
.withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means .withDutyCycleNeutralDeadband(0.04) // This sets the minimum output of motor so if its less than 4% it wont move
); );
public static final TalonFXConfiguration INDEXER_MOTOR_CONFIG = new TalonFXConfiguration() public static final TalonFXConfiguration INDEXER_MOTOR_CONFIG = new TalonFXConfiguration()
@@ -137,6 +137,6 @@ public class ShooterConstants {
).withMotorOutput( ).withMotorOutput(
new MotorOutputConfigs() new MotorOutputConfigs()
.withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny .withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny
.withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means .withDutyCycleNeutralDeadband(0.04) // This sets the minimum output of motor so if its less than 4% it wont move
); );
} }