Skip to content

Commit 9728aa2

Browse files
committed
note ejection code, commented out
easier naming in robotcontainer (cmon guys)
1 parent 6cbd105 commit 9728aa2

File tree

4 files changed

+91
-34
lines changed

4 files changed

+91
-34
lines changed

src/main/java/frc/team3128/RobotContainer.java

Lines changed: 73 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,11 @@
5959
public class RobotContainer {
6060

6161
private Swerve swerve;
62+
private Hopper hopper;
63+
private Intake intake;
64+
private Shooter shooter;
65+
66+
6267
private Leds leds;
6368

6469
// private NAR_ButtonBoard judgePad;
@@ -82,8 +87,13 @@ public RobotContainer() {
8287
controller = new NAR_XboxController(2);
8388
buttonPad = new NAR_ButtonBoard(3);
8489

90+
swerve = Swerve.getInstance();
91+
hopper = Hopper.getInstance();
92+
intake = Intake.getInstance();
93+
shooter = Shooter.getInstance();
94+
8595
//uncomment line below to enable driving
86-
CommandScheduler.getInstance().setDefaultCommand(Swerve.getInstance(), new CmdSwerveDrive(controller::getLeftX,controller::getLeftY, controller::getRightX, true));
96+
CommandScheduler.getInstance().setDefaultCommand(swerve, new CmdSwerveDrive(controller::getLeftX,controller::getLeftY, controller::getRightX, true));
8797

8898
initRobotTest();
8999

@@ -116,55 +126,87 @@ private void configureButtonBindings() {
116126

117127
controller.getButton(XboxButton.kLeftTrigger).onTrue(intake(Intake.Setpoint.GROUND));
118128
controller.getButton(XboxButton.kLeftBumper).onTrue(retractIntake());
119-
controller.getButton(XboxButton.kRightTrigger).onTrue(Shooter.getInstance().rampUpShooter()).onFalse(Shooter.getInstance().setShooting(true));
129+
controller.getButton(XboxButton.kRightTrigger).onTrue(shooter.rampUpShooter()).onFalse(shooter.setShooting(true));
120130

121-
controller.getButton(XboxButton.kA).onTrue(Shooter.getInstance().runShooter(0.8));
122-
controller.getButton(XboxButton.kY).onTrue(Shooter.getInstance().runShooter(0));
123-
controller.getButton(XboxButton.kB).onTrue(Shooter.getInstance().runKickMotor(KICK_SHOOTING_POWER)).onFalse(Shooter.getInstance().runKickMotor(0));
131+
controller.getButton(XboxButton.kA).onTrue(shooter.runShooter(0.8));
132+
controller.getButton(XboxButton.kY).onTrue(shooter.runShooter(0));
133+
controller.getButton(XboxButton.kB).onTrue(shooter.runKickMotor(KICK_SHOOTING_POWER)).onFalse(shooter.runKickMotor(0));
124134

125135
controller.getButton(XboxButton.kY).whileTrue(ampUp()).onFalse(ampFinAndDown());
126136

127137

128138
// new Trigger(()->true).onTrue(queueNote());
129139

130-
new Trigger(()-> Shooter.getInstance().getShooting())
140+
//Shooting
141+
new Trigger(()-> shooter.getShooting())
131142
.onTrue(sequence(
132-
Shooter.getInstance().runKickMotor(KICK_POWER),
133-
Hopper.getInstance().runManipulator(.8)
143+
shooter.runKickMotor(KICK_POWER),
144+
hopper.runManipulator(.8)
134145
))
135146
.onFalse(sequence(
136-
Shooter.getInstance().runKickMotor(0),
137-
Hopper.getInstance().runManipulator(0),
138-
Shooter.getInstance().stopMotors()
147+
hopper.runManipulator(0),
148+
shooter.stopMotors()
139149
));
140150

141-
new Trigger(()-> Shooter.getInstance().noteInRollers()).negate()
142-
.and(()->Hopper.getInstance().hasObjectPresent()).negate()
143-
.onTrue(Shooter.getInstance().setShooting(false));
144-
145-
new Trigger(()-> Intake.getInstance().getMeasurement() > 90)
146-
.and(()->!Hopper.getInstance().hasObjectPresent())
147-
.onTrue(Hopper.getInstance().runManipulator(HOPPER_INTAKE_POWER))
148-
.onFalse(Hopper.getInstance().runManipulator(0));
149-
150-
new Trigger(()-> Intake.getInstance().getMeasurement() < 20)
151-
.and(()->Hopper.getInstance().hasObjectPresent()).negate()
152-
.onTrue(Hopper.getInstance().runManipulator(0));
153-
154-
new Trigger(()-> Shooter.getInstance().noteInRollers()).negate()
155-
.and(()->Hopper.getInstance().hasObjectPresent())
156-
.and(() -> !Shooter.getInstance().getShooting())
151+
//Stops shooting when all notes are gone
152+
new Trigger(()-> shooter.noteInRollers()).negate()
153+
.and(()->hopper.hasObjectPresent()).negate()
154+
.onTrue(shooter.setShooting(false));
155+
156+
//Queues note to hopper
157+
new Trigger(()-> intake.getMeasurement() > 90)
158+
.and(()->!hopper.hasObjectPresent())
159+
.onTrue(hopper.runManipulator(HOPPER_INTAKE_POWER))
160+
.onFalse(hopper.runManipulator(0));
161+
162+
//Stops hopper if intake is retracted and is empty
163+
new Trigger(()-> intake.getMeasurement() < 20)
164+
.and(()->hopper.hasObjectPresent()).negate()
165+
.onTrue(hopper.runManipulator(0));
166+
167+
//Queues note to shooter
168+
new Trigger(()-> shooter.noteInRollers()).negate()
169+
.and(()->hopper.hasObjectPresent())
170+
.and(() -> !shooter.getShooting())
157171
.onTrue(sequence(
158-
Shooter.getInstance().runKickMotor(KICK_POWER),
159-
Hopper.getInstance().runManipulator(HOPPER_INTAKE_POWER)
172+
shooter.runKickMotor(KICK_POWER),
173+
hopper.runManipulator(HOPPER_INTAKE_POWER)
160174
))
161175
.onFalse(sequence(
162-
Shooter.getInstance().runKickMotor(-.1),
176+
shooter.runKickMotor(-.1),
163177
waitSeconds(.1),
164-
Shooter.getInstance().runKickMotor(0)
178+
shooter.runKickMotor(0)
165179
));
166180

181+
// new Trigger(() -> shouldEjectNote()).onTrue(ejectNote());
182+
183+
}
184+
185+
private Timer ejecTimer = new Timer();
186+
private boolean ejectTimerStarted = false;
167187

188+
private boolean shouldEjectNote(){
189+
if(shooter.noteInRollers() && hopper.hasObjectPresent() && !ejectTimerStarted){
190+
ejectTimerStarted = true;
191+
ejecTimer.start();
192+
}
193+
194+
else if(shooter.noteInRollers() && hopper.hasObjectPresent() && ejectTimerStarted){
195+
if(ejecTimer.hasElapsed(2)){
196+
ejectTimerStarted = false;
197+
ejecTimer.stop();
198+
ejecTimer.reset();
199+
return true;
200+
}
201+
}
202+
203+
else{
204+
ejectTimerStarted = false;
205+
ejecTimer.stop();
206+
ejecTimer.reset();
207+
}
208+
209+
return false;
168210
}
169211

170212
@SuppressWarnings("unused")

src/main/java/frc/team3128/commands/CmdManager.java

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
import common.hardware.input.NAR_XboxController;
1010
import edu.wpi.first.wpilibj.DriverStation.Alliance;
1111
import edu.wpi.first.wpilibj2.command.Command;
12+
import edu.wpi.first.wpilibj2.command.CommandScheduler;
1213
import edu.wpi.first.wpilibj2.command.ScheduleCommand;
1314
import edu.wpi.first.wpilibj2.command.StartEndCommand;
1415
import frc.team3128.Robot;
@@ -174,4 +175,17 @@ public static Command ampFinAndDown(){
174175
amper.retract()
175176
);
176177
}
178+
179+
public static Command ejectNote(){
180+
CommandScheduler.getInstance().cancel(CommandScheduler.getInstance().requiring(hopper));
181+
CommandScheduler.getInstance().cancel(CommandScheduler.getInstance().requiring(intake));
182+
return sequence(
183+
intake.stopRollers(),
184+
intake.retract(),
185+
waitSeconds(0.3),
186+
hopper.runManipulator(HOPPER_OUTTAKE_POWER),
187+
waitSeconds(0.2),
188+
hopper.runManipulator(0)
189+
);
190+
}
177191
}

src/main/java/frc/team3128/subsystems/Amper.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,8 @@ private Amper() {
3939
super(new TrapController(PIDConstants, TRAP_CONSTRAINTS), ELEV_MOTOR);
4040

4141
//TODO: remove once done testing
42-
this.setSafetyThresh(100);
42+
// this.setSafetyThresh(100);
43+
4344
// setkG_Function(() -> getMeasurement()*Math.sin(AMPER_ANGLE));
4445

4546
setTolerance(POSITION_TOLERANCE);

src/main/java/frc/team3128/subsystems/Intake.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -41,11 +41,11 @@ private Intake() {
4141

4242
setTolerance(ANGLE_TOLERANCE);
4343
setConstraints(MIN_SETPOINT, MAX_SETPOINT);
44-
setSafetyThresh(5);
44+
// setSafetyThresh(5);
4545
// initShuffleboard();
4646

4747
//TODO: remove once done testing
48-
this.setSafetyThresh(1000);
48+
// this.setSafetyThresh(1000);
4949

5050
}
5151

0 commit comments

Comments
 (0)