Skip to content

Commit

Permalink
proto intake
Browse files Browse the repository at this point in the history
  • Loading branch information
GearBoxFox committed Jan 12, 2025
1 parent 3247b42 commit 768e85f
Show file tree
Hide file tree
Showing 9 changed files with 70 additions and 16 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2025.1.1"
id "edu.wpi.first.GradleRIO" version "2025.2.1"
id "io.freefair.lombok" version "8.4"
id "com.peterabeles.gversion" version "1.10"
id "org.sonarqube" version "4.4.1.3373"
Expand Down
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/BuildConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,12 @@ public final class BuildConstants {
public static final String MAVEN_GROUP = "";
public static final String MAVEN_NAME = "2025Reefscape";
public static final String VERSION = "unspecified";
public static final int GIT_REVISION = 35;
public static final String GIT_SHA = "8674f2facd6148db82f6d5a34d2d6eb8c13f0b3c";
public static final String GIT_DATE = "2025-01-10 21:32:01 EST";
public static final int GIT_REVISION = 38;
public static final String GIT_SHA = "3247b4284f4e00bc01d2ba380d636b3d9f9fb3d4";
public static final String GIT_DATE = "2025-01-12 13:32:06 EST";
public static final String GIT_BRANCH = "intake";
public static final String BUILD_DATE = "2025-01-11 16:11:33 EST";
public static final long BUILD_UNIX_TIME = 1736629893778L;
public static final String BUILD_DATE = "2025-01-12 16:15:02 EST";
public static final long BUILD_UNIX_TIME = 1736716502078L;
public static final int DIRTY = 1;

private BuildConstants(){}
Expand Down
29 changes: 27 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,9 @@
import frc.robot.subsystems.drive.module.ModuleIO;
import frc.robot.subsystems.drive.module.ModuleIOSim;
import frc.robot.subsystems.drive.module.ModuleIOSparkMax;
import frc.robot.subsystems.intake.IntakeIO;
import frc.robot.subsystems.intake.IntakeIOProto;
import frc.robot.subsystems.intake.IntakeSubsystem;
import org.ironmaple.simulation.SimulatedArena;
import org.ironmaple.simulation.drivesims.SwerveDriveSimulation;
import org.littletonrobotics.junction.Logger;
Expand All @@ -23,16 +26,20 @@ public class RobotContainer {
private final CommandXboxController driveController = new CommandXboxController(0);

DriveSubsystem driveSubsystem;
private final IntakeSubsystem intakeSubsystem;

public RobotContainer() {
switch (Constants.getMode()) {
case REAL ->
case REAL -> {
driveSubsystem = new DriveSubsystem(
new GyroIOPigeon2(),
new ModuleIOSparkMax(DriveConstants.MODULE_CONSTANTS[0]),
new ModuleIOSparkMax(DriveConstants.MODULE_CONSTANTS[1]),
new ModuleIOSparkMax(DriveConstants.MODULE_CONSTANTS[2]),
new ModuleIOSparkMax(DriveConstants.MODULE_CONSTANTS[3])
);
intakeSubsystem = new IntakeSubsystem(new IntakeIOProto());
}

case SIM -> {
driveSimulation = new SwerveDriveSimulation(DriveConstants.MAPLE_SIM_CONFIG, new Pose2d(3, 3, new Rotation2d()));
Expand All @@ -46,8 +53,10 @@ public RobotContainer() {
);

SimulatedArena.getInstance().resetFieldForAuto();

intakeSubsystem = new IntakeSubsystem(new IntakeIO() {});
}
case REPLAY ->
case REPLAY -> {
driveSubsystem = new DriveSubsystem(
new GyroIO() {
},
Expand All @@ -56,6 +65,11 @@ public RobotContainer() {
new ModuleIO() {},
new ModuleIO() {}
);
intakeSubsystem = new IntakeSubsystem(new IntakeIO() {});
}
default -> {
intakeSubsystem = new IntakeSubsystem(new IntakeIO() {});
}
}
configureBindings();
}
Expand All @@ -67,6 +81,17 @@ private void configureBindings() {
() -> -driveController.getLeftX(),
() -> -driveController.getRightX()
));

driveController.a().whileTrue(
Commands.run(() -> intakeSubsystem.setIntakePower(6.0), intakeSubsystem)
).whileFalse(
Commands.run(() -> intakeSubsystem.setIntakePower(0.0))
);
driveController.b().whileTrue(
Commands.run(() -> intakeSubsystem.setIntakePower(-6.0), intakeSubsystem)
).whileFalse(
Commands.run(() -> intakeSubsystem.setIntakePower(0.0))
);
}

public Command getAutonomousCommand() {
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/drive/DriveConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ public class DriveConstants {
.driveId(4)
.steerId(5)
.encoderId(6)
.encoderOffset(Rotation2d.fromDegrees(-101.60).unaryMinus())
.encoderOffset(Rotation2d.fromDegrees(-101.60).unaryMinus().plus(Rotation2d.k180deg))
.steerInverted(true)
.turnInverted(false)
.build(),
Expand All @@ -87,7 +87,7 @@ public class DriveConstants {
.driveId(10)
.steerId(11)
.encoderId(12)
.encoderOffset(Rotation2d.fromDegrees(60.20).unaryMinus())
.encoderOffset(Rotation2d.fromDegrees(60.20).unaryMinus().plus(Rotation2d.k180deg))
.steerInverted(true)
.turnInverted(false)
.build()
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.robot.subsystems.drive.intake;
package frc.robot.subsystems.intake;

public class IntakeConstants {
public static final int INTAKE_ID = 0;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.robot.subsystems.drive.intake;
package frc.robot.subsystems.intake;

import edu.wpi.first.math.geometry.Rotation2d;
import org.littletonrobotics.junction.AutoLog;
Expand All @@ -11,7 +11,7 @@ class IntakeIOInputs {
public double pivotVoltage = 0.0;
public double intakeVoltage = 0.0;
public double pivotDraw = 0.0;
public double intakeDraw = 0.0;
public double intakeCurrentDraw = 0.0;
public double pivotAppliedVolts = 0.0;
public double intakeAppliedVolts = 0.0;
public double pivotTemperature = 0.0;
Expand Down
29 changes: 29 additions & 0 deletions src/main/java/frc/robot/subsystems/intake/IntakeIOProto.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
package frc.robot.subsystems.intake;

import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.NeutralModeValue;

public class IntakeIOProto implements IntakeIO {
private final TalonFX intake;

public IntakeIOProto() {
intake = new TalonFX(17);

var config = new TalonFXConfiguration();
config.MotorOutput.NeutralMode = NeutralModeValue.Brake;

intake.getConfigurator().apply(config);
}

@Override
public void updateInputs(IntakeIOInputsAutoLogged inputs) {
inputs.intakeAppliedVolts = intake.getMotorVoltage().getValueAsDouble();
inputs.intakeCurrentDraw = intake.getSupplyCurrent().getValueAsDouble();
}

@Override
public void setMotorVoltageIntake(double voltage) {
intake.setVoltage(voltage);
}
}
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.robot.subsystems.drive.intake;
package frc.robot.subsystems.intake;

import com.ctre.phoenix6.BaseStatusSignal;
import com.ctre.phoenix6.StatusSignal;
Expand Down Expand Up @@ -104,7 +104,7 @@ public void updateInputs (IntakeIOInputsAutoLogged inputs){
);
inputs.intakeVoltage = intakeVoltageSignal.refresh().getValueAsDouble();
inputs.pivotVoltage = pivotVoltageSignal.refresh().getValueAsDouble();
inputs.intakeDraw = intakeDrawSignal.refresh().getValueAsDouble();
inputs.intakeCurrentDraw = intakeDrawSignal.refresh().getValueAsDouble();
inputs.pivotDraw = pivotDrawSignal.refresh().getValueAsDouble();
inputs.intakeAppliedVolts = intakeAppliedVoltsSignal.refresh().getValueAsDouble();
inputs.pivotAppliedVolts = pivotAppliedVoltsSignal.refresh().getValueAsDouble();
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.robot.subsystems.drive.intake;
package frc.robot.subsystems.intake;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
Expand Down

0 comments on commit 768e85f

Please sign in to comment.