Skip to content

Commit 1825564

Browse files
Tweaked aim point a little bit to the right by setting to 0.510 (had been missing to the left slightly when at 0.500) Also added a "waitDuration" to ShooterReadyAimFire, and put some initial waitDurations into the "TrenchAuto."
1 parent 8cd54cb commit 1825564

File tree

3 files changed

+5
-5
lines changed

3 files changed

+5
-5
lines changed

src/main/java/org/mayheminc/robot2020/autonomousroutines/TrenchAuto.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ public TrenchAuto() {
2424
// first, shoot the balls that were pre-loaded
2525

2626
addCommands(new IntakeSetPositionWithoutWaiting(RobotContainer.intake.PIVOT_DOWN));
27-
addCommands(new ShooterReadyAimFire());
27+
addCommands(new ShooterReadyAimFire(3.0));
2828

2929
// then, perform a 3-point turn
3030
addCommands(new DriveStraightOnHeading(0.3, DistanceUnits.INCHES, 48, 160));
@@ -41,7 +41,7 @@ public TrenchAuto() {
4141
addCommands(new DriveStraightOnHeading(0.3, DistanceUnits.INCHES, 120, 0));
4242
addCommands(new DriveStraightOnHeading(-0.1, DistanceUnits.INCHES, 6, 0));
4343

44-
addCommands(new ShooterReadyAimFire());
44+
addCommands(new ShooterReadyAimFire(6.0));
4545

4646
// turn the wheel off now that the shooting is all done
4747
addCommands( new ShooterSetWheel(0.0));

src/main/java/org/mayheminc/robot2020/commands/ShooterReadyAimFire.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@ public class ShooterReadyAimFire extends SequentialCommandGroup {
2020
/**
2121
* Creates a new ShooterReadyAimFire.
2222
*/
23-
public ShooterReadyAimFire() {
23+
public ShooterReadyAimFire(double waitDuration) {
2424
// Add your commands in the super() call, e.g.
2525
// super(new FooCommand(), new BarCommand());
2626
super();
@@ -43,7 +43,7 @@ public ShooterReadyAimFire() {
4343
new ShooterSetFeeder(1.0),
4444
new SequentialCommandGroup(new Wait(0.1), new ChimneySetChimney(0.5)),
4545
new SequentialCommandGroup(new Wait(0.2), new MagazineSetTurntable(0.3)),
46-
new Wait(6.0)));
46+
new Wait(waitDuration)));
4747

4848
addCommands(new ParallelRaceGroup(
4949
new MagazineSetTurntable(0.0),

src/main/java/org/mayheminc/robot2020/subsystems/Targeting.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ public class Targeting extends SubsystemBase {
3131
private final static double FOV_HORIZ_CAMERA_IN_DEGREES = 76.5;
3232

3333
// Define the "target location" to be halfway from left to right
34-
private final double CENTER_OF_TARGET_X = 0.5;
34+
private final double CENTER_OF_TARGET_X = 0.510;
3535

3636
// Calculate ticks per degree.
3737
// encoder ticks * turret pulley teeth / drive pulley teeth / 360 degrees

0 commit comments

Comments
 (0)