@@ -21,6 +21,8 @@ public class IntakeEject extends Subsystem implements IntakeEjectInterface {
2121 private final DoubleSolenoid rightVerticalSolenoid = RobotMap .rightIntakeVerticalSolenoid ;
2222 private final DoubleSolenoid leftHorizontalSolenoid = RobotMap .leftIntakeHorizontalSolenoid ;
2323 private final DoubleSolenoid rightHorizontalSolenoid = RobotMap .rightIntakeHorizontalSolenoid ;
24+ private boolean rightOpen = false ;
25+ private boolean leftOpen = false ;
2426
2527 /**
2628 * Set the default command for a subsystem here.
@@ -128,34 +130,54 @@ public void lowerIntake() {
128130 * Toggles the left intake between open and closed
129131 */
130132 public void toggleLeftIntake () {
131- DoubleSolenoid .Value set ;
132- if (Robot .getBool ("Bool/Left Horizontal Solenoid Open" , true )) {
133- set = Robot .getBool ("Intake Left Horizontal Solenoid Inverted" , false ) ? DoubleSolenoid .Value .kForward
134- : DoubleSolenoid .Value .kReverse ;
133+ // DoubleSolenoid.Value set;
134+ // if (Robot.getBool("Left Horizontal Solenoid Open", true)) {
135+ // set = Robot.getBool("Intake Left Horizontal Solenoid Inverted", false) ?
136+ // DoubleSolenoid.Value.kForward
137+ // : DoubleSolenoid.Value.kReverse;
138+ // } else {
139+ // set = Robot.getBool("Intake Left Horizontal Solenoid Inverted", false) ?
140+ // DoubleSolenoid.Value.kReverse
141+ // : DoubleSolenoid.Value.kForward;
142+ // }
143+ // leftHorizontalSolenoid.set(set);
144+ // SmartDashboard.putBoolean("Bool/Left Horizontal Solenoid Open",
145+ // !Robot.getBool("Left Horizontal Solenoid Open", true));
146+ if (leftOpen ) {
147+ // set to closed
148+ leftHorizontalSolenoid .set (DoubleSolenoid .Value .kReverse );
135149 } else {
136- set = Robot . getBool ( "Intake Left Horizontal Solenoid Inverted" , false ) ? DoubleSolenoid . Value . kReverse
137- : DoubleSolenoid .Value .kForward ;
150+ // set to open
151+ leftHorizontalSolenoid . set ( DoubleSolenoid .Value .kForward ) ;
138152 }
139- leftHorizontalSolenoid .set (set );
140- SmartDashboard .putBoolean ("Bool/Left Horizontal Solenoid Open" ,
141- Robot .getBool ("Left Horizontal Solenoid Open" , true ));
153+ leftOpen = !leftOpen ;
142154 }
143155
144156 /**
145157 * Toggles the right intake between open and closed
146158 */
147159 public void toggleRightIntake () {
148- DoubleSolenoid .Value set ;
149- if (Robot .getBool ("Bool/Right Horizontal Solenoid Open" , true )) {
150- set = Robot .getBool ("Intake Right Horizontal Solenoid Inverted" , false ) ? DoubleSolenoid .Value .kForward
151- : DoubleSolenoid .Value .kReverse ;
160+ // DoubleSolenoid.Value set;
161+ // if (Robot.getBool("Right Horizontal Solenoid Open", true)) {
162+ // set = Robot.getBool("Intake Right Horizontal Solenoid Inverted", false) ?
163+ // DoubleSolenoid.Value.kForward
164+ // : DoubleSolenoid.Value.kReverse;
165+ // } else {
166+ // set = Robot.getBool("Intake Right Horizontal Solenoid Inverted", false) ?
167+ // DoubleSolenoid.Value.kReverse
168+ // : DoubleSolenoid.Value.kForward;
169+ // }
170+ // rightHorizontalSolenoid.set(set);
171+ // SmartDashboard.putBoolean("Bool/Right Horizontal Solenoid Open",
172+ // !Robot.getBool("Right Horizontal Solenoid Open", true));
173+ if (rightOpen ) {
174+ // set to closed
175+ rightHorizontalSolenoid .set (DoubleSolenoid .Value .kReverse );
152176 } else {
153- set = Robot . getBool ( "Intake Right Horizontal Solenoid Inverted" , false ) ? DoubleSolenoid . Value . kReverse
154- : DoubleSolenoid .Value .kForward ;
177+ // set to open
178+ rightHorizontalSolenoid . set ( DoubleSolenoid .Value .kForward ) ;
155179 }
156- rightHorizontalSolenoid .set (set );
157- SmartDashboard .putBoolean ("Bool/Right Horizontal Solenoid Open" ,
158- Robot .getBool ("right Horizontal Solenoid Open" , true ));
180+ rightOpen = !rightOpen ;
159181 }
160182
161183 /**
@@ -168,10 +190,12 @@ public void closeIntake() {
168190 DoubleSolenoid .Value rightSet = Robot .getBool ("Intake Right Horizontal Solenoid Inverted" , false )
169191 ? DoubleSolenoid .Value .kReverse
170192 : DoubleSolenoid .Value .kForward ;
171- SmartDashboard .putBoolean ("Bool/Left Horizontal Solenoid Open" , true );
172- SmartDashboard .putBoolean ("Bool/Right Horizontal Solenoid Open" , true );
193+ SmartDashboard .putBoolean ("Bool/Left Horizontal Solenoid Open" , false );
194+ SmartDashboard .putBoolean ("Bool/Right Horizontal Solenoid Open" , false );
173195 leftHorizontalSolenoid .set (leftSet );
174196 rightHorizontalSolenoid .set (rightSet );
197+ leftOpen = false ;
198+ rightOpen = false ;
175199 }
176200
177201 /**
@@ -184,9 +208,11 @@ public void openIntake() {
184208 DoubleSolenoid .Value rightSet = Robot .getBool ("Intake Right Horizontal Solenoid Inverted" , false )
185209 ? DoubleSolenoid .Value .kForward
186210 : DoubleSolenoid .Value .kReverse ;
187- SmartDashboard .putBoolean ("Bool/Left Horizontal Solenoid Open" , false );
188- SmartDashboard .putBoolean ("Bool/Right Horizontal Solenoid Open" , false );
211+ SmartDashboard .putBoolean ("Bool/Left Horizontal Solenoid Open" , true );
212+ SmartDashboard .putBoolean ("Bool/Right Horizontal Solenoid Open" , true );
189213 leftHorizontalSolenoid .set (leftSet );
190214 rightHorizontalSolenoid .set (rightSet );
215+ leftOpen = false ;
216+ rightOpen = false ;
191217 }
192218}
0 commit comments