mirror of
https://github.com/Team4388/2026KPopRobotHunters.git
synced 2026-06-09 00:38:03 -06:00
limit switch through robot map
This commit is contained in:
@@ -59,14 +59,14 @@ public class RobotContainer {
|
||||
public final RobotMap m_robotMap = new RobotMap(Mode.REAL);
|
||||
|
||||
/*Limit Switch */
|
||||
public final DigitalInput m_armLimitSwitch = new DigitalInput(9);
|
||||
// public final DigitalInput m_armLimitSwitch = new DigitalInput(9);
|
||||
|
||||
/* Subsystems */
|
||||
public final LED m_robotLED = new LED(Constants.LEDConstants.LED_SPARK_ID);
|
||||
//Testing of Colors
|
||||
public final Vision m_vision = new Vision();
|
||||
public final SwerveDrive m_robotSwerveDrive = new SwerveDrive(m_robotMap.swerveDrivetrain, m_vision);
|
||||
public final Intake m_robotIntake = new Intake(m_robotMap.intakeIO, m_armLimitSwitch);
|
||||
public final Intake m_robotIntake = new Intake(m_robotMap.intakeIO);
|
||||
public final Shooter m_robotShooter = new Shooter(m_robotMap.shooterIO, m_robotSwerveDrive, m_robotIntake, m_robotLED);
|
||||
|
||||
|
||||
|
||||
@@ -12,6 +12,7 @@ import com.ctre.phoenix6.hardware.TalonFX;
|
||||
import com.ctre.phoenix6.hardware.CANcoder;
|
||||
import com.ctre.phoenix6.swerve.SwerveDrivetrain;
|
||||
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import frc4388.robot.constants.Constants;
|
||||
//import frc4388.robot.constants.Constants.ElevatorConstants;
|
||||
import frc4388.robot.constants.Constants.SimConstants;
|
||||
@@ -91,7 +92,7 @@ public class RobotMap {
|
||||
//Configure Intake 20,21
|
||||
TalonFX arm = new TalonFX(IntakeConstants.ARM_ID.id, Constants.CANIVORE_CANBUS);
|
||||
TalonFX roller = new TalonFX(IntakeConstants.ROLLER_ID.id, Constants.CANIVORE_CANBUS);
|
||||
|
||||
DigitalInput armLimitSwitch = new DigitalInput(IntakeConstants.ARM_LIMIT_SWITCH_CHANNEL);
|
||||
// DigitalInput basinLimitSwitch = new DigitalInput(ElevatorConstants.BASIN_LIMIT_SWITCH);
|
||||
// DigitalInput endeffectorLimitSwitch = new DigitalInput(ElevatorConstants.ENDEFFECTOR_LIMIT_SWITCH);
|
||||
// DigitalInput IRIntakeBeam = new DigitalInput(ElevatorConstants.INTAKE_LIMIT_SWITCH);
|
||||
@@ -100,7 +101,7 @@ public class RobotMap {
|
||||
// shooterIO = new ShooterIO() {};
|
||||
shooterIO = new ShooterReal(shooter1, shooter2, indexer);
|
||||
|
||||
intakeIO = new IntakeReal(arm, roller);
|
||||
intakeIO = new IntakeReal(armLimitSwitch, arm, roller);
|
||||
|
||||
// Fault
|
||||
FaultPidgeon2.addDevice(swerveDrivetrainReal.getPigeon2(), "Gyro");
|
||||
|
||||
@@ -7,12 +7,12 @@ public final class BuildConstants {
|
||||
public static final String MAVEN_GROUP = "";
|
||||
public static final String MAVEN_NAME = "2026KPopRobotHunters";
|
||||
public static final String VERSION = "unspecified";
|
||||
public static final int GIT_REVISION = 52;
|
||||
public static final String GIT_SHA = "736d7ef8233e918aa0cc1cc3f06f2069517bed59";
|
||||
public static final String GIT_DATE = "2026-02-14 13:49:33 MST";
|
||||
public static final String GIT_BRANCH = "shoot-button";
|
||||
public static final String BUILD_DATE = "2026-02-14 14:55:59 MST";
|
||||
public static final long BUILD_UNIX_TIME = 1771106159811L;
|
||||
public static final int GIT_REVISION = 59;
|
||||
public static final String GIT_SHA = "7f251857dc4fc6f925d5900e9822f20c8841fa1d";
|
||||
public static final String GIT_DATE = "2026-02-14 15:05:25 MST";
|
||||
public static final String GIT_BRANCH = "operator-controls";
|
||||
public static final String BUILD_DATE = "2026-02-14 15:56:10 MST";
|
||||
public static final long BUILD_UNIX_TIME = 1771109770332L;
|
||||
public static final int DIRTY = 1;
|
||||
|
||||
private BuildConstants(){}
|
||||
|
||||
@@ -16,15 +16,12 @@ public class Intake extends SubsystemBase {
|
||||
IntakeStateAutoLogged state = new IntakeStateAutoLogged();
|
||||
|
||||
Supplier<Pose2d> m_swervePoseSupplier;
|
||||
public DigitalInput m_armLimitSwitch;
|
||||
|
||||
public Intake(
|
||||
IntakeIO io,
|
||||
DigitalInput m_armLimitSwitch
|
||||
IntakeIO io
|
||||
// Supplier<Pose2d> swervePoseSupplier
|
||||
) {
|
||||
this.io = io;
|
||||
this.m_armLimitSwitch= m_armLimitSwitch;
|
||||
// this.m_swervePoseSupplier = swervePoseSupplier;
|
||||
}
|
||||
|
||||
@@ -76,8 +73,7 @@ public class Intake extends SubsystemBase {
|
||||
io.setRollerVelocity(state, RotationsPerSecond.of(IntakeConstants.ROLLER_ACTIVE.get()));
|
||||
break;
|
||||
case Retracted:
|
||||
if (!m_armLimitSwitch.get()){
|
||||
System.out.println("Triggered!");
|
||||
if (!state.retractedLimit){
|
||||
io.stopArm();
|
||||
} else {
|
||||
io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_LIMIT_RETRACTED.get()));
|
||||
@@ -88,7 +84,11 @@ public class Intake extends SubsystemBase {
|
||||
io.armExtend(IntakeConstants.ARM_EXTEND_PERCENT_OUTPUT.get());
|
||||
break;
|
||||
case Retracting:
|
||||
io.armRetract(IntakeConstants.ARM_RETRACT_PERCENT_OUTPUT.get());
|
||||
if (!state.retractedLimit){
|
||||
io.stopArm();
|
||||
} else {
|
||||
io.armRetract(IntakeConstants.ARM_RETRACT_PERCENT_OUTPUT.get());
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
@@ -21,6 +21,7 @@ public class IntakeConstants {
|
||||
|
||||
public static final CanDevice ARM_ID = new CanDevice("ARM", 20);
|
||||
public static final CanDevice ROLLER_ID = new CanDevice("INTAKE_ROLLER", 21);
|
||||
public static final int ARM_LIMIT_SWITCH_CHANNEL = 9;
|
||||
|
||||
// Limits
|
||||
|
||||
|
||||
@@ -13,6 +13,7 @@ import edu.wpi.first.units.measure.Current;
|
||||
public interface IntakeIO {
|
||||
@AutoLog
|
||||
public class IntakeState {
|
||||
boolean retractedLimit = false;
|
||||
Angle armAngle = Rotations.of(0);
|
||||
Angle armTargetAngle = Rotations.of(0);
|
||||
Current armMotorCurrent = Amps.of(0);
|
||||
|
||||
@@ -5,18 +5,20 @@ import com.ctre.phoenix6.controls.VelocityDutyCycle;
|
||||
import com.ctre.phoenix6.hardware.TalonFX;
|
||||
|
||||
import edu.wpi.first.units.measure.*;
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.DigitalOutput;
|
||||
|
||||
public class IntakeReal implements IntakeIO {
|
||||
|
||||
|
||||
TalonFX m_armMotor;
|
||||
TalonFX m_rollerMotor;
|
||||
DigitalInput m_armLimitSwitch;
|
||||
|
||||
PositionDutyCycle armPosition = new PositionDutyCycle(0);
|
||||
VelocityDutyCycle rollerVelocity = new VelocityDutyCycle(0);
|
||||
|
||||
public IntakeReal(
|
||||
|
||||
DigitalInput armLimitSwitch,
|
||||
TalonFX armMotor,
|
||||
TalonFX rollerMotor
|
||||
) {
|
||||
@@ -24,6 +26,7 @@ public class IntakeReal implements IntakeIO {
|
||||
// m_pitchMotor = pitchMotor;
|
||||
m_armMotor = armMotor;
|
||||
m_rollerMotor = rollerMotor;
|
||||
m_armLimitSwitch = armLimitSwitch;
|
||||
|
||||
// Apply the configs
|
||||
m_armMotor.getConfigurator().apply(IntakeConstants.ARM_PID);
|
||||
@@ -96,7 +99,7 @@ public class IntakeReal implements IntakeIO {
|
||||
public void updateInputs(IntakeState state) {
|
||||
state.armAngle = m_armMotor.getPosition().getValue().div(IntakeConstants.ARM_MOTOR_GEAR_RATIO);
|
||||
state.armMotorCurrent = m_armMotor.getStatorCurrent().getValue();
|
||||
|
||||
state.retractedLimit = m_armLimitSwitch.get();
|
||||
state.rollerVelocity = m_rollerMotor.getVelocity().getValue().div(IntakeConstants.ROLLER_MOTOR_GEAR_RATIO);
|
||||
state.rollerMotorCurrent = m_rollerMotor.getStatorCurrent().getValue();
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user