Skip to content

Commit d57cdb6

Browse files
committed
New Auto Aim
1 parent 618ba75 commit d57cdb6

File tree

3 files changed

+8
-5
lines changed

3 files changed

+8
-5
lines changed

src/main/java/frc/robot/Constants.java

+3-3
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,7 @@ public static class Speeds {
7171
public static final double SHOOTER_FAST_SPIN_SPEED = 1;
7272
public static final double SHOOTER_SLOW_SPIN_SPEED = 0.8;
7373
public static final double SHOOTER_AMP_SPEED = 1;
74-
public static final double SHOOTER_AMP_SLOW_SPEED = 0.5;
74+
public static final double SHOOTER_AMP_SLOW_SPEED = 0.3;
7575
public static final double SHOOTER_INTAKE_SPEED = -0.15;
7676
public static final double SHOOTER_IDLE_SPEED = 0.3;
7777

@@ -153,8 +153,8 @@ public static class Presets {
153153

154154
public static final double ELEVATOR_HEIGHT_RATE = -0.025;
155155

156-
public static final double SHOOTER_AMP_HANDOFF = 50;
157-
public static final double ELEVATOR_AMP_HANDOFF = 0.045;
156+
public static final double SHOOTER_AMP_HANDOFF = 85;
157+
public static final double ELEVATOR_AMP_HANDOFF = 0.120;
158158

159159
public static final InterpolatingDoubleTreeMap SHOOTER_DISTANCE_ANGLE = new InterpolatingDoubleTreeMap();
160160

src/main/java/frc/robot/commands/auto/AutoAmp.java

+4-1
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,10 @@
66
package frc.robot.commands.auto;
77

88
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
9+
import frc.robot.commands.elevator.SetElevator;
910
import frc.robot.commands.intake.FeedActuate;
1011
import frc.robot.commands.shooter.SpinShooter;
12+
import frc.robot.subsystems.ElevatorSubsystem;
1113
import frc.robot.subsystems.IntakeSubsystem;
1214
import frc.robot.subsystems.ShooterSubsystem;
1315
import frc.robot.subsystems.IntakeSubsystem.ActuatorState;
@@ -26,7 +28,8 @@ public AutoAmp(
2628
// Add your commands in the addCommands() call, e.g.
2729
// addCommands(new FooCommand(), new BarCommand());
2830
addCommands(
29-
new SpinShooter(shooter, ShooterState.AMP, false).withTimeout(0.20),
31+
new FeedActuate(intake, FeedMode.INTAKE).withTimeout(0.3),
32+
new SpinShooter(shooter, ShooterState.SLOW, false).withTimeout(1.00),
3033
new FeedActuate(intake, ActuatorState.STOWED, FeedMode.OUTTAKE).withTimeout(0.5)
3134
// new SpinShooter(shooter, ShooterState.SLOW, false).withTimeout(0.1)
3235
);

src/main/java/frc/robot/subsystems/ShooterSubsystem.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,7 @@ public ShooterSubsystem() {
8383
// soft limits
8484
SoftwareLimitSwitchConfigs softLimits = new SoftwareLimitSwitchConfigs();
8585

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

8989
softLimits.ForwardSoftLimitEnable = true;

0 commit comments

Comments
 (0)