Skip to content
Merged
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
6 changes: 5 additions & 1 deletion src/main/java/frc/robot/Autos.java
Original file line number Diff line number Diff line change
Expand Up @@ -505,7 +505,7 @@ public Command getDepotClimbAuto() {
lockHoodUnderTrench(routine, TrenchPoses.getClosestTrenchPose(swerve.getPose()), 1);
Path[] paths = {Path.PLtoD, Path.DtoCL};
Command autoCommand =
paths[0].getTrajectory(routine).resetOdometry().alongWith(setleftClimbAutoFalse());
paths[0].getTrajectory(routine).resetOdometry().alongWith(setleftClimbAutoTrue());

for (Path p : paths) {
autoCommand = autoCommand.andThen(runPath(p, routine));
Expand Down Expand Up @@ -548,4 +548,8 @@ public Command getTestAuto() {
public Command waitUntilEmpty() {
return Commands.waitSeconds(3.0);
}

public Command getJustScoreAuto() {
return setAutoScoreReqTrue().andThen(Commands.waitSeconds(5)).andThen(setAutoScoreReqFalse());
}
}
69 changes: 37 additions & 32 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,6 @@
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.RobotModeTriggers;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.Superstructure.SuperState;
import frc.robot.components.cancoder.CANcoderIO;
import frc.robot.components.cancoder.CANcoderIOSim;
import frc.robot.components.candle.CANdleIOReal;
Expand Down Expand Up @@ -69,6 +68,7 @@
import frc.robot.subsystems.swerve.odometry.PhoenixOdometryThread;
import frc.robot.utils.CommandXboxControllerSubsystem;
import frc.robot.utils.FieldUtils.ClimbTargets;
import frc.robot.utils.FieldUtils.FeedTargets;
import frc.robot.utils.FieldUtils.TrenchPoses;
import frc.robot.utils.autoaim.AutoAim;
import java.util.Arrays;
Expand Down Expand Up @@ -508,7 +508,11 @@ public Robot() {
driver.setDefaultCommand(driver.rumbleCmd(0.0, 0.0));
operator.setDefaultCommand(operator.rumbleCmd(0.0, 0.0));
shooter.setDefaultCommand(
shooter.rest(swerve::getPose, swerve::getVelocityFieldRelative, superstructure::canScore));
shooter.rest(
swerve::getPose,
swerve::getVelocityFieldRelative,
superstructure::inScoringArea,
() -> FeedTargets.getFeedTarget(Superstructure.getFeedTarget()).getPose()));
swerve.setDefaultCommand(
swerve
.driveOpenLoopFieldRelative(
Expand Down Expand Up @@ -600,36 +604,36 @@ private void addControllerBindings(Indexer indexer, Shooter shooter, Intake inta
: Rotation2d.k180deg)));

// autoaim (alpha)
autoAimReq
.and(() -> ROBOT_EDITION == RobotEdition.ALPHA)
.whileTrue(
swerve.faceHub(
() ->
-1
* modifyJoystick(driver.getLeftY())
* SwerveSubsystem.SWERVE_CONSTANTS.getMaxLinearSpeed(),
() ->
-1
* modifyJoystick(driver.getLeftX())
* SwerveSubsystem.SWERVE_CONSTANTS.getMaxLinearSpeed(),
ROBOT_EDITION == RobotEdition.ALPHA
? AutoAim.ALPHA_HUB_SHOT_TREE
: AutoAim.COMP_HUB_SHOT_TREE));

new Trigger(swerve::isNearTrench)
.and(() -> Superstructure.getState() != SuperState.INTAKE)
.and(() -> isTeleopEnabled())
.and(() -> !Superstructure.getPoseOverride())
.whileTrue(
swerve
.trenchAlign(
() ->
modifyJoystick(driver.getLeftY())
* SwerveSubsystem.SWERVE_CONSTANTS.getMaxLinearSpeed(),
() ->
modifyJoystick(driver.getLeftX())
* SwerveSubsystem.SWERVE_CONSTANTS.getMaxLinearSpeed())
.alongWith(Commands.print("afkljsdflkjs")));
// autoAimReq
// .and(() -> ROBOT_EDITION == RobotEdition.ALPHA)
// .whileTrue(
// swerve.faceHub(
// () ->
// -1
// * modifyJoystick(driver.getLeftY())
// * SwerveSubsystem.SWERVE_CONSTANTS.getMaxLinearSpeed(),
// () ->
// -1
// * modifyJoystick(driver.getLeftX())
// * SwerveSubsystem.SWERVE_CONSTANTS.getMaxLinearSpeed(),
// ROBOT_EDITION == RobotEdition.ALPHA
// ? AutoAim.ALPHA_HUB_SHOT_TREE
// : AutoAim.COMP_HUB_SHOT_TREE));

// new Trigger(swerve::isNearTrench)
// .and(() -> Superstructure.getState() != SuperState.INTAKE)
// .and(() -> isTeleopEnabled())
// .and(() -> !Superstructure.getPoseOverride())
// .whileTrue(
// swerve
// .trenchAlign(
// () ->
// modifyJoystick(driver.getLeftY())
// * SwerveSubsystem.SWERVE_CONSTANTS.getMaxLinearSpeed(),
// () ->
// modifyJoystick(driver.getLeftX())
// * SwerveSubsystem.SWERVE_CONSTANTS.getMaxLinearSpeed())
// .alongWith(Commands.print("afkljsdflkjs")));

// current zero shooter hood
driver
Expand Down Expand Up @@ -722,6 +726,7 @@ private void addAutos() {
autoChooser.addOption("Depot Climb", autos.getDepotClimbAuto());
autoChooser.addOption("Depot Outpost Climb", autos.getDepotOutpostClimbAuto());
autoChooser.addOption("Test Auto", autos.getTestAuto());
autoChooser.addOption("Just Score", autos.getJustScoreAuto());

haveAutosGenerated = true;
System.out.println("Done generating autos");
Expand Down
34 changes: 27 additions & 7 deletions src/main/java/frc/robot/Superstructure.java
Original file line number Diff line number Diff line change
Expand Up @@ -197,8 +197,8 @@ private void addTriggers() {
operator.leftBumper().onTrue(Commands.runOnce(() -> feedTarget = FeedTarget.LEFT));
operator.rightBumper().onTrue(Commands.runOnce(() -> feedTarget = FeedTarget.RIGHT));

operator.leftTrigger().onTrue(Commands.runOnce(() -> poseOverride = true));
operator.rightTrigger().onTrue(Commands.runOnce(() -> poseOverride = false));
// operator.leftTrigger().onTrue(Commands.runOnce(() -> poseOverride = true));
// operator.rightTrigger().onTrue(Commands.runOnce(() -> poseOverride = false));

operator
.povLeft()
Expand Down Expand Up @@ -384,14 +384,22 @@ private void addCommands() {
intake.restExtended(),
// intake.restRetracted(),
indexer.rest(),
shooter.rest(swerve::getPose, swerve::getVelocityFieldRelative, this::canScore),
shooter.rest(
swerve::getPose,
swerve::getVelocityFieldRelative,
this::inScoringArea,
() -> FeedTargets.getFeedTarget(feedTarget).getPose()),
climber.retract());

bindCommands(
SuperState.INTAKE,
intake.intake(),
indexer.rest(),
shooter.rest(swerve::getPose, swerve::getVelocityFieldRelative, this::canScore),
shooter.rest(
swerve::getPose,
swerve::getVelocityFieldRelative,
this::inScoringArea,
() -> FeedTargets.getFeedTarget(feedTarget).getPose()),
climber.retract());

bindCommands(
Expand Down Expand Up @@ -565,19 +573,31 @@ private void addCommands() {
SuperState.PRE_CLIMB,
intake.restRetracted(),
indexer.rest(),
shooter.rest(swerve::getPose, swerve::getVelocityFieldRelative, this::canScore),
shooter.rest(
swerve::getPose,
swerve::getVelocityFieldRelative,
this::inScoringArea,
() -> FeedTargets.getFeedTarget(feedTarget).getPose()),
climber.extend());
bindCommands(
SuperState.CLIMB,
intake.restRetracted(),
indexer.rest(),
shooter.rest(swerve::getPose, swerve::getVelocityFieldRelative, this::canScore),
shooter.rest(
swerve::getPose,
swerve::getVelocityFieldRelative,
this::inScoringArea,
() -> FeedTargets.getFeedTarget(feedTarget).getPose()),
climber.retract());
bindCommands(
SuperState.POST_CLIMB,
intake.restRetracted(),
indexer.rest(),
shooter.rest(swerve::getPose, swerve::getVelocityFieldRelative, this::canScore),
shooter.rest(
swerve::getPose,
swerve::getVelocityFieldRelative,
this::inScoringArea,
() -> FeedTargets.getFeedTarget(feedTarget).getPose()),
climber.extend());

bindCommands(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,10 +71,10 @@ public Command kick(DoubleSupplier flywheelSpeedSupplier) {
double spinnerSpeed = surfaceSpeedInPerSec / (Math.PI * SPINNER_DIAMETER_INCHES);
Logger.recordOutput("Indexer/Spinner/Adjusted speed", spinnerSpeed);
Logger.recordOutput("Indexer/Kicker/Adjusted speed", kickerSpeed);
spinnerIO.setRollerVelocity(spinnerSpeed - 1);
// spinnerIO.setRollerVelocity(spinnerSpeed - 1);
// kickerIO.setRollerVelocity(kickerSpeed - 5);
// spinnerIO.setRollerVelocity(20);
kickerIO.setRollerVelocity(15);
spinnerIO.setRollerVelocity(60);
kickerIO.setRollerVelocity(25);
})
// .withTimeout(3),
// this.run(
Expand Down
14 changes: 10 additions & 4 deletions src/main/java/frc/robot/subsystems/intake/SlapdownSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
import org.littletonrobotics.junction.Logger;

public class SlapdownSubsystem extends SubsystemBase implements Intake {
public static final Rotation2d PIVOT_MIN_POSITION = Rotation2d.fromRotations(-0.051025);
public static final Rotation2d PIVOT_MIN_POSITION = Rotation2d.fromRotations(-0.052002);
public static final Rotation2d PIVOT_MAX_POSITION =
Rotation2d.fromDegrees(122); // Not so sure abt this one...
public static final Rotation2d PIVOT_EXTENDED_POSITION = PIVOT_MIN_POSITION;
Expand Down Expand Up @@ -132,7 +132,13 @@ public Command restExtended() {
pivotIO.setMotorPositionSetpoint(PIVOT_EXTENDED_POSITION);
rollerIO.setRollerVoltage(0.0);
})
.unless(atExtensionTrigger);
.until(atExtensionTrigger)
.andThen(
this.run(
() -> {
pivotIO.setMotorVoltage(0);
rollerIO.setRollerVoltage(0);
}));
}

@Override
Expand Down Expand Up @@ -204,8 +210,8 @@ public static TalonFXConfiguration getPivotConfig() {
config.CurrentLimits.SupplyCurrentLimitEnable = true;

// TODO: TUNE
config.MotionMagic.MotionMagicCruiseVelocity = 1;
config.MotionMagic.MotionMagicAcceleration = 1;
config.MotionMagic.MotionMagicCruiseVelocity = 5;
config.MotionMagic.MotionMagicAcceleration = 5;

return config;
}
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/subsystems/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,8 @@ public Command feed(
public Command rest(
Supplier<Pose2d> robotPoseSupplier,
Supplier<ChassisSpeeds> chassisSpeedsSupplier,
BooleanSupplier canScore);
BooleanSupplier canScore,
Supplier<Pose2d> feedTarget);

/** Run balls out from the shooter. This is for antijamming the robot */
public Command spit();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,8 @@ public Command feed(
public Command rest(
Supplier<Pose2d> robotPoseSupplier,
Supplier<ChassisSpeeds> chassisSpeedsSupplier,
BooleanSupplier canScore) {
BooleanSupplier canScore,
Supplier<Pose2d> feedTarget) {
return this.run(
() -> {
hoodIO.setHoodPosition(HOOD_MIN_ROTATION);
Expand Down
88 changes: 49 additions & 39 deletions src/main/java/frc/robot/subsystems/shooter/TurretSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@
import frc.robot.components.cancoder.CANcoderIO;
import frc.robot.components.cancoder.CANcoderIOInputsAutoLogged;
import frc.robot.utils.FieldUtils;
import frc.robot.utils.FieldUtils.FeedTargets;
import frc.robot.utils.autoaim.AutoAim;
import frc.robot.utils.autoaim.InterpolatingShotTree.ShotData;
import java.util.function.BooleanSupplier;
Expand Down Expand Up @@ -204,24 +203,33 @@ public Command feed(
public Command rest(
Supplier<Pose2d> robotPoseSupplier,
Supplier<ChassisSpeeds> chassisSpeedsSupplier,
BooleanSupplier canScore) {
BooleanSupplier inScoringArea,
Supplier<Pose2d> feedTarget) {
return this.run(
() -> {
hoodIO.setHoodPosition(HOOD_MIN_ANGLE);
flywheelIO.setFlywheelVoltage(0.0);
if (canScore.getAsBoolean()) {
// if (canScore.getAsBoolean()) {
// turretIO.setTurretPosition(
// AutoAim.getTurretFeedTargetRotation(
// FeedTargets.getFeedTarget(Superstructure.getFeedTarget()).getTranslation(),
// robotPoseSupplier.get(),
// chassisSpeedsSupplier.get()));
// } else {
if (inScoringArea.getAsBoolean()) {
turretIO.setTurretPosition(
AutoAim.getTurretFeedTargetRotation(
FeedTargets.getFeedTarget(Superstructure.getFeedTarget()).getTranslation(),
AutoAim.getTurretHubTargetRotation(
FieldUtils.getCurrentHubTranslation(),
robotPoseSupplier.get(),
chassisSpeedsSupplier.get()));
} else {
turretIO.setTurretPosition(
AutoAim.getTurretHubTargetRotation(
FieldUtils.getCurrentHubTranslation(),
AutoAim.getTurretFeedTargetRotation(
feedTarget.get().getTranslation(),
robotPoseSupplier.get(),
chassisSpeedsSupplier.get()));
}
// }
});
}

Expand Down Expand Up @@ -253,38 +261,40 @@ public Command score(
Supplier<Pose2d> robotPoseSupplier,
Supplier<ShotData> shotDataSupplier,
Supplier<ChassisSpeeds> chassisSpeedsSupplier) {
return this.run(
() -> {
switch (Superstructure.getFixedShotTarget()) {
// in front of left trench with intake facing trench
case LEFT:
hoodIO.setHoodPosition(AutoAim.getLeftFixedShotData().hoodAngle());
flywheelIO.setMotionProfiledFlywheelVelocity(
AutoAim.getLeftFixedShotData().flywheelVelocityRotPerSec());
turretIO.setTurretPosition(AutoAim.LEFT_FIXED_SHOT_TURRET_ANGLE);
// in front of tower with intake facing left (to avoid deadzone)
case MID:
hoodIO.setHoodPosition(AutoAim.getMidFixedShotData().hoodAngle());
flywheelIO.setMotionProfiledFlywheelVelocity(
AutoAim.getMidFixedShotData().flywheelVelocityRotPerSec());
turretIO.setTurretPosition(AutoAim.MID_FIXED_SHOT_TURRET_ANGLE);
// in front of right trench with intake facing alliance wall
case RIGHT:
hoodIO.setHoodPosition(AutoAim.getRightFixedShotData().hoodAngle());
flywheelIO.setMotionProfiledFlywheelVelocity(
AutoAim.getRightFixedShotData().flywheelVelocityRotPerSec());
turretIO.setTurretPosition(AutoAim.RIGHT_FIXED_SHOT_TURRET_ANGLE);
case NONE:
hoodIO.setHoodPosition(shotDataSupplier.get().hoodAngle());
flywheelIO.setMotionProfiledFlywheelVelocity(
shotDataSupplier.get().flywheelVelocityRotPerSec());
turretIO.setTurretPosition(
AutoAim.getTurretHubTargetRotation(
FieldUtils.getCurrentHubTranslation(),
robotPoseSupplier.get(),
chassisSpeedsSupplier.get()));
}
});
return resetTurretToCalculatedPosition()
.andThen(
this.run(
() -> {
switch (Superstructure.getFixedShotTarget()) {
// in front of left trench with intake facing trench
case LEFT:
hoodIO.setHoodPosition(AutoAim.getLeftFixedShotData().hoodAngle());
flywheelIO.setMotionProfiledFlywheelVelocity(
AutoAim.getLeftFixedShotData().flywheelVelocityRotPerSec());
turretIO.setTurretPosition(AutoAim.LEFT_FIXED_SHOT_TURRET_ANGLE);
// in front of tower with intake facing left (to avoid deadzone)
case MID:
hoodIO.setHoodPosition(AutoAim.getMidFixedShotData().hoodAngle());
flywheelIO.setMotionProfiledFlywheelVelocity(
AutoAim.getMidFixedShotData().flywheelVelocityRotPerSec());
turretIO.setTurretPosition(AutoAim.MID_FIXED_SHOT_TURRET_ANGLE);
// in front of right trench with intake facing alliance wall
case RIGHT:
hoodIO.setHoodPosition(AutoAim.getRightFixedShotData().hoodAngle());
flywheelIO.setMotionProfiledFlywheelVelocity(
AutoAim.getRightFixedShotData().flywheelVelocityRotPerSec());
turretIO.setTurretPosition(AutoAim.RIGHT_FIXED_SHOT_TURRET_ANGLE);
case NONE:
hoodIO.setHoodPosition(shotDataSupplier.get().hoodAngle());
flywheelIO.setMotionProfiledFlywheelVelocity(
shotDataSupplier.get().flywheelVelocityRotPerSec());
turretIO.setTurretPosition(
AutoAim.getTurretHubTargetRotation(
FieldUtils.getCurrentHubTranslation(),
robotPoseSupplier.get(),
chassisSpeedsSupplier.get()));
}
}));
}

@Override
Expand Down
Loading
Loading