Skip to content
This repository has been archived by the owner on May 19, 2024. It is now read-only.

Commit

Permalink
feat: Working shooting.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Mar 15, 2024
1 parent d04ec44 commit 5cdee84
Show file tree
Hide file tree
Showing 6 changed files with 7 additions and 8 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/RobotConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -53,5 +53,5 @@ public enum Subsystem {
Subsystem.SHOOTER,
Subsystem.SWERVE);

public static final Set<Subsystem> REAL_SUBSYSTEMS = EnumSet.of(Subsystem.ODOMETRY, Subsystem.SWERVE);
public static final Set<Subsystem> REAL_SUBSYSTEMS = ALL_SUBSYSTEMS;
}
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/arm/ArmState.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@ public record ArmState(State shoulder, State wrist) {
public static final ArmState STOW =
new ArmState(ShoulderMotorConstants.MINIMUM_ANGLE, WristMotorConstants.MAXIMUM_ANGLE);

public static final ArmState SHOOT = STOW.withWrist(Rotation2d.fromDegrees(18));
public static final ArmState SHOOT = STOW.withWrist(WristMotorConstants.MAXIMUM_ANGLE.plus(Rotation2d.fromDegrees(-65)));

public static final ArmState INTAKE = STOW.withWrist(Rotation2d.fromDegrees(4));
public static final ArmState INTAKE = STOW.withWrist(WristMotorConstants.MAXIMUM_ANGLE.plus(Rotation2d.fromDegrees(-79)));

public static final ArmState AMP =
new ArmState(ShoulderMotorConstants.MAXIMUM_ANGLE, Rotation2d.fromDegrees(0));
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/arm/ShoulderMotorIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ public class ShoulderMotorIOSparkMax implements ShoulderMotorIO {

/** Creates a new shoulder motor using a Spark Max. */
public ShoulderMotorIOSparkMax() {
sparkMax = new CANSparkMax(ShoulderMotorConstants.CAN.id(), MotorType.kBrushless);
sparkMax = new CANSparkMax(1, MotorType.kBrushless);

feedback = new PIDController(ShoulderMotorConstants.KP, 0, 0);

Expand Down
3 changes: 1 addition & 2 deletions src/main/java/frc/robot/arm/WristMotorIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,7 @@ public class WristMotorIOSparkMax implements WristMotorIO {
private final AccelerationCalculator accelerationCalculator;

public WristMotorIOSparkMax() {
// TODO test, use dedicated wrist SparkMAX
sparkMax = new CANSparkMax(1, MotorType.kBrushless);
sparkMax = new CANSparkMax(2, MotorType.kBrushless);

feedback = new PIDController(WristMotorConstants.KP, 0, 0);

Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/auto/Auto.java
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,7 @@ public Command readyIntake() {
}

public Command intakeNote() {
return readyIntake().andThen(Commands.parallel(intake.intake(), shooter.intake()));
return readyIntake().andThen(intake.intake());
}

public Command stow() {
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/intake/IntakeConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ public static class PivotMotorConstants {
public static final double DISTANCE = Units.inchesToMeters(10.275);

/** Pivot motor's minimum angle. */
public static final Rotation2d MINIMUM_ANGLE = Rotation2d.fromDegrees(-48);
public static final Rotation2d MINIMUM_ANGLE = Rotation2d.fromDegrees(-40);

/** Pivot motor's maximum angle. */
public static final Rotation2d MAXIMUM_ANGLE = Rotation2d.fromDegrees(86);
Expand Down

0 comments on commit 5cdee84

Please sign in to comment.