diff --git a/notes/superstructure.md b/notes/superstructure.md index b236a1a..ddecbc3 100644 --- a/notes/superstructure.md +++ b/notes/superstructure.md @@ -10,9 +10,13 @@ IDLE <--> |intakeReq + intakeEmpty| INTAKE READY <--> |intakeReq + empty| INTAKE -READY --> |feedReq| FEED +READY --> |feedReq| SPIN_UP_FEED -READY --> |scoreReq| SCORE +READY --> |scoreReq| SPIN_UP_SCORE + +SPIN_UP_FEED --> |atVelocity| FEED + +SPIN_UP_SCORE --> |atVelocity| SCORE FEED --> |flowReq| FEED_FLOW diff --git a/src/main/java/frc/robot/Autos.java b/src/main/java/frc/robot/Autos.java index d7e1e8f..ebad639 100644 --- a/src/main/java/frc/robot/Autos.java +++ b/src/main/java/frc/robot/Autos.java @@ -25,7 +25,8 @@ public class Autos { // mehhhhhhh private static boolean autoPreScore; private static boolean autoScore; - private static boolean autoIntakeCoral; + private static boolean autoIntake; + private static boolean autoFeed; // private static boolean autoIntakeAlgae; @@ -37,9 +38,12 @@ public class Autos { public static Trigger autoScoreReq = new Trigger(() -> autoScore).and(DriverStation::isAutonomous); - @AutoLogOutput(key = "Superstructure/Auto Coral Intake Request") - public static Trigger autoIntakeCoralReq = - new Trigger(() -> autoIntakeCoral).and(DriverStation::isAutonomous); + @AutoLogOutput(key = "Superstructure/Auto Intake Request") + public static Trigger autoIntakeReq = + new Trigger(() -> autoIntake).and(DriverStation::isAutonomous); + + @AutoLogOutput(key = "Superstructure/Auto Feed Request") + public static Trigger autoFeedReq = new Trigger(() -> autoFeed).and(DriverStation::isAutonomous); public enum PathEndType { PLACEHOLDER; diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 402b704..036f351 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -158,7 +158,8 @@ public enum RobotType { @AutoLogOutput(key = "Robot/Zeroing Request") private Trigger zeroingReq = driver.b(); - private final Superstructure superstructure = new Superstructure(swerve, driver, operator); + private final Superstructure superstructure = + new Superstructure(swerve, indexer, intake, shooter, driver, operator); private final Autos autos; private Optional lastAlliance = Optional.empty(); diff --git a/src/main/java/frc/robot/Superstructure.java b/src/main/java/frc/robot/Superstructure.java index 91759fa..9be6815 100644 --- a/src/main/java/frc/robot/Superstructure.java +++ b/src/main/java/frc/robot/Superstructure.java @@ -9,19 +9,29 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.Trigger; +import frc.robot.subsystems.indexer.IndexerSubsystem; +import frc.robot.subsystems.intake.IntakeSubsystem; +import frc.robot.subsystems.shooter.ShooterSubsystem; import frc.robot.subsystems.swerve.SwerveSubsystem; import frc.robot.utils.CommandXboxControllerSubsystem; +import frc.robot.utils.FieldUtils.FeedTargets; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; public class Superstructure { - /** - * We should have a state for every single "pose" the robot will hit. See this document for - * screenshots of the robot in each state. There are also named positions in cad for each state. - */ + /** We should have a state for every single action the robot will perform. */ public enum SuperState { - IDLE(); + IDLE, + INTAKE, + READY, + SPIN_UP_FEED, + FEED, + FEED_FLOW, + SPIN_UP_SCORE, + SCORE, + SCORE_FLOW, + SPIT; public final Trigger trigger; private SuperState() { @@ -41,15 +51,35 @@ public Trigger getTrigger() { private Timer stateTimer = new Timer(); private final SwerveSubsystem swerve; + private final IndexerSubsystem indexer; + private final IntakeSubsystem intake; + private final ShooterSubsystem shooter; private final CommandXboxControllerSubsystem driver; private final CommandXboxControllerSubsystem operator; // Declare triggers - @AutoLogOutput(key = "Superstructure/Pre Score Request") - public Trigger preScoreReq; - @AutoLogOutput(key = "Superstructure/Score Request") - public Trigger scoreReq; + private Trigger scoreReq; + + @AutoLogOutput(key = "Superstructure/Intake Request") + private Trigger intakeReq; + + @AutoLogOutput(key = "Superstructure/Feed Request") + private Trigger feedReq; + + @AutoLogOutput(key = "Superstructure/Flowstate Request") + private Trigger flowReq; + + @AutoLogOutput(key = "Superstructure/Anti Jam Req") + private Trigger antiJamReq; + + @AutoLogOutput(key = "Superstructure/Is Full") + private Trigger isFull; + + @AutoLogOutput(key = "Superstructure/Is Empty") + private Trigger isEmpty; + + private boolean shouldFeed = false; // @AutoLogOutput(key = "Superstructure/At Extension?") // public Trigger atExtensionTrigger = new Trigger(this::atExtension).or(Robot::isSimulation); @@ -57,22 +87,159 @@ public Trigger getTrigger() { /** Creates a new Superstructure. */ public Superstructure( SwerveSubsystem swerve, + IndexerSubsystem indexer, + IntakeSubsystem intake, + ShooterSubsystem shooter, CommandXboxControllerSubsystem driver, CommandXboxControllerSubsystem operator) { this.swerve = swerve; + this.indexer = indexer; + this.intake = intake; + this.shooter = shooter; this.driver = driver; this.operator = operator; addTriggers(); addTransitions(); + addCommands(); stateTimer.start(); } private void addTriggers() { - preScoreReq = driver.rightTrigger().or(Autos.autoPreScoreReq); + // Toggles for feeding + operator.leftBumper().onTrue(Commands.runOnce(() -> shouldFeed = true)); + operator.rightBumper().onTrue(Commands.runOnce(() -> shouldFeed = false)); + + scoreReq = + driver + .rightTrigger() + .and(DriverStation::isTeleop) + .and(() -> shouldFeed == false) + .or(Autos.autoScoreReq); // Maybe should include if its our turn? + + intakeReq = driver.leftTrigger().and(DriverStation::isTeleop).or(Autos.autoIntakeReq); + + feedReq = + driver + .rightBumper() + .and(DriverStation::isTeleop) + .and(() -> shouldFeed == true) + .or(Autos.autoFeedReq); + + flowReq = driver.leftTrigger().and(driver.rightTrigger()); + + antiJamReq = driver.a().or(operator.a()); + + isFull = new Trigger(indexer::isFull); + + isEmpty = new Trigger(indexer::isEmpty); + } + + private void addTransitions() { + bindTransition(SuperState.IDLE, SuperState.INTAKE, intakeReq); + + bindTransition(SuperState.INTAKE, SuperState.IDLE, intakeReq.negate().and(isEmpty)); + + bindTransition( + SuperState.INTAKE, SuperState.READY, (intakeReq.negate().and(isEmpty.negate())).or(isFull)); + + bindTransition(SuperState.INTAKE, SuperState.SPIN_UP_FEED, feedReq); + + bindTransition(SuperState.READY, SuperState.INTAKE, intakeReq.and(isFull.negate())); + + bindTransition(SuperState.READY, SuperState.SPIN_UP_SCORE, scoreReq); + + bindTransition( + SuperState.SPIN_UP_SCORE, + SuperState.SCORE, + new Trigger(shooter::atFlywheelVelocitySetpoint)); + + bindTransition( + SuperState.SPIN_UP_FEED, SuperState.FEED, new Trigger(shooter::atFlywheelVelocitySetpoint)); + + bindTransition(SuperState.FEED, SuperState.IDLE, isEmpty); + + bindTransition(SuperState.SCORE, SuperState.IDLE, isEmpty); - scoreReq = driver.rightTrigger().negate().and(DriverStation::isTeleop).or(Autos.autoScoreReq); + // FEED_FLOW transitions + { + bindTransition(SuperState.FEED, SuperState.FEED_FLOW, flowReq); + + bindTransition(SuperState.FEED_FLOW, SuperState.FEED, flowReq.negate().and(feedReq)); + + bindTransition( + SuperState.FEED_FLOW, SuperState.READY, flowReq.negate().and(isEmpty.negate())); + + // No so sure about the end condition here. + bindTransition(SuperState.FEED_FLOW, SuperState.IDLE, flowReq.negate().and(isEmpty)); + } + + // SCORE_FLOW transitions + { + bindTransition(SuperState.SCORE, SuperState.SCORE_FLOW, flowReq); + + bindTransition(SuperState.SCORE_FLOW, SuperState.SCORE, flowReq.negate().and(scoreReq)); + + bindTransition( + SuperState.SCORE_FLOW, SuperState.READY, flowReq.negate().and(isEmpty.negate())); + + // No so sure about the end condition here. + bindTransition(SuperState.SCORE_FLOW, SuperState.IDLE, flowReq.negate().and(isEmpty)); + } + + // Transition from any state to SPIT for anti jamming + antiJamReq.onTrue(changeStateTo(SuperState.SPIT)); + + bindTransition(SuperState.SPIT, SuperState.IDLE, antiJamReq.negate()); + } + + private void addCommands() { + bindCommands( + SuperState.IDLE, + intake.rest(), + indexer.rest(), + shooter.rest()); // Maybe the indexer should be indexing? + + bindCommands(SuperState.INTAKE, intake.intake(), indexer.index(), shooter.rest()); + + bindCommands( + SuperState.READY, + intake.rest(), + indexer.index(), + shooter.rest()); // Maybe index at slower speed? + + bindCommands( + SuperState.SPIN_UP_SCORE, intake.rest(), indexer.rest(), shooter.shoot(swerve::getPose)); + + bindCommands( + SuperState.SPIN_UP_FEED, + intake.rest(), + indexer.rest(), + shooter.feed( + swerve::getPose, () -> FeedTargets.BLUE_BACK_RIGHT.getPose())); // TODO: SELECTION LOGIC + + bindCommands( + SuperState.SCORE, intake.rest(), indexer.indexToShoot(), shooter.shoot(swerve::getPose)); + + bindCommands( + SuperState.SCORE_FLOW, intake.intake(), indexer.index(), shooter.shoot(swerve::getPose)); + + bindCommands( + SuperState.FEED, + intake.rest(), + indexer.index(), + shooter.feed( + swerve::getPose, + () -> FeedTargets.BLUE_BACK_RIGHT.getPose())); // TODO: ADD SOME SELECTION LOGIC + + bindCommands( + SuperState.FEED_FLOW, + intake.intake(), + indexer.index(), + shooter.feed(swerve::getPose, () -> FeedTargets.BLUE_BACK_RIGHT.getPose())); + + bindCommands(SuperState.SPIT, intake.outake(), indexer.outtake(), shooter.spit()); } public void periodic() { @@ -105,6 +272,16 @@ private void bindTransition(SuperState start, SuperState end, Trigger trigger, C trigger.and(start.getTrigger()).onTrue(Commands.parallel(changeStateTo(end), cmd)); } + /** + * Runs the passed in command(s) in parallel when the superstructure is in the passed in state + * + * @param state + * @param commands + */ + private void bindCommands(SuperState state, Command... commands) { + state.getTrigger().whileTrue(Commands.parallel(commands)); + } + // public boolean atExtension(SuperState state) { // } @@ -130,8 +307,6 @@ private void setSubstates() {} // public Command transitionAfterZeroing() { // } - private void addTransitions() {} - /** * Only for setting initial state at the beginning of auto * diff --git a/src/main/java/frc/robot/subsystems/indexer/IndexerSubsystem.java b/src/main/java/frc/robot/subsystems/indexer/IndexerSubsystem.java index 37698d1..af761a4 100644 --- a/src/main/java/frc/robot/subsystems/indexer/IndexerSubsystem.java +++ b/src/main/java/frc/robot/subsystems/indexer/IndexerSubsystem.java @@ -65,15 +65,6 @@ public Command stopKicker() { public Command shoot() { return this.run(() -> kickerIO.setRollerVoltage(0)); } - ; - - public boolean isFull(boolean firstBeamBreak, boolean secondBeamBreak) { - if (firstBeamBreak && secondBeamBreak) { - return true; - } else { - return false; - } - } public boolean isEmpty() { return !firstCANRangeInputs.isDetected && !secondCANRangeInputs.isDetected; @@ -87,13 +78,15 @@ public Command index() { return this.run( () -> { indexRollerIO.setRollerVoltage(5); + kickerIO.setRollerVoltage(-5); }); } - public Command score() { + public Command indexToShoot() { return this.run( () -> { indexRollerIO.setRollerVoltage(10); + kickerIO.setRollerVoltage(5); }); } @@ -101,6 +94,15 @@ public Command outtake() { return this.run( () -> { indexRollerIO.setRollerVoltage(-5); + kickerIO.setRollerVoltage(-5); + }); + } + + public Command rest() { + return this.run( + () -> { + indexRollerIO.setRollerVoltage(0.0); + kickerIO.setRollerVoltage(0.0); }); } diff --git a/src/main/java/frc/robot/subsystems/shooter/FlywheelIO.java b/src/main/java/frc/robot/subsystems/shooter/FlywheelIO.java index 4885bfb..ac355ed 100644 --- a/src/main/java/frc/robot/subsystems/shooter/FlywheelIO.java +++ b/src/main/java/frc/robot/subsystems/shooter/FlywheelIO.java @@ -26,13 +26,13 @@ public class FlywheelIO { @AutoLog public static class FlywheelIOInputs { - public double flywheelLeaderVelocityMetersPerSecond = 0.0; + public double flywheelLeaderVelocityRotationsPerSecond = 0.0; public double flywheelLeaderStatorCurrentAmps = 0.0; public double flywheelLeaderSupplyCurrentAmp = 0.0; public double flywheelLeaderVoltage = 0.0; public double flywheelLeaderTempC = 0.0; - public double flywheelFollowerVelocityMetersPerSecond = 0.0; + public double flywheelFollowerVelocityRotationsPerSecond = 0.0; public double flywheelFollowerStatorCurrentAmps = 0.0; public double flywheelFollowerSupplyCurrentAmp = 0.0; public double flywheelFollowerVoltage = 0.0; @@ -59,6 +59,8 @@ public static class FlywheelIOInputs { private MotionMagicVelocityVoltage motionMagicVelocityVoltage = new MotionMagicVelocityVoltage(0.0).withEnableFOC(true).withAcceleration(100); + private double velocitySetpointRotPerSec = 0.0; + // todo: tune acceleration public FlywheelIO(TalonFXConfiguration config, CANBus canbus) { @@ -107,9 +109,11 @@ public static TalonFXConfiguration getFlywheelConfiguration() { config.MotorOutput.NeutralMode = NeutralModeValue.Coast; config.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive; - config.Slot0.kS = 0.2; - config.Slot0.kV = 0.12; - config.Slot0.kP = 0.3; + config.Feedback.SensorToMechanismRatio = ShooterSubsystem.FLYWHEEL_GEAR_RATIO; + + config.Slot0.kS = 0.0; + config.Slot0.kV = 0.15; // From sim + config.Slot0.kP = 10.0; config.Slot0.kD = 0.0; config.CurrentLimits.StatorCurrentLimit = 120.0; @@ -124,10 +128,12 @@ public void setFlywheelVoltage(double volts) { } public void setMotionProfiledFlywheelVelocity(double flywheelVelocity) { + velocitySetpointRotPerSec = flywheelVelocity; flywheelLeader.setControl(motionMagicVelocityVoltage.withVelocity(flywheelVelocity)); } public void stop() { // thought i should add a stop command, dont think i had to though + velocitySetpointRotPerSec = 0.0; flywheelLeader.setControl(voltageOut.withOutput(0.0)); } @@ -144,16 +150,20 @@ public void updateInputs(FlywheelIOInputs inputs) { flywheelFollowerSupplyCurrent, flywheelFollowerTemp); - inputs.flywheelLeaderVelocityMetersPerSecond = flywheelLeaderVelocity.getValueAsDouble(); + inputs.flywheelLeaderVelocityRotationsPerSecond = flywheelLeaderVelocity.getValueAsDouble(); inputs.flywheelLeaderVoltage = flywheelLeaderVoltage.getValueAsDouble(); inputs.flywheelLeaderStatorCurrentAmps = flywheelLeaderStatorCurrent.getValueAsDouble(); inputs.flywheelLeaderSupplyCurrentAmp = flywheelLeaderSupplyCurrent.getValueAsDouble(); inputs.flywheelLeaderTempC = flywheelLeaderTemp.getValueAsDouble(); - inputs.flywheelFollowerVelocityMetersPerSecond = flywheelFollowerVelocity.getValueAsDouble(); + inputs.flywheelFollowerVelocityRotationsPerSecond = flywheelFollowerVelocity.getValueAsDouble(); inputs.flywheelFollowerVoltage = flywheelFollowerVoltage.getValueAsDouble(); inputs.flywheelFollowerStatorCurrentAmps = flywheelFollowerStatorCurrent.getValueAsDouble(); inputs.flywheelFollowerSupplyCurrentAmp = flywheelFollowerSupplyCurrent.getValueAsDouble(); inputs.flywheelFollowerTempC = flywheelFollowerTemp.getValueAsDouble(); } + + public double getSetpointRotPerSec() { + return velocitySetpointRotPerSec; + } } diff --git a/src/main/java/frc/robot/subsystems/shooter/HoodIO.java b/src/main/java/frc/robot/subsystems/shooter/HoodIO.java index 44ea671..e852e44 100644 --- a/src/main/java/frc/robot/subsystems/shooter/HoodIO.java +++ b/src/main/java/frc/robot/subsystems/shooter/HoodIO.java @@ -14,7 +14,6 @@ import com.ctre.phoenix6.controls.VelocityVoltage; import com.ctre.phoenix6.controls.VoltageOut; import com.ctre.phoenix6.hardware.TalonFX; -import com.ctre.phoenix6.signals.GravityTypeValue; import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.signals.NeutralModeValue; import edu.wpi.first.math.geometry.Rotation2d; @@ -82,12 +81,12 @@ public static TalonFXConfiguration getHoodConfiguration() { config.Feedback.SensorToMechanismRatio = ShooterSubsystem.HOOD_GEAR_RATIO; - config.Slot0.GravityType = GravityTypeValue.Elevator_Static; + // config.Slot0.GravityType = GravityTypeValue.Arm_Cosine; Potentially need, maybe not tho. - config.Slot0.kS = 0.24; - config.Slot0.kG = 0.56; - config.Slot0.kV = 0.6; - config.Slot0.kP = 110.0; + config.Slot0.kS = 0.0; + config.Slot0.kG = 0.0; + config.Slot0.kV = 1.1; + config.Slot0.kP = 5.0; config.Slot0.kD = 0.0; config.CurrentLimits.StatorCurrentLimit = 80.0; diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java index 99bc648..9cfde0a 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java @@ -6,7 +6,8 @@ import static edu.wpi.first.units.Units.Volts; -import com.google.common.base.Supplier; +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -15,7 +16,9 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Mechanism; -import java.util.function.DoubleSupplier; +import frc.robot.utils.autoaim.AutoAim; +import frc.robot.utils.autoaim.InterpolatingShotTree.ShotData; +import java.util.function.Supplier; import org.littletonrobotics.junction.Logger; public class ShooterSubsystem extends SubsystemBase { @@ -25,6 +28,8 @@ public class ShooterSubsystem extends SubsystemBase { public static double FLYWHEEL_GEAR_RATIO = 28.0 / 24.0; + public static double FLYWHEEL_VELOCITY_TOLERANCE_ROTATIONS_PER_SECOND = 5.0; // TODO: TUNE + HoodIO hoodIO; HoodIOInputsAutoLogged hoodInputs = new HoodIOInputsAutoLogged(); @@ -52,12 +57,44 @@ public ShooterSubsystem(HoodIO hoodIO, FlywheelIO flywheelIO) { this.flywheelIO = flywheelIO; } - public Command shoot(DoubleSupplier voltage) { - return this.run(() -> flywheelIO.setFlywheelVoltage(voltage.getAsDouble())); + public Command shoot(Supplier robotPoseSupplier) { + return this.run( + () -> { + ShotData shotData = + AutoAim.HUB_SHOT_TREE.get(AutoAim.distanceToHub(robotPoseSupplier.get())); + hoodIO.setHoodPosition(shotData.hoodAngle()); + flywheelIO.setMotionProfiledFlywheelVelocity(shotData.flywheelVelocityRotPerSec()); + }); + } + + public Command feed(Supplier robotPoseSupplier, Supplier feedTarget) { + return this.run( + () -> { + ShotData shotData = + AutoAim.FEED_SHOT_TREE.get( + robotPoseSupplier + .get() + .getTranslation() + .getDistance(feedTarget.get().getTranslation())); + hoodIO.setHoodPosition(shotData.hoodAngle()); + flywheelIO.setMotionProfiledFlywheelVelocity(shotData.flywheelVelocityRotPerSec()); + }); } - public Command feed(DoubleSupplier voltage) { - return this.run(() -> flywheelIO.setFlywheelVoltage(voltage.getAsDouble())); + public Command rest() { + return this.run( + () -> { + hoodIO.setHoodPosition(Rotation2d.kZero); // TODO: TUNE TUCKED POSITION IF NEEDED + flywheelIO.setFlywheelVoltage(0.0); + }); + } + + public Command spit() { + return this.run( + () -> { + hoodIO.setHoodPosition(Rotation2d.kZero); + flywheelIO.setMotionProfiledFlywheelVelocity(20); + }); // TODO: TUNE HOOD POS AND FLYWHEEL VELOCITY } public Command setHoodPositionCommand(Supplier hoodPosition) { @@ -108,4 +145,11 @@ public Command runFlywheelSysid() { flywheelSysid.dynamic(Direction.kForward), flywheelSysid.dynamic(Direction.kReverse)); } + + public boolean atFlywheelVelocitySetpoint() { + return MathUtil.isNear( + flywheelInputs.flywheelLeaderVelocityRotationsPerSecond, + flywheelIO.getSetpointRotPerSec(), + FLYWHEEL_VELOCITY_TOLERANCE_ROTATIONS_PER_SECOND); + } } diff --git a/src/main/java/frc/robot/utils/FieldUtils.java b/src/main/java/frc/robot/utils/FieldUtils.java index a514981..d5db691 100644 --- a/src/main/java/frc/robot/utils/FieldUtils.java +++ b/src/main/java/frc/robot/utils/FieldUtils.java @@ -27,4 +27,29 @@ public static Pose2d getCurrentHubPose() { ? BLUE_HUB_POS : RED_HUB_POS; } + + public enum FeedTargets { + BLUE_BACK_RIGHT(new Translation2d(0.6643, 0.75)), // Eyeballed in Choreo + BLUE_BACK_LEFT(new Translation2d(0.75, 7.367)), + RED_BACK_RIGHT(ChoreoAllianceFlipUtil.flip(BLUE_BACK_RIGHT.getPose())), + RED_BACK_LEFT(ChoreoAllianceFlipUtil.flip(BLUE_BACK_LEFT.getPose())); + + private Pose2d targetPose; + + private FeedTargets(Pose2d pose) { + this.targetPose = pose; + } + + private FeedTargets(Translation2d translation) { + this.targetPose = new Pose2d(translation, Rotation2d.kZero); + } + + public Pose2d getPose() { + return targetPose; + } + + public Translation2d getTranslation() { + return targetPose.getTranslation(); + } + } } diff --git a/src/main/java/frc/robot/utils/autoaim/AutoAim.java b/src/main/java/frc/robot/utils/autoaim/AutoAim.java index 732d6e4..1426b50 100644 --- a/src/main/java/frc/robot/utils/autoaim/AutoAim.java +++ b/src/main/java/frc/robot/utils/autoaim/AutoAim.java @@ -1,14 +1,34 @@ package frc.robot.utils.autoaim; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import frc.robot.utils.FieldUtils; +import frc.robot.utils.autoaim.InterpolatingShotTree.ShotData; + public class AutoAim { public static final InterpolatingShotTree HUB_SHOT_TREE = new InterpolatingShotTree(); // If we need other shot trees (i.e. for feeding) we can put them here - static { + static { // For hub shot tree // TODO: ADD SHOTS TO HUB SHOT HERE + HUB_SHOT_TREE.put( + 1.0, new ShotData(Rotation2d.kCW_90deg, 10, 0.5)); // Placeholder to prevent crashes + } + + // Ig we'll see if we need more than 1 feed shot tree + public static final InterpolatingShotTree FEED_SHOT_TREE = new InterpolatingShotTree(); + + static { // For feed shot tree + // TODO: POPULATE + FEED_SHOT_TREE.put( + 1.0, new ShotData(Rotation2d.kCW_90deg, 10, 0.5)); // Placeholder to prevent crashes } // TODO: SOTM + + public static double distanceToHub(Pose2d pose) { + return pose.getTranslation().getDistance(FieldUtils.getCurrentHubTranslation()); + } } diff --git a/src/main/java/frc/robot/utils/autoaim/InterpolatingShotTree.java b/src/main/java/frc/robot/utils/autoaim/InterpolatingShotTree.java index 00468d5..deaebd9 100644 --- a/src/main/java/frc/robot/utils/autoaim/InterpolatingShotTree.java +++ b/src/main/java/frc/robot/utils/autoaim/InterpolatingShotTree.java @@ -5,8 +5,8 @@ import java.util.TreeMap; public class InterpolatingShotTree { - private record ShotData( - Rotation2d hoodRotation, double flywheelVelocityRotPerSec, double flightTimeSec) {} + public record ShotData( + Rotation2d hoodAngle, double flywheelVelocityRotPerSec, double flightTimeSec) {} private final TreeMap map = new TreeMap<>(); @@ -88,7 +88,7 @@ private ShotData interpolate(ShotData startValue, ShotData endValue, double t) { return new ShotData( Rotation2d.fromRadians( MathUtil.interpolate( - startValue.hoodRotation().getRadians(), endValue.hoodRotation().getRadians(), t)), + startValue.hoodAngle().getRadians(), endValue.hoodAngle().getRadians(), t)), MathUtil.interpolate( startValue.flywheelVelocityRotPerSec(), endValue.flywheelVelocityRotPerSec(), t), MathUtil.interpolate(startValue.flightTimeSec(), endValue.flightTimeSec(), t));