Skip to content

Commit 0038847

Browse files
committed
End of competition
1 parent 155e8a4 commit 0038847

File tree

7 files changed

+29
-21
lines changed

7 files changed

+29
-21
lines changed

src/main/java/org/aluminati3555/frc2020/auto/actions/ActionAlignWithVision.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ public class ActionAlignWithVision implements AluminatiAutoTask {
3939
* Initializes the PID controller
4040
*/
4141
public static final void initialize() {
42-
controller = new AluminatiTuneablePIDController(5809, 0.2, 0, 0, 400, 1, 0.6, 0);
42+
controller = new AluminatiTuneablePIDController(5809, 0.05, 0, 0, 400, 1, 0.6, 0);
4343
}
4444

4545
private DriveSystem driveSystem;

src/main/java/org/aluminati3555/frc2020/auto/actions/ActionTurnToHeading.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ public class ActionTurnToHeading implements AluminatiAutoTask {
4040
* Initializes the PID controller
4141
*/
4242
public static final void initialize() {
43-
controller = new AluminatiPIDController(0.2, 0, 0, 400, 1, 1, 0);
43+
controller = new AluminatiPIDController(0.05, 0, 0, 400, 1, 0.6, 0);
4444
}
4545

4646
private DriveSystem driveSystem;

src/main/java/org/aluminati3555/frc2020/auto/modes/Mode3PowerCell.java

+2-2
Original file line numberDiff line numberDiff line change
@@ -77,10 +77,10 @@ public Mode3PowerCell(AluminatiLimelight limelight, DriveSystem driveSystem,
7777
taskList.add(new ActionSetLimelightPipeline(limelight, 1));
7878

7979
// Shoot three power cells
80-
taskList.add(new ActionExtendHood(shooterSystem));
80+
//taskList.add(new ActionExtendHood(shooterSystem));
8181
taskList.add(new ActionAlignWithVision(driveSystem, limelight));
8282
taskList.add(new ActionShootPowerCell(limelight, shooterSystem, magazineSystem, 3));
83-
taskList.add(new ActionRetractHood(shooterSystem));
83+
//taskList.add(new ActionRetractHood(shooterSystem));
8484

8585
// Set the limelight to the driver pipeline
8686
taskList.add(new ActionSetLimelightPipeline(limelight, 0));

src/main/java/org/aluminati3555/frc2020/auto/modes/Mode3PowerCellGoForward.java

+2-2
Original file line numberDiff line numberDiff line change
@@ -117,10 +117,10 @@ public Mode3PowerCellGoForward(RobotState robotState, AluminatiLimelight limelig
117117
taskList.add(new ActionSetLimelightPipeline(limelight, 1));
118118

119119
// Shoot three power cells
120-
taskList.add(new ActionExtendHood(shooterSystem));
120+
//taskList.add(new ActionExtendHood(shooterSystem));
121121
taskList.add(new ActionAlignWithVision(driveSystem, limelight));
122122
taskList.add(new ActionShootPowerCell(limelight, shooterSystem, magazineSystem, 3));
123-
taskList.add(new ActionRetractHood(shooterSystem));
123+
//taskList.add(new ActionRetractHood(shooterSystem));
124124

125125
// Set the limelight to the driver pipeline
126126
taskList.add(new ActionSetLimelightPipeline(limelight, 0));

src/main/java/org/aluminati3555/frc2020/auto/modes/Mode3PowerCellPositionTrenchRun.java

+2-2
Original file line numberDiff line numberDiff line change
@@ -117,10 +117,10 @@ public Mode3PowerCellPositionTrenchRun(RobotState robotState, AluminatiLimelight
117117
taskList.add(new ActionSetLimelightPipeline(limelight, 1));
118118

119119
// Shoot three power cells
120-
taskList.add(new ActionExtendHood(shooterSystem));
120+
//taskList.add(new ActionExtendHood(shooterSystem));
121121
taskList.add(new ActionAlignWithVision(driveSystem, limelight));
122122
taskList.add(new ActionShootPowerCell(limelight, shooterSystem, magazineSystem, 3));
123-
taskList.add(new ActionRetractHood(shooterSystem));
123+
//taskList.add(new ActionRetractHood(shooterSystem));
124124

125125
// Set the limelight to the driver pipeline
126126
taskList.add(new ActionSetLimelightPipeline(limelight, 0));

src/main/java/org/aluminati3555/frc2020/systems/IntakeSystem.java

+11
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,8 @@
3737
* @author Caleb Heydon
3838
*/
3939
public class IntakeSystem implements AluminatiSystem {
40+
private static final int INTAKE_CURRENT_LIMIT = 50;
41+
4042
private AluminatiTalonSRX intakeMotor;
4143
private AluminatiSolenoid extenderSolenoid;
4244

@@ -152,6 +154,15 @@ public void update(double timestamp, SystemMode mode) {
152154
public IntakeSystem(AluminatiTalonSRX intakeMotor, AluminatiSolenoid extenderSolenoid,
153155
AluminatiXboxController operatorController, MagazineSystem magazineSystem, RobotFaults robotFaults) {
154156
this.intakeMotor = intakeMotor;
157+
158+
// Configure current limit
159+
this.intakeMotor.configPeakCurrentDuration(500);
160+
this.intakeMotor.configPeakCurrentLimit(INTAKE_CURRENT_LIMIT);
161+
this.intakeMotor.configContinuousCurrentLimit(INTAKE_CURRENT_LIMIT);
162+
this.intakeMotor.enableCurrentLimit(true);
163+
164+
this.intakeMotor.configOpenloopRamp(0.1);
165+
155166
this.extenderSolenoid = extenderSolenoid;
156167

157168
this.operatorController = operatorController;

src/main/java/org/aluminati3555/frc2020/systems/ShooterSystem.java

+10-13
Original file line numberDiff line numberDiff line change
@@ -208,6 +208,13 @@ public void update(double timestamp, SystemMode mode) {
208208
}
209209

210210
if (mode == SystemMode.OPERATOR_CONTROLLED) {
211+
// Do hood control
212+
if (operatorController.getY(Hand.kLeft) >= 0.5) {
213+
retractHood();
214+
} else {
215+
extendHood();
216+
}
217+
211218
if (driverController.getTriggerAxis(Hand.kLeft) >= 0.5) {
212219
// Driver wants the robot to align with vision target and flywheel to get up to
213220
// speed
@@ -234,9 +241,6 @@ public void update(double timestamp, SystemMode mode) {
234241
driveSystem.setVisionTracking(false);
235242
}
236243

237-
// Extend hood
238-
extendHood();
239-
240244
// Set flywheel speed
241245
double targetHeight = limelight.getVertical();
242246
// double rpm = limelight.hasTarget() ? ShooterUtil.calculateRPM(targetHeight) :
@@ -259,9 +263,6 @@ public void update(double timestamp, SystemMode mode) {
259263

260264
wasTracking = false;
261265

262-
// Extend hood to mid position
263-
extendHoodMid();
264-
265266
// Set flywheel speed
266267
set(SHORT_SHOT_RPM);
267268

@@ -281,9 +282,6 @@ public void update(double timestamp, SystemMode mode) {
281282
// Stop feeding power cells
282283
magazineSystem.stopFeedingPowerCells();
283284

284-
// Retract hood
285-
retractHood();
286-
287285
// Disable flywheel
288286
stop();
289287
}
@@ -349,7 +347,7 @@ public void update(double timestamp, SystemMode mode) {
349347
break;
350348
case NONE:
351349
if (hoodPosition == HoodPosition.DOWN) {
352-
hoodMotor.set(0.02);
350+
hoodMotor.set(0.05);
353351
} else {
354352
hoodMotor.set(0);
355353
}
@@ -375,10 +373,9 @@ public ShooterSystem(AluminatiMotorGroup motorGroup, AluminatiSpark hoodMotor,
375373

376374
this.robotFaults = robotFaults;
377375

378-
this.hoodPosition = HoodPosition.UNKNOWN;
376+
this.hoodPosition = HoodPosition.UP;
379377
this.hoodAction = HoodAction.NONE;
380378
this.hoodActionList = new ArrayList<HoodAction>();
381-
this.hoodActionList.add(HoodAction.RETRACT);
382379

383380
this.wasTracking = false;
384381

@@ -414,7 +411,7 @@ protected void update(TuningData data) {
414411
this.motorGroup.getMasterTalon().configContinuousCurrentLimit(SHOOTER_CURRENT_LIMIT);
415412
this.motorGroup.getMasterTalon().enableCurrentLimit(true);
416413

417-
this.turnController = new AluminatiTuneablePIDController(5808, 0.2, 0, 0, 400, 1, 1, 0);
414+
this.turnController = new AluminatiTuneablePIDController(5808, 0.05, 0, 0, 400, 1, 0.6, 0);
418415
}
419416

420417
public enum HoodPosition {

0 commit comments

Comments
 (0)