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

Commit e8e1bb9

Browse files
committed
fix intake smartdashboard keys and streamline code (sorta)
1 parent 1c8db12 commit e8e1bb9

1 file changed

Lines changed: 10 additions & 10 deletions

File tree

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

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -128,34 +128,34 @@ public void lowerIntake() {
128128
* Toggles the left intake between open and closed
129129
*/
130130
public void toggleLeftIntake() {
131+
boolean open = Robot.getBool("Left Horizontal Solenoid Open", true);
131132
DoubleSolenoid.Value set;
132-
if (Robot.getBool("Bool/Left Horizontal Solenoid Open", true)) {
133+
if (open) {
133134
set = Robot.getBool("Intake Left Horizontal Solenoid Inverted", false) ? DoubleSolenoid.Value.kForward
134135
: DoubleSolenoid.Value.kReverse;
135136
} else {
136137
set = Robot.getBool("Intake Left Horizontal Solenoid Inverted", false) ? DoubleSolenoid.Value.kReverse
137138
: DoubleSolenoid.Value.kForward;
138139
}
139140
leftHorizontalSolenoid.set(set);
140-
SmartDashboard.putBoolean("Bool/Left Horizontal Solenoid Open",
141-
Robot.getBool("Left Horizontal Solenoid Open", true));
141+
SmartDashboard.putBoolean("Bool/Left Horizontal Solenoid Open", !open);
142142
}
143143

144144
/**
145145
* Toggles the right intake between open and closed
146146
*/
147147
public void toggleRightIntake() {
148+
boolean open = Robot.getBool("Right Horizontal Solenoid Open", true);
148149
DoubleSolenoid.Value set;
149-
if (Robot.getBool("Bool/Right Horizontal Solenoid Open", true)) {
150+
if (open) {
150151
set = Robot.getBool("Intake Right Horizontal Solenoid Inverted", false) ? DoubleSolenoid.Value.kForward
151152
: DoubleSolenoid.Value.kReverse;
152153
} else {
153154
set = Robot.getBool("Intake Right Horizontal Solenoid Inverted", false) ? DoubleSolenoid.Value.kReverse
154155
: DoubleSolenoid.Value.kForward;
155156
}
156157
rightHorizontalSolenoid.set(set);
157-
SmartDashboard.putBoolean("Bool/Right Horizontal Solenoid Open",
158-
Robot.getBool("right Horizontal Solenoid Open", true));
158+
SmartDashboard.putBoolean("Bool/Right Horizontal Solenoid Open", !open);
159159
}
160160

161161
/**
@@ -168,8 +168,8 @@ public void closeIntake() {
168168
DoubleSolenoid.Value rightSet = Robot.getBool("Intake Right Horizontal Solenoid Inverted", false)
169169
? DoubleSolenoid.Value.kReverse
170170
: DoubleSolenoid.Value.kForward;
171-
SmartDashboard.putBoolean("Bool/Left Horizontal Solenoid Open", true);
172-
SmartDashboard.putBoolean("Bool/Right Horizontal Solenoid Open", true);
171+
SmartDashboard.putBoolean("Bool/Left Horizontal Solenoid Open", false);
172+
SmartDashboard.putBoolean("Bool/Right Horizontal Solenoid Open", false);
173173
leftHorizontalSolenoid.set(leftSet);
174174
rightHorizontalSolenoid.set(rightSet);
175175
}
@@ -184,8 +184,8 @@ public void openIntake() {
184184
DoubleSolenoid.Value rightSet = Robot.getBool("Intake Right Horizontal Solenoid Inverted", false)
185185
? DoubleSolenoid.Value.kForward
186186
: DoubleSolenoid.Value.kReverse;
187-
SmartDashboard.putBoolean("Bool/Left Horizontal Solenoid Open", false);
188-
SmartDashboard.putBoolean("Bool/Right Horizontal Solenoid Open", false);
187+
SmartDashboard.putBoolean("Bool/Left Horizontal Solenoid Open", true);
188+
SmartDashboard.putBoolean("Bool/Right Horizontal Solenoid Open", true);
189189
leftHorizontalSolenoid.set(leftSet);
190190
rightHorizontalSolenoid.set(rightSet);
191191
}

0 commit comments

Comments
 (0)