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

Commit bd1bb22

Browse files
committed
Caution merge conflicts: Driver station computer changes while testing intake
1 parent 1c8db12 commit bd1bb22

File tree

6 files changed

+74
-30
lines changed

6 files changed

+74
-30
lines changed

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

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,6 @@
99

1010
import org.usfirst.frc.team199.Robot2018.commands.CloseIntake;
1111
import org.usfirst.frc.team199.Robot2018.commands.IntakeCube;
12-
import org.usfirst.frc.team199.Robot2018.commands.LowerIntake;
1312
import org.usfirst.frc.team199.Robot2018.commands.OpenIntake;
1413
import org.usfirst.frc.team199.Robot2018.commands.OutakeCube;
1514
import org.usfirst.frc.team199.Robot2018.commands.PIDMove;
@@ -109,7 +108,7 @@ public OI() {
109108
// raiseIntake.whenPressed(new RaiseIntake());
110109
// lowerIntake = new JoystickButton(manipulator, getButton("Lower Intake
111110
// Button", 4));
112-
lowerIntake.whenPressed(new LowerIntake());
111+
// lowerIntake.whenPressed(new LowerIntake());
113112
intake = new JoystickButton(manipulator, getButton("Intake Button", 5));
114113
intake.whenPressed(new IntakeCube());
115114
outake = new JoystickButton(manipulator, getButton("Outake Button", 6));

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

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -215,6 +215,8 @@ public void teleopPeriodic() {
215215
// SmartDashboard.putNumber("Avg Enc Dist", dt.getEncAvgDist());
216216
//
217217
SmartDashboard.putNumber("Angle", dt.getAHRSAngle());
218+
SmartDashboard.putNumber("Left Current draw", rmap.pdp.getCurrent(4));
219+
SmartDashboard.putNumber("Right Current draw", rmap.pdp.getCurrent(11));
218220
}
219221

220222
boolean firstTime = true;

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

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -195,10 +195,9 @@ public RobotMap() {
195195
rightVelocityController.setContinuous(false);
196196
rightVelocityController.setAbsoluteTolerance(Robot.getConst("VelocityToleranceRight", 2));
197197

198-
// robotDrive = new DifferentialDrive(leftVelocityController,
199-
// rightVelocityController);
200-
// robotDrive.setMaxOutput(Robot.getConst("Max High Speed", 204));
201-
robotDrive = new DifferentialDrive(dtLeft, dtRight);
198+
robotDrive = new DifferentialDrive(leftVelocityController, rightVelocityController);
199+
robotDrive.setMaxOutput(Robot.getConst("Max High Speed", 204));
200+
// robotDrive = new DifferentialDrive(dtLeft, dtRight);
202201

203202
distEncAvg = new PIDSourceAverage(leftEncDist, rightEncDist);
204203
fancyGyro = new AHRS(SPI.Port.kMXP);

Robot2018/src/org/usfirst/frc/team199/Robot2018/commands/IntakeCube.java

Lines changed: 19 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,30 +2,48 @@
22

33
import org.usfirst.frc.team199.Robot2018.Robot;
44

5+
import edu.wpi.first.wpilibj.Timer;
56
import edu.wpi.first.wpilibj.command.Command;
67

78
/**
89
*
910
*/
1011
public class IntakeCube extends Command {
1112

13+
private Timer tim;
14+
private boolean overDraw;
15+
1216
public IntakeCube() {
1317
// Use requires() here to declare subsystem dependencies
1418
// eg. requires(chassis);
19+
tim = new Timer();
1520
}
1621

1722
// Called just before this Command runs the first time
1823
protected void initialize() {
24+
tim.reset();
25+
tim.start();
26+
overDraw = false;
1927
}
2028

2129
// Called repeatedly when this Command is scheduled to run
2230
protected void execute() {
2331
Robot.intakeEject.runIntake(-1);
32+
if (Robot.intakeEject.hasCube()) {
33+
if (!overDraw) {
34+
overDraw = true;
35+
tim.start();
36+
}
37+
} else {
38+
overDraw = false;
39+
tim.stop();
40+
tim.reset();
41+
}
2442
}
2543

2644
// Make this return true when this Command no longer needs to run execute()
2745
protected boolean isFinished() {
28-
return Robot.intakeEject.hasCube();
46+
return tim.get() > Robot.getConst("Has Cube Timeout", 0.5);
2947
}
3048

3149
// Called once after isFinished returns true

Robot2018/src/org/usfirst/frc/team199/Robot2018/commands/TeleopDrive.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@ public TeleopDrive() {
2323
// Called just before this Command runs the first time
2424
@Override
2525
protected void initialize() {
26-
// Robot.dt.enableVelocityPIDs();
26+
Robot.dt.enableVelocityPIDs();
2727
}
2828

2929
// Called repeatedly when this Command is scheduled to run

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

Lines changed: 48 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -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

Comments
 (0)