Skip to content

Commit

Permalink
New Auto Aim
Browse files Browse the repository at this point in the history
  • Loading branch information
cherriae committed Oct 7, 2024
1 parent 618ba75 commit d57cdb6
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 5 deletions.
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ public static class Speeds {
public static final double SHOOTER_FAST_SPIN_SPEED = 1;
public static final double SHOOTER_SLOW_SPIN_SPEED = 0.8;
public static final double SHOOTER_AMP_SPEED = 1;
public static final double SHOOTER_AMP_SLOW_SPEED = 0.5;
public static final double SHOOTER_AMP_SLOW_SPEED = 0.3;
public static final double SHOOTER_INTAKE_SPEED = -0.15;
public static final double SHOOTER_IDLE_SPEED = 0.3;

Expand Down Expand Up @@ -153,8 +153,8 @@ public static class Presets {

public static final double ELEVATOR_HEIGHT_RATE = -0.025;

public static final double SHOOTER_AMP_HANDOFF = 50;
public static final double ELEVATOR_AMP_HANDOFF = 0.045;
public static final double SHOOTER_AMP_HANDOFF = 85;
public static final double ELEVATOR_AMP_HANDOFF = 0.120;

public static final InterpolatingDoubleTreeMap SHOOTER_DISTANCE_ANGLE = new InterpolatingDoubleTreeMap();

Expand Down
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/commands/auto/AutoAmp.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,10 @@
package frc.robot.commands.auto;

import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import frc.robot.commands.elevator.SetElevator;
import frc.robot.commands.intake.FeedActuate;
import frc.robot.commands.shooter.SpinShooter;
import frc.robot.subsystems.ElevatorSubsystem;
import frc.robot.subsystems.IntakeSubsystem;
import frc.robot.subsystems.ShooterSubsystem;
import frc.robot.subsystems.IntakeSubsystem.ActuatorState;
Expand All @@ -26,7 +28,8 @@ public AutoAmp(
// Add your commands in the addCommands() call, e.g.
// addCommands(new FooCommand(), new BarCommand());
addCommands(
new SpinShooter(shooter, ShooterState.AMP, false).withTimeout(0.20),
new FeedActuate(intake, FeedMode.INTAKE).withTimeout(0.3),
new SpinShooter(shooter, ShooterState.SLOW, false).withTimeout(1.00),
new FeedActuate(intake, ActuatorState.STOWED, FeedMode.OUTTAKE).withTimeout(0.5)
// new SpinShooter(shooter, ShooterState.SLOW, false).withTimeout(0.1)
);
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ public ShooterSubsystem() {
// soft limits
SoftwareLimitSwitchConfigs softLimits = new SoftwareLimitSwitchConfigs();

softLimits.ForwardSoftLimitThreshold = 65 * Constants.Physical.SHOOTER_ANGLE_GEAR_RATIO / 360;
softLimits.ForwardSoftLimitThreshold = 85 * Constants.Physical.SHOOTER_ANGLE_GEAR_RATIO / 360;
softLimits.ReverseSoftLimitThreshold = -25 * Constants.Physical.SHOOTER_ANGLE_GEAR_RATIO / 360;

softLimits.ForwardSoftLimitEnable = true;
Expand Down

0 comments on commit d57cdb6

Please sign in to comment.