Skip to content

Commit

Permalink
Spiky auto tuning
Browse files Browse the repository at this point in the history
  • Loading branch information
jwbonner committed Apr 1, 2024
1 parent b1a825e commit b309dca
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 10 deletions.
7 changes: 2 additions & 5 deletions src/main/java/org/littletonrobotics/frc2024/RobotState.java
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,6 @@ public record AimingParameters(
new LoggedTunableNumber("RobotState/AutoLookahead", 0.5);
private static final LoggedTunableNumber lookahead =
new LoggedTunableNumber("RobotState/lookaheadS", 0.35);
@Setter private boolean useAutoLookahead = false;
private static final double poseBufferSizeSeconds = 2.0;

private static final double armAngleCoefficient = 57.254371165197;
Expand Down Expand Up @@ -210,10 +209,8 @@ public AimingParameters getAimingParameters() {
.plus(FudgeFactors.speaker.getTransform());
Pose2d fieldToPredictedVehicle;
if (DriverStation.isAutonomousEnabled()) {
fieldToPredictedVehicle =
useAutoLookahead
? getPredictedPose(autoLookahead.get(), autoLookahead.get())
: getEstimatedPose();
fieldToPredictedVehicle = getPredictedPose(autoLookahead.get(), autoLookahead.get());

} else {
fieldToPredictedVehicle =
lookaheadDisable.getAsBoolean()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
import lombok.RequiredArgsConstructor;
import org.littletonrobotics.frc2024.AutoSelector.AutoQuestionResponse;
import org.littletonrobotics.frc2024.FieldConstants;
import org.littletonrobotics.frc2024.RobotState;
import org.littletonrobotics.frc2024.subsystems.drive.Drive;
import org.littletonrobotics.frc2024.subsystems.drive.trajectory.DriveTrajectories;
import org.littletonrobotics.frc2024.subsystems.drive.trajectory.HolonomicTrajectory;
Expand All @@ -37,7 +36,7 @@ public class AutoBuilder {

private static final double preloadDelay = 1.0;
private static final double spikeIntakeDelay = 0.35;
private static final double spikeFeedThroughDelay = 0.35;
private static final double spikeFeedThroughDelay = 0.45;
private static final double stageAimX = FieldConstants.Stage.center.getX() - 0.3;

/** All shot compensation values used when shooting corresponding centerline note. */
Expand Down Expand Up @@ -164,9 +163,7 @@ private Command scoreSpikes(AutoQuestionResponse startingLocation, boolean score
() -> scoresThree)))

// Always aim and run flywheels
.deadlineWith(superstructure.aimWithCompensation(0.0), flywheels.shootCommand())
.beforeStarting(() -> RobotState.getInstance().setUseAutoLookahead(true))
.finallyDo(() -> RobotState.getInstance().setUseAutoLookahead(false));
.deadlineWith(superstructure.aimWithCompensation(0.0), flywheels.shootCommand());
}

/** Scores two centerline notes with the given trajectories. */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -292,6 +292,12 @@ public class DriveTrajectories {
.addPoseWaypoint(
new Pose2d(centerlineNote, shotToCenterlineIntakeOrientation)
.transformBy(new Translation2d(centerlineIntakeOffset, 0.0).toTransform2d()))
.addPoseWaypoint(
new Pose2d(centerlineNote, shotToCenterlineIntakeOrientation)
.transformBy(
new Translation2d(
centerlineIntakeOffset + centerlinePrepareIntakeOffset, 0.0)
.toTransform2d()))
.build();
shotToCenterlineIntakeSegments[i] = shotToCenterlineIntake;

Expand Down Expand Up @@ -327,6 +333,12 @@ public class DriveTrajectories {
new Pose2d(centerlineNote, spikeTocenterlineIntakeOrientation)
.transformBy(
new Translation2d(centerlineIntakeOffset, 0.0).toTransform2d()))
.addPoseWaypoint(
new Pose2d(centerlineNote, spikeTocenterlineIntakeOrientation)
.transformBy(
new Translation2d(
centerlineIntakeOffset + centerlinePrepareIntakeOffset, 0.0)
.toTransform2d()))
.build();
spikeToCenterlineIntakeSegments[spikeIndex][i] = spikeToCenterline;
}
Expand Down

0 comments on commit b309dca

Please sign in to comment.