Skip to content
Merged
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
18 changes: 17 additions & 1 deletion src/main/java/frc/robot/subsystems/Superstructure.java
Original file line number Diff line number Diff line change
@@ -1,9 +1,11 @@
package frc.robot.subsystems;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Command.InterruptionBehavior;
Expand All @@ -20,6 +22,7 @@
import frc.robot.subsystems.shoulder.ShoulderSubsystem;
import frc.robot.subsystems.wrist.WristSubsystem;
import frc.robot.utils.autoaim.AlgaeIntakeTargets;
import frc.robot.utils.autoaim.AutoAim;
import frc.robot.utils.autoaim.CoralTargets;
import frc.robot.utils.autoaim.HumanPlayerTargets;
import java.util.HashMap;
Expand Down Expand Up @@ -799,7 +802,20 @@ private void configureStateTransitionCommands() {
.whileTrue(shoulder.setTargetAngleSlow(ShoulderSubsystem.SHOULDER_SCORE_PROCESSOR_POS))
.whileTrue(wrist.setTargetAngle(WristSubsystem.WRIST_SCORE_PROCESSOR_POS))
.whileTrue(manipulator.setVoltage(-2.0))
.and(() -> stateTimer.hasElapsed(2.0))
.and(
() ->
!MathUtil.isNear(
pose.get().getX(),
DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Blue
? AutoAim.BLUE_PROCESSOR_POS.getX()
: AutoAim.RED_PROCESSOR_POS.getX(),
0.5)
|| !MathUtil.isNear(
pose.get().getY(),
DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Blue
? AutoAim.BLUE_PROCESSOR_POS.getY()
: AutoAim.RED_PROCESSOR_POS.getY(),
0.5))
.onTrue(this.forceState(SuperState.IDLE));

stateTriggers
Expand Down