Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 13 additions & 0 deletions src/main/deploy/tuning/arc.json
Original file line number Diff line number Diff line change
Expand Up @@ -116,6 +116,19 @@
"velocity": 70.0
}
]
},
{
"hood": 45.0,
"points": [
{
"distance": 5.5,
"velocity": 65
},
{
"distance": 6.5,
"velocity": 65
}
]
}
]
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/RobotState.java
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ public static void periodic() {
? ShooterConstants.Positions.blueAllianceWall
: ShooterConstants.Positions.redAllianceWall;

inAllianceZone = currentPose.getMeasureX().minus(allianceWall).abs(Meters) < ShooterConstants.Positions.spinUpZone.in(Meters);
inAllianceZone = currentPose.getMeasureX().minus(allianceWall).abs(Meters) < ShooterConstants.Positions.allianceZone.in(Meters);

// Other logging
var shift = HubShiftUtil.getOfficialShiftInfo();
Expand Down
23 changes: 20 additions & 3 deletions src/main/java/frc/robot/commands/robot/RobotCommands.java
Original file line number Diff line number Diff line change
Expand Up @@ -69,11 +69,18 @@ public static Command shootHubNoAim(Shooter shooter, Hopper hopper, IntakeSubsys
BooleanSupplier shouldStopShooting =
() -> !drive.rotationIsNear(RobotState.rotationToHub(), ShooterConstants.defenseTolerance);

BooleanSupplier upToSpeedAndAimed =
() -> shouldShoot.getAsBoolean() && shooter.isShooterReady();

return Commands.repeatingSequence(
Commands.waitUntil(shouldShoot),
Commands.waitUntil(upToSpeedAndAimed),
hopper.feedForShooting(shouldShoot, intake)
.until(shouldStopShooting)
).alongWith(shooter.shootAtDistance(RobotState::hubDistance));
).alongWith(
Commands.waitUntil(upToSpeedAndAimed)
.deadlineFor(shooter.spinUpForDistance(RobotState::hubDistance))
.andThen(shooter.shootAtDistance(RobotState::hubDistance))
);
}

/**
Expand Down Expand Up @@ -107,9 +114,19 @@ public static Command ferry(Shooter shooter, Hopper hopper, IntakeSubsystem inta
return new Rotation2d(botToTarget.getX(), botToTarget.getY());
};

BooleanSupplier ready = () ->
drive.rotationIsNear(targetingAngle.get(), ShooterConstants.aimingTolerance)
&& shooter.isShooterReady();

return DriveCommands.joystickDriveAtAngle(targetingAngle)
.alongWith(
shooter.shootAtDistance(targetDistance),
Commands.waitUntil(ready)
.deadlineFor(shooter.spinUpForDistance(targetDistance))
.andThen(shooter.shootAtDistance(targetDistance)),

Commands.waitUntil(ready)
.andThen(hopper.feedForShooting(() -> true, intake)),

Commands.runOnce(() -> {
Logger.recordOutput("Ferry/Target", target.get());
Logger.recordOutput("Ferry/IsFerrying", true);
Expand Down
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/subsystems/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -254,7 +254,9 @@ public Command shootAtDistance(Supplier<Distance> distance) {
() -> RotationsPerSecond.of(shooterParams.get().velocity),
() -> Degrees.of(shooterParams.get().hood)
)
).finallyDo(interrupted -> Logger.recordOutput("Command/ShootAtDistance", false));
)
.finallyDo(interrupted -> Logger.recordOutput("Command/ShootAtDistance", false))
.deadlineFor(Commands.run(() -> Logger.recordOutput("Shooter/ShotDistance", distance.get())));
}

/**
Expand Down
11 changes: 5 additions & 6 deletions src/main/java/frc/robot/subsystems/shooter/ShooterConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ public class ShooterConstants {
public static final int shooter2CANID = 1;
public static final int shooter3CANID = 2;

public static final Current currentLimit = Amps.of(60);
public static final Current currentLimit = Amps.of(50);
public static final Time currentLimitTime = Seconds.of(0.2);

//
Expand Down Expand Up @@ -84,16 +84,15 @@ public class Positions {
public static final Translation2d redHubPose = new Translation2d(11.938,4.034536);

public static final Distance allianceZone = Meters.of(4.5974);
public static final Distance spinUpZone = Meters.of(6.0);

public static final Distance blueAllianceWall = Meters.of(0);
public static final Distance redAllianceWall = Meters.of(FieldConstants.layout.getFieldLength());

public static final Translation2d blueTargetLeft = new Translation2d(2,6);
public static final Translation2d blueTargetRight = new Translation2d(2,2);
public static final Translation2d blueTargetLeft = new Translation2d(1,6);
public static final Translation2d blueTargetRight = new Translation2d(1,2);

public static final Translation2d redTargetLeft = new Translation2d(14,6);
public static final Translation2d redTargetRight = new Translation2d(14,2);
public static final Translation2d redTargetLeft = new Translation2d(15,6);
public static final Translation2d redTargetRight = new Translation2d(15,2);

public static final double centerLineY = 4.034536;
}
Expand Down
Loading