Skip to content

Commit 17a749b

Browse files
Changes from at the practice field on the morning of GSD load-in day, as well as changes made at the event on Thursday night: new "1-button" ShooterFiringSequency, enhancements and code-sharing of some autonomous programs,
1 parent 1e3550d commit 17a749b

17 files changed

+253
-77
lines changed

src/main/java/org/mayheminc/robot2020/RobotContainer.java

Lines changed: 16 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -106,18 +106,19 @@ private void configureDefaultCommands() {
106106
private void configureAutonomousPrograms() {
107107
LinkedList<Command> autonomousPrograms = new LinkedList<Command>();
108108

109-
autonomousPrograms.push(/* 11 */ new StayStill());
110-
autonomousPrograms.push(/* 10 */ new StartBWDriveOnlyToRP());
111-
autonomousPrograms.push(/* 09 */ new StartBWDriveOnlyToWall());
112-
autonomousPrograms.push(/* 08 */ new StartFWDriveOnlyToRP());
113-
autonomousPrograms.push(/* 07 */ new StartFWDriveOnlyToWall());
114-
autonomousPrograms.push(/* 06 */ new StartBWShoot3ThenToRP());
115-
autonomousPrograms.push(/* 05 */ new StartBWShoot3ThenToWall());
116-
autonomousPrograms.push(/* 04 */ new StartFWShoot3ThenToRP());
117-
autonomousPrograms.push(/* 03 */ new StartFWShoot3ThenToWall());
118-
autonomousPrograms.push(/* 02 */ new StartFWRendezvous());
119-
autonomousPrograms.push(/* 01 */ new StartBWOppTrench());
120-
autonomousPrograms.push(/* 00 */ new StartBWTrench());
109+
autonomousPrograms.push(/* 12 */ new StayStill());
110+
autonomousPrograms.push(/* 11 */ new StartBWDriveOnlyToRP());
111+
autonomousPrograms.push(/* 10 */ new StartBWDriveOnlyToWall());
112+
autonomousPrograms.push(/* 09 */ new StartFWDriveOnlyToRP());
113+
autonomousPrograms.push(/* 08 */ new StartFWDriveOnlyToWall());
114+
autonomousPrograms.push(/* 07 */ new StartBWShoot3ThenToRP());
115+
autonomousPrograms.push(/* 06 */ new StartBWShoot3ThenToWall());
116+
autonomousPrograms.push(/* 05 */ new StartFWShoot3ThenToRP());
117+
autonomousPrograms.push(/* 04 */ new StartFWShoot3ThenToWall());
118+
autonomousPrograms.push(/* 03 */ new StartFWRendezvous());
119+
autonomousPrograms.push(/* 02 */ new StartBWOppTrench());
120+
autonomousPrograms.push(/* 01 */ new StartBWTrench3());
121+
autonomousPrograms.push(/* 00 */ new StartBWTrench5());
121122

122123
autonomous.setAutonomousPrograms(autonomousPrograms);
123124

@@ -204,7 +205,9 @@ private void configureDriverPadButtons() {
204205
// TODO: above hard-coded constant (3000) should be a named constant from
205206
// Shooter.java
206207

207-
DRIVER_PAD.DRIVER_PAD_LEFT_UPPER_TRIGGER_BUTTON.whileHeld(new ShooterPermissionToFire());
208+
DRIVER_PAD.DRIVER_PAD_LEFT_UPPER_TRIGGER_BUTTON.whenHeld(new ShooterFiringSequence(60.0));
209+
DRIVER_PAD.DRIVER_PAD_LEFT_UPPER_TRIGGER_BUTTON.whenReleased(new ShooterCeaseFire());
210+
208211
DRIVER_PAD.DRIVER_PAD_LEFT_LOWER_TRIGGER_BUTTON.whileHeld(new FeederSet(1.0));
209212

210213
}

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

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@ public StartBWOppTrench() {
2727
// lower the intake and turn it on before driving forwards
2828
addCommands(new IntakeSetPosition(RobotContainer.intake.PIVOT_DOWN));
2929
addCommands(new IntakeSetRollers(-1.0));
30+
addCommands(new Wait(5.0));
3031

3132
// make sure the hood is down
3233
addCommands(new HoodSetAbsWhileHeld(Hood.TARGET_ZONE_POSITION));
@@ -51,7 +52,9 @@ public StartBWOppTrench() {
5152

5253
// turn on the intake gently while shooting to help balls settle
5354
addCommands(new IntakeSetRollers(-0.2));
54-
addCommands(new ShooterReadyAimFire(5.0));
55+
56+
// use the "one button" firing sequence
57+
addCommands(new ShooterFiringSequence(5.0));
5558

5659
// turn the shooter wheel and intake off now that the shooting is all done
5760
addCommands(new ShooterWheelSet(0.0));

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

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -31,12 +31,14 @@ public StartBWShoot3() {
3131
new HoodSetAbsWhileHeld(Hood.INITIATION_LINE_POSITION),
3232
new TurretSetAbs((180.0 * Turret.TICKS_PER_DEGREE), Turret.WAIT_FOR_DONE)));
3333

34-
addCommands(new ShooterReadyAimFire(1.5));
34+
addCommands(new ShooterFiringSequence(1.5));
35+
36+
// note that the above turns everything off again when it is done.
3537

3638
// turn the shooter wheel and intake off now that the shooting is all done
37-
addCommands(new ParallelCommandGroup( // below commands in parallel
38-
new ShooterWheelSet(0.0), //
39-
new IntakeSetRollers(0.0), // turn off the rollers
40-
new HoodSetAbs(Hood.STARTING_POSITION)));
39+
// addCommands(new ParallelRaceGroup( // below commands in parallel
40+
// new ShooterWheelSet(0.0), //
41+
// new IntakeSetRollers(0.0), // turn off the rollers
42+
// new HoodSetAbs(Hood.STARTING_POSITION)));
4143
}
4244
}

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

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -19,13 +19,14 @@ public class StartBWTrench extends SequentialCommandGroup {
1919
/**
2020
* Add your docs here.
2121
*/
22-
public StartBWTrench() {
22+
public StartBWTrench(double extraDistance) {
23+
// Note: extra distance planned to be 40 inches
2324

2425
// start backwards and shoot the first three balls
2526
addCommands(new StartBWShoot3());
2627

2728
// then, drive to the trench entrance (jog left a little to get there)
28-
addCommands(new DriveStraightOnHeading(0.5, DistanceUnits.INCHES, 40, 150));
29+
addCommands(new DriveStraightOnHeading(0.4, DistanceUnits.INCHES, 46, 140));
2930

3031
// pick up balls while heading down the trench.
3132
addCommands(new ParallelCommandGroup(
@@ -34,7 +35,7 @@ public StartBWTrench() {
3435
// ensure the hood is down
3536
new HoodSetAbsWhileHeld(Hood.STARTING_POSITION),
3637
// drive the path under the control panel to the end
37-
new DriveStraightOnHeading(0.3, DistanceUnits.INCHES, 180, 180)));
38+
new DriveStraightOnHeading(0.3, DistanceUnits.INCHES, 140 + extraDistance, 180)));
3839

3940
// now driven to the balls at far end of trench
4041
addCommands(new Wait(0.8), // wait for last two balls to get into robot
@@ -44,7 +45,7 @@ public StartBWTrench() {
4445

4546
// after getting all three balls, go back to shooting position
4647
// first, make sure we drive straight out from under the control panel
47-
addCommands(new DriveStraightOnHeading(-0.5, DistanceUnits.INCHES, 48, 180));
48+
addCommands(new DriveStraightOnHeading(-0.6, DistanceUnits.INCHES, 8 + extraDistance, 180));
4849

4950
// drive diagonally over towards the shooting position, while turning on shooter
5051
// wheels, raising the hood, and re-aiming the turret
@@ -61,7 +62,7 @@ public StartBWTrench() {
6162
addCommands(new IntakeSetRollers(-0.2));
6263

6364
// start the shooting sequence
64-
addCommands(new ShooterReadyAimFire(6.0));
65+
addCommands(new ShooterFiringSequence(6.0));
6566

6667
// turn the shooter wheel and intake off now that the shooting is all done
6768
addCommands(new ShooterWheelSet(0.0));
Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
/*----------------------------------------------------------------------------*/
2+
/* Copyright (c) 2018 FIRST. All Rights Reserved. */
3+
/* Open Source Software - may be modified and shared by FRC teams. The code */
4+
/* must be accompanied by the FIRST BSD license file in the root directory of */
5+
/* the project. */
6+
/*----------------------------------------------------------------------------*/
7+
8+
package org.mayheminc.robot2020.autonomousroutines;
9+
10+
import edu.wpi.first.wpilibj2.command.*;
11+
12+
public class StartBWTrench3 extends SequentialCommandGroup {
13+
/**
14+
* Add your docs here.
15+
*/
16+
public StartBWTrench3() {
17+
addCommands(new StartBWTrench(0.0)); // use extraDistance of 0 inches to stop before control panel
18+
}
19+
}
Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
/*----------------------------------------------------------------------------*/
2+
/* Copyright (c) 2018 FIRST. All Rights Reserved. */
3+
/* Open Source Software - may be modified and shared by FRC teams. The code */
4+
/* must be accompanied by the FIRST BSD license file in the root directory of */
5+
/* the project. */
6+
/*----------------------------------------------------------------------------*/
7+
8+
package org.mayheminc.robot2020.autonomousroutines;
9+
10+
import edu.wpi.first.wpilibj2.command.*;
11+
12+
public class StartBWTrench5 extends SequentialCommandGroup {
13+
/**
14+
* Add your docs here.
15+
*/
16+
public StartBWTrench5() {
17+
addCommands(new StartBWTrench(40)); // use extraDistance of 40 inches for control panel
18+
}
19+
}

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

Lines changed: 12 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,8 @@ public StartFWRendezvous() {
2525
// start out facing in the normal direction
2626
addCommands(new DriveZeroGyro(0.0));
2727

28+
addCommands(new IntakeSetPosition(RobotContainer.intake.PIVOT_DOWN));
29+
2830
// shoot the 3 balls we started with
2931
// first, lower the intake, start the shooter wheel, and wait until the turret
3032
// is turned towards the target
@@ -34,7 +36,7 @@ public StartFWRendezvous() {
3436
new HoodSetAbs(Hood.INITIATION_LINE_POSITION),
3537
new TurretSetAbs((10.0 * Turret.TICKS_PER_DEGREE), Turret.WAIT_FOR_DONE)));
3638

37-
addCommands(new ShooterReadyAimFire(1.0));
39+
addCommands(new ShooterFiringSequence(1.5));
3840

3941
// drive a little bit out to get away from other robots.
4042
addCommands(new DriveStraightOnHeading(-0.2, DistanceUnits.INCHES, 36, 30));
@@ -43,13 +45,17 @@ public StartFWRendezvous() {
4345
// further
4446
addCommands(new IntakeSetPosition(RobotContainer.intake.PIVOT_DOWN));
4547

46-
// rais the hood a little to shoot from this increased distance
48+
// raise the hood a little to shoot from this increased distance
4749
addCommands(new HoodSetAbsWhileHeld((Hood.INITIATION_LINE_POSITION + Hood.TRENCH_MID_POSITION) / 2.0));
48-
addCommands(new DriveStraightOnHeading(-0.3, DistanceUnits.INCHES, 144, 50));
50+
addCommands(new DriveStraightOnHeading(-0.3, DistanceUnits.INCHES, 124, 40));
4951

5052
// turn on the intake to pick up balls
5153
addCommands(new IntakeSetRollers(-1.0));
52-
addCommands(new DriveStraightOnHeading(0.3, DistanceUnits.INCHES, 84, 30));
54+
addCommands(new DriveStraightOnHeading(0.15, DistanceUnits.INCHES, 72, 65));
55+
56+
// back up to get free of the boundary post, then turn and drive towards goal
57+
addCommands(new DriveStraightOnHeading(-0.1, DistanceUnits.INCHES, 16, 20));
58+
addCommands(new DriveStraightOnHeading(+0.2, DistanceUnits.INCHES, 48, 20));
5359

5460
// now driven to get the balls, stay here and shoot them
5561
addCommands(new Wait(0.8), // wait for the balls to get into robot
@@ -58,11 +64,11 @@ public StartFWRendezvous() {
5864
// in shooting position, prepare everything for shooting
5965
addCommands(new ParallelCommandGroup( // run the following commands in parallel:
6066
new ShooterWheelSet(ShooterWheel.SHOOTER_WHEEL_TRENCH_FRONT_SPEED),
61-
new TurretSetAbs((-40.0 * Turret.TICKS_PER_DEGREE), Turret.WAIT_FOR_DONE)));
67+
new TurretSetAbs((0.0 * Turret.TICKS_PER_DEGREE), Turret.WAIT_FOR_DONE)));
6268

6369
// turn on the intake gently while shooting to help balls settle
6470
addCommands(new IntakeSetRollers(-0.2));
65-
addCommands(new ShooterReadyAimFire(5.0));
71+
addCommands(new ShooterFiringSequence(6.0));
6672

6773
// turn the shooter wheel and intake off now that the shooting is all done
6874
addCommands(new ShooterWheelSet(0.0));

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

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,9 +9,9 @@
99

1010
import org.mayheminc.robot2020.RobotContainer;
1111

12-
import edu.wpi.first.wpilibj2.command.InstantCommand;
12+
import edu.wpi.first.wpilibj2.command.CommandBase;
1313

14-
public class HoodSetAbsWhileHeld extends InstantCommand {
14+
public class HoodSetAbsWhileHeld extends CommandBase {
1515
double m_set;
1616

1717
/**
@@ -30,4 +30,9 @@ public void initialize() {
3030
RobotContainer.hood.setPosition(m_set);
3131
}
3232

33+
@Override
34+
public boolean isFinished() {
35+
return true;
36+
}
37+
3338
}

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

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -8,15 +8,18 @@
88
*
99
*/
1010
public class PrintAutonomousTimeRemaining extends CommandBase {
11-
String Message = "";
11+
String Message = "";
12+
1213
public PrintAutonomousTimeRemaining(String msg) {
1314
this.Message = msg;
1415
}
15-
16+
1617
// Called just before this Command runs the first time
1718
@Override
1819
public void initialize() {
19-
// DriverStation.reportError(Message + " At: " + Robot.autonomousTimeRemaining() + "\n", false);
20+
21+
// DriverStation.reportError(Message + " At: " + Robot.autonomousTimeRemaining()
22+
// + "\n", false);
2023
}
2124

2225
// Make this return true when this Command no longer needs to run execute()

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

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@ public class ShooterAimToTarget extends CommandBase {
1818
public ShooterAimToTarget() {
1919
// Use addRequirements() here to declare subsystem dependencies.
2020
addRequirements(RobotContainer.hood);
21-
addRequirements(RobotContainer.shooterWheel);
2221
addRequirements(RobotContainer.turret);
2322
}
2423

@@ -42,7 +41,7 @@ public void execute() {
4241
@Override
4342
public void end(boolean interrupted) {
4443
if (!interrupted) {
45-
RobotContainer.shooterWheel.setSpeed(RobotContainer.targeting.getDesiredWheelSpeed());
44+
// RobotContainer.shooterWheel.setSpeed(RobotContainer.targeting.getDesiredWheelSpeed());
4645

4746
// want to also schedule a command here that does the shooting!
4847
}

0 commit comments

Comments
 (0)