diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 2559999..77ee3f6 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -134,7 +134,7 @@ public class RobotContainer { private Command RobotRev = new SequentialCommandGroup( new InstantCommand(() -> m_robotShooter.spinUpShooting(), m_robotShooter), IntakeExtended, - new InstantCommand(() -> m_robotIntake.setMode(IntakeMode.RollerStop), m_robotIntake) + new InstantCommand(() -> m_robotIntake.setMode(IntakeMode.Idle), m_robotIntake) ); private Command RobotShootDriving = new SequentialCommandGroup( diff --git a/src/main/java/frc4388/robot/RobotMap.java b/src/main/java/frc4388/robot/RobotMap.java index b3dc909..cc680c3 100644 --- a/src/main/java/frc4388/robot/RobotMap.java +++ b/src/main/java/frc4388/robot/RobotMap.java @@ -13,6 +13,7 @@ import org.photonvision.PhotonCamera; import com.ctre.phoenix6.hardware.CANcoder; import com.ctre.phoenix6.swerve.SwerveDrivetrain; +import com.revrobotics.spark.SparkMax; import edu.wpi.first.wpilibj.DigitalInput; import frc4388.robot.constants.Constants; @@ -98,7 +99,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); + SparkMax roller = new SparkMax(IntakeConstants.ROLLER_ID.id, com.revrobotics.spark.SparkLowLevel.MotorType.kBrushless); 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); @@ -118,7 +119,7 @@ public class RobotMap { FaultTalonFX.addDevice(shooter2, "Shooter2"); FaultTalonFX.addDevice(indexer, "Indexer"); FaultTalonFX.addDevice(arm, "Arm"); - FaultTalonFX.addDevice(roller, "Roller"); + // FaultTalonFX.addDevice(roller, "Roller"); FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getDriveMotor(), "Module 0 Drive"); FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getSteerMotor(), "Module 0 Steer"); diff --git a/src/main/java/frc4388/robot/constants/BuildConstants.java b/src/main/java/frc4388/robot/constants/BuildConstants.java index 57f5e5e..d7cb571 100644 --- a/src/main/java/frc4388/robot/constants/BuildConstants.java +++ b/src/main/java/frc4388/robot/constants/BuildConstants.java @@ -7,13 +7,13 @@ public final class BuildConstants { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "2026KPopRobotHunters-new"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 183; - public static final String GIT_SHA = "d639b3076d10f39eb5bc18c42c3dc5e707e991ff"; - public static final String GIT_DATE = "2026-03-21 15:49:44 MDT"; + public static final int GIT_REVISION = 184; + public static final String GIT_SHA = "c6b0d29acdb24728ed566b25d6434a45fbd963c7"; + public static final String GIT_DATE = "2026-03-25 11:15:46 MDT"; public static final String GIT_BRANCH = "New-Intake"; - public static final String BUILD_DATE = "2026-03-23 10:56:08 MDT"; - public static final long BUILD_UNIX_TIME = 1774284968618L; - public static final int DIRTY = 0; + public static final String BUILD_DATE = "2026-03-25 11:17:58 MDT"; + public static final long BUILD_UNIX_TIME = 1774459078868L; + public static final int DIRTY = 1; private BuildConstants(){} } diff --git a/src/main/java/frc4388/robot/subsystems/intake/Intake.java b/src/main/java/frc4388/robot/subsystems/intake/Intake.java index 21782aa..b73cb8f 100644 --- a/src/main/java/frc4388/robot/subsystems/intake/Intake.java +++ b/src/main/java/frc4388/robot/subsystems/intake/Intake.java @@ -30,6 +30,8 @@ public class Intake extends SubsystemBase { public enum IntakeMode { Extended, Retracted, + Extending, + Retracting, Idle, Bouncing } @@ -101,6 +103,14 @@ public class Intake extends SubsystemBase { io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_LIMIT_RETRACTED.get())); io.setRollerOutput(state, 0); break; + case Extending: + io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_EXTEND_PERCENT_OUTPUT.get())); + io.setRollerOutput(state, IntakeConstants.ROLLER_PERCENT_OUTPUT.get()); + break; + case Retracting: + io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_RETRACT_PERCENT_OUTPUT.get())); + io.setRollerOutput(state, 0); + break; case Bouncing: io.setRollerOutput(state, 0); diff --git a/src/main/java/frc4388/robot/subsystems/intake/IntakeReal.java b/src/main/java/frc4388/robot/subsystems/intake/IntakeReal.java index 820ae3e..1e13f86 100644 --- a/src/main/java/frc4388/robot/subsystems/intake/IntakeReal.java +++ b/src/main/java/frc4388/robot/subsystems/intake/IntakeReal.java @@ -1,11 +1,13 @@ package frc4388.robot.subsystems.intake; +import static edu.wpi.first.units.Units.Amps; import static edu.wpi.first.units.Units.Rotations; 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.revrobotics.spark.SparkMax; import edu.wpi.first.math.trajectory.TrapezoidProfile; import edu.wpi.first.math.util.Units; @@ -17,7 +19,7 @@ import edu.wpi.first.wpilibj.DigitalInput; public class IntakeReal implements IntakeIO { TalonFX m_armMotor; - TalonFX m_rollerMotor; + SparkMax m_rollerMotor; DigitalInput m_armLimitSwitch; PositionDutyCycle armPosition = new PositionDutyCycle(0); @@ -26,7 +28,7 @@ public class IntakeReal implements IntakeIO { public IntakeReal( DigitalInput armLimitSwitch, TalonFX armMotor, - TalonFX rollerMotor + SparkMax rollerMotor ) { // m_angleMotor = angleMotor; // m_pitchMotor = pitchMotor; @@ -37,7 +39,7 @@ public class IntakeReal implements IntakeIO { // Apply the configs m_armMotor.getConfigurator().apply(IntakeConstants.ARM_PID); m_armMotor.getConfigurator().apply(IntakeConstants.ARM_MOTOR_CONFIG); - m_rollerMotor.getConfigurator().apply(IntakeConstants.ROLLER_MOTOR_CONFIG); + // m_rollerMotor.getConfigurator().apply(IntakeConstants.ROLLER_MOTOR_CONFIG); armPosition.Slot = 0; // rollerVelocity.Slot = 0; @@ -59,11 +61,6 @@ public class IntakeReal implements IntakeIO { public void setRollerOutput(IntakeState state, double rollerOutput) { state.rollerTargetOutput = rollerOutput; - - if(rollerOutput == 0) { - m_rollerMotor.set(0); - return; - } m_rollerMotor.set(rollerOutput); } @@ -133,7 +130,7 @@ public class IntakeReal implements IntakeIO { state.armAngle = m_armMotor.getPosition().getValue().div(IntakeConstants.ARM_MOTOR_GEAR_RATIO); state.armMotorCurrent = m_armMotor.getStatorCurrent().getValue(); state.rollerOutput = m_rollerMotor.get(); - state.rollerMotorCurrent = m_rollerMotor.getStatorCurrent().getValue(); + state.rollerMotorCurrent = Amps.of(m_rollerMotor.getOutputCurrent()); state.retractedLimit = !m_armLimitSwitch.get(); state.armMotorVelocity = m_armMotor.getVelocity().getValue(); diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json new file mode 100644 index 0000000..c6b1b9e --- /dev/null +++ b/vendordeps/REVLib.json @@ -0,0 +1,133 @@ +{ + "fileName": "REVLib.json", + "name": "REVLib", + "version": "2026.0.5", + "frcYear": "2026", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", + "mavenUrls": [ + "https://maven.revrobotics.com/" + ], + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2026.json", + "javaDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2026.0.5" + } + ], + "jniDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2026.0.5", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibBackendDriver", + "version": "2026.0.5", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibWpiBackendDriver", + "version": "2026.0.5", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-cpp", + "version": "2026.0.5", + "libName": "REVLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2026.0.5", + "libName": "REVLibDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibBackendDriver", + "version": "2026.0.5", + "libName": "BackendDriver", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibWpiBackendDriver", + "version": "2026.0.5", + "libName": "REVLibWpi", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ] +} \ No newline at end of file