Skip to content
This repository was archived by the owner on Sep 14, 2019. It is now read-only.

Commit 6d529c6

Browse files
committed
simplified intakeEject open/close code
made toggleRightIntake and toggleLeftIntake simpler --> just uses booleans but does put result into a pref kForward now = closed and kReverse = closed (as it actually is in real life) changed a few SD keys in RobotMap for intake solenoid ports to be clearer as to what they should be "drawbacks": toggle methods do not take inversion into account, but having that is the same as being able to change ports through SD (which we do have the capability to do); needs testing to see if ports are correct
1 parent ffdfb12 commit 6d529c6

File tree

2 files changed

+40
-64
lines changed

2 files changed

+40
-64
lines changed

Robot2018/src/org/usfirst/frc/team199/Robot2018/RobotMap.java

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -127,10 +127,10 @@ public RobotMap() {
127127

128128
leftIntakeMotor = new VictorSP(getPort("IntakeLeftVictorSP", 8));
129129
rightIntakeMotor = new VictorSP(getPort("IntakeRightVictorSP", 9));
130-
leftIntakeSolenoid = new DoubleSolenoid(getPort("IntakeLeftHorizontalSolenoidPort1", 4),
131-
getPort("IntakeLeftHorizontalSolenoidPort2", 5));
132-
rightIntakeSolenoid = new DoubleSolenoid(getPort("IntakeRightHorizontalSolenoidPort1", 2),
133-
getPort("IntakeRightHorizontalSolenoidPort2", 3));
130+
leftIntakeSolenoid = new DoubleSolenoid(getPort("IntakeLeftSolenoidForward", 4),
131+
getPort("IntakeLeftSolenoidReverse", 5));
132+
rightIntakeSolenoid = new DoubleSolenoid(getPort("IntakeRightSolenoidForward", 2),
133+
getPort("IntakeRightSolenoidReverse", 3));
134134

135135
leftEncPort1 = new DigitalInput(getPort("1LeftEnc", 2));
136136
leftEncPort2 = new DigitalInput(getPort("2LeftEnc", 3));

Robot2018/src/org/usfirst/frc/team199/Robot2018/subsystems/IntakeEject.java

Lines changed: 36 additions & 60 deletions
Original file line numberDiff line numberDiff line change
@@ -11,44 +11,48 @@
1111
import edu.wpi.first.wpilibj.command.Subsystem;
1212

1313
/**
14-
*
14+
* kForward = intake closed, kReverse = intake open
1515
*/
1616
public class IntakeEject extends Subsystem implements IntakeEjectInterface {
1717
private final PowerDistributionPanel pdp = RobotMap.pdp;
1818
private final VictorSP leftIntakeMotor = RobotMap.leftIntakeMotor;
1919
private final VictorSP rightIntakeMotor = RobotMap.rightIntakeMotor;
2020
private final DoubleSolenoid leftSolenoid = RobotMap.leftIntakeSolenoid;
2121
private final DoubleSolenoid rightSolenoid = RobotMap.rightIntakeSolenoid;
22-
private boolean leftOpen = isForw(leftSolenoid.get());
23-
private boolean rightOpen = isForw(rightSolenoid.get());
22+
private boolean leftOpen = isOpen(leftSolenoid.get());
23+
private boolean rightOpen = isOpen(rightSolenoid.get());
2424

2525
/**
26-
* Return whether or not the doubleSolenoid is set to open
26+
* Return whether or not a side of the intake (L/R) is open
2727
*
2828
* @param val
29-
* The value of the doublesolenoid
29+
* The value (kForward, kReverse, kOff) of the DoubleSolenoid for one
30+
* side of the intake
3031
*/
31-
public boolean isForw(DoubleSolenoid.Value val) {
32-
return val == DoubleSolenoid.Value.kForward;
32+
public boolean isOpen(DoubleSolenoid.Value val) {
33+
return val == DoubleSolenoid.Value.kReverse;
3334
}
3435

3536
/**
3637
* Set the default command for a subsystem here.
3738
*/
39+
@Override
3840
public void initDefaultCommand() {
3941
setDefaultCommand(new DefaultIntake());
4042
}
4143

4244
/**
4345
* @return current left motor value
4446
*/
47+
@Override
4548
public double getLeftIntakeSpeed() {
4649
return leftIntakeMotor.get();
4750
}
4851

4952
/**
5053
* @return current right motor value
5154
*/
55+
@Override
5256
public double getRightIntakeSpeed() {
5357
return rightIntakeMotor.get();
5458
}
@@ -58,6 +62,7 @@ public double getRightIntakeSpeed() {
5862
* robot
5963
*
6064
*/
65+
@Override
6166
public boolean hasCube() {
6267
return pdp.getCurrent(Robot.rmap.getPort("PDP Intake Left Channel", 4)) > Robot.getConst("Max Current", 39)
6368
|| pdp.getCurrent(Robot.rmap.getPort("PDP Intake Right Channel", 11)) > Robot.getConst("Max Current",
@@ -68,6 +73,7 @@ public boolean hasCube() {
6873
* stops the motors
6974
*
7075
*/
76+
@Override
7177
public void stopIntake() {
7278
leftIntakeMotor.stopMotor();
7379
rightIntakeMotor.stopMotor();
@@ -79,6 +85,7 @@ public void stopIntake() {
7985
* @param speed
8086
* Speed the left motor should run at
8187
*/
88+
@Override
8289
public void runLeftIntake(double speed) {
8390
double actualSpeed = speed * Robot.getConst("Intake Motor Speed Multiplier", 0.5);
8491
leftIntakeMotor.set(actualSpeed);
@@ -90,6 +97,7 @@ public void runLeftIntake(double speed) {
9097
* @param speed
9198
* Speed the left motor should run at
9299
*/
100+
@Override
93101
public void runRightIntake(double speed) {
94102
double actualSpeed = speed * Robot.getConst("Intake Motor Speed Multiplier", 0.5);
95103
rightIntakeMotor.set(actualSpeed);
@@ -101,81 +109,48 @@ public void runRightIntake(double speed) {
101109
* @param speed
102110
* - negative -> rollers in, positive -> rollers out
103111
*/
112+
@Override
104113
public void runIntake(double speed) {
105114
runLeftIntake(speed);
106115
runRightIntake(speed);
107116
}
108117

109118
/**
110-
* Toggles the left intake between open and closed Laura's that works because it
111-
* has been TESTED
119+
* Toggles the left intake between open (kReverse) and closed (kForward).
112120
*/
113-
// public void toggleLeftIntake() {
114-
// if (leftOpen) {
115-
// // set to closed
116-
// leftHorizontalSolenoid.set(DoubleSolenoid.Value.kReverse);
117-
// } else {
118-
// // set to open
119-
// leftHorizontalSolenoid.set(DoubleSolenoid.Value.kForward);
120-
// }
121-
// leftOpen = !leftOpen;
122-
// }
123-
124-
/**
125-
* Takes into account SmartDashboard keys and current position to toggle the
126-
* position of one of the horizontal solenoids
127-
*
128-
* @param left
129-
* Whether or not the solenoid to toggle is the left solenoid
130-
* @return The DoubleSolenoid.Value that the solenoid should be set to
131-
*/
132-
public DoubleSolenoid.Value toggleHorizontal(boolean left) {
133-
boolean open = left ? leftOpen : rightOpen;
134-
String side = left ? "Left" : "Right";
135-
String key = "Intake " + side + " Horizontal Solenoid Inverted";
136-
boolean inverted = Robot.getBool(key, false);
137-
if ((open && inverted) || (!open && !inverted)) {
138-
return DoubleSolenoid.Value.kForward;
121+
@Override
122+
public void toggleLeftIntake() {
123+
if (leftOpen) {
124+
// set to closed
125+
leftSolenoid.set(DoubleSolenoid.Value.kForward);
139126
} else {
140-
return DoubleSolenoid.Value.kReverse;
127+
// set to open
128+
leftSolenoid.set(DoubleSolenoid.Value.kReverse);
141129
}
142-
}
143-
144-
/**
145-
* Laura's thing that "works" because it has been tested
146-
*/
147-
// public void toggleRightIntake() {
148-
// if (rightOpen) {
149-
// // set to closed
150-
// rightHorizontalSolenoid.set(DoubleSolenoid.Value.kReverse);
151-
// } else {
152-
// // set to open
153-
// rightHorizontalSolenoid.set(DoubleSolenoid.Value.kForward);
154-
// }
155-
// rightOpen = !rightOpen;
156-
// }
157-
158-
/**
159-
* Toggles the left intake between open and closed
160-
*/
161-
public void toggleLeftIntake() {
162-
leftSolenoid.set(toggleHorizontal(true));
163130
leftOpen = !leftOpen;
164131
Preferences.getInstance().putBoolean("Left Horizontal Solenoid Open", leftOpen);
165132
}
166133

167134
/**
168-
* Toggles the right intake between open and closed
135+
* Toggles the right intake between open (kReverse) and closed (kForward).
169136
*/
137+
@Override
170138
public void toggleRightIntake() {
171-
rightSolenoid.set(toggleHorizontal(false));
139+
if (rightOpen) {
140+
// set to closed
141+
rightSolenoid.set(DoubleSolenoid.Value.kForward);
142+
} else {
143+
// set to open
144+
rightSolenoid.set(DoubleSolenoid.Value.kReverse);
145+
}
172146
rightOpen = !rightOpen;
173-
Preferences.getInstance().putBoolean("Right Horizontal Solenoid Open", rightOpen);
147+
Preferences.getInstance().putBoolean("Right Solenoid Open", rightOpen);
174148
}
175149

176150
/**
177151
* Closes the intake
178152
*/
153+
@Override
179154
public void closeIntake() {
180155
if (leftOpen) {
181156
toggleLeftIntake();
@@ -188,6 +163,7 @@ public void closeIntake() {
188163
/**
189164
* Opens the intake
190165
*/
166+
@Override
191167
public void openIntake() {
192168
if (!leftOpen) {
193169
toggleLeftIntake();

0 commit comments

Comments
 (0)