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

Commit 27a4be9

Browse files
2 parents b507e2a + 05cf3da commit 27a4be9

6 files changed

Lines changed: 104 additions & 19 deletions

File tree

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

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -130,12 +130,10 @@ public RobotMap() {
130130

131131
leftIntakeMotor = new VictorSP(getPort("IntakeLeftVictorSP", 9));
132132
rightIntakeMotor = new VictorSP(getPort("IntakeRightVictorSP", 8));
133-
// leftIntakeHorizontalSolenoid = new
134-
// DoubleSolenoid(getPort("IntakeLeftHorizontalSolenoidPort1", 2),
135-
// getPort("IntakeLeftHorizontalSolenoidPort2", 3));
136-
// rightIntakeHorizontalSolenoid = new
137-
// DoubleSolenoid(getPort("IntakeRightHorizontalSolenoidPort1", 4),
138-
// getPort("IntakeRightHorizontalSolenoidPort2", 5));
133+
leftIntakeHorizontalSolenoid = new DoubleSolenoid(getPort("IntakeLeftHorizontalSolenoidPort1", 2),
134+
getPort("IntakeLeftHorizontalSolenoidPort2", 3));
135+
rightIntakeHorizontalSolenoid = new DoubleSolenoid(getPort("IntakeRightHorizontalSolenoidPort1", 4),
136+
getPort("IntakeRightHorizontalSolenoidPort2", 5));
139137
// leftIntakeVerticalSolenoid = new
140138
// DoubleSolenoid(getPort("IntakeLeftVerticalSolenoidPort1", 6),
141139
// getPort("IntakeLeftVerticalSolenoidPort2", 7));
Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
package org.usfirst.frc.team199.Robot2018.commands;
2+
3+
import org.usfirst.frc.team199.Robot2018.Robot;
4+
5+
import edu.wpi.first.wpilibj.command.Command;
6+
7+
/**
8+
*
9+
*/
10+
public class DefaultIntake extends Command {
11+
12+
public DefaultIntake() {
13+
// Use requires() here to declare subsystem dependencies
14+
// eg. requires(chassis);
15+
requires(Robot.intakeEject);
16+
}
17+
18+
// Called just before this Command runs the first time
19+
protected void initialize() {
20+
}
21+
22+
// Called repeatedly when this Command is scheduled to run
23+
protected void execute() {
24+
// 1 and 5 represent the axes' index in driver station
25+
Robot.intakeEject.runLeftIntake(Robot.oi.manipulator.getRawAxis(1));
26+
Robot.intakeEject.runRightIntake(Robot.oi.manipulator.getRawAxis(5));
27+
}
28+
29+
// Make this return true when this Command no longer needs to run execute()
30+
protected boolean isFinished() {
31+
return false;
32+
}
33+
34+
// Called once after isFinished returns true
35+
protected void end() {
36+
Robot.intakeEject.runIntake(0);
37+
}
38+
39+
// Called when another command which requires one or more of the same
40+
// subsystems is scheduled to run
41+
protected void interrupted() {
42+
end();
43+
}
44+
}

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@ protected void initialize() {
2020

2121
// Called repeatedly when this Command is scheduled to run
2222
protected void execute() {
23-
Robot.intakeEject.runIntake(1);
23+
Robot.intakeEject.runIntake(-1);
2424
}
2525

2626
// Make this return true when this Command no longer needs to run execute()

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

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,24 +20,28 @@ public OutakeCube() {
2020
// Called just before this Command runs the first time
2121
protected void initialize() {
2222
tim = new Timer();
23+
tim.reset();
24+
tim.start();
2325
}
2426

2527
// Called repeatedly when this Command is scheduled to run
2628
protected void execute() {
27-
Robot.intakeEject.runIntake(-1);
29+
Robot.intakeEject.runIntake(1);
2830
}
2931

3032
// Make this return true when this Command no longer needs to run execute()
3133
protected boolean isFinished() {
32-
return tim.get() > Robot.getConst("Outake Time", 1);
34+
return tim.get() > Robot.getConst("Outake Time", 0.5);
3335
}
3436

3537
// Called once after isFinished returns true
3638
protected void end() {
39+
Robot.intakeEject.runIntake(0);
3740
}
3841

3942
// Called when another command which requires one or more of the same
4043
// subsystems is scheduled to run
4144
protected void interrupted() {
45+
end();
4246
}
4347
}

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

Lines changed: 33 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22

33
import org.usfirst.frc.team199.Robot2018.Robot;
44
import org.usfirst.frc.team199.Robot2018.RobotMap;
5+
import org.usfirst.frc.team199.Robot2018.commands.DefaultIntake;
56

67
import edu.wpi.first.wpilibj.DoubleSolenoid;
78
import edu.wpi.first.wpilibj.PowerDistributionPanel;
@@ -24,6 +25,7 @@ public class IntakeEject extends Subsystem implements IntakeEjectInterface {
2425
* Set the default command for a subsystem here.
2526
*/
2627
public void initDefaultCommand() {
28+
setDefaultCommand(new DefaultIntake());
2729
}
2830

2931
/**
@@ -46,9 +48,9 @@ public double getRightIntakeSpeed() {
4648
*
4749
*/
4850
public boolean hasCube() {
49-
return pdp.getCurrent(Robot.rmap.getPort("PDP Intake Left Channel", 4)) > Robot.getConst("Max Current", 38)
50-
&& pdp.getCurrent(Robot.rmap.getPort("PDP Intake Right Channel", 11)) > Robot.getConst("Max Current",
51-
38);
51+
return pdp.getCurrent(Robot.rmap.getPort("PDP Intake Left Channel", 4)) > Robot.getConst("Max Current", 39)
52+
|| pdp.getCurrent(Robot.rmap.getPort("PDP Intake Right Channel", 11)) > Robot.getConst("Max Current",
53+
39);
5254
}
5355

5456
/**
@@ -60,16 +62,37 @@ public void stopIntake() {
6062
rightIntakeMotor.stopMotor();
6163
}
6264

65+
/**
66+
* Sets the left roller to run at the specified speed
67+
*
68+
* @param speed
69+
* Speed the left motor should run at
70+
*/
71+
public void runLeftIntake(double speed) {
72+
double actualSpeed = speed * Robot.getConst("Intake Motor Left Speed Multiplier", 1);
73+
leftIntakeMotor.set(actualSpeed);
74+
}
75+
76+
/**
77+
* Sets the left roller to run at the specified speed
78+
*
79+
* @param speed
80+
* Speed the left motor should run at
81+
*/
82+
public void runRightIntake(double speed) {
83+
double actualSpeed = speed * Robot.getConst("Intake Motor Right Speed Multiplier", 1);
84+
rightIntakeMotor.set(actualSpeed);
85+
}
86+
6387
/**
6488
* Spins the rollers
6589
*
6690
* @param speed
6791
* - positive -> rollers in, negative -> rollers out
6892
*/
6993
public void runIntake(double speed) {
70-
double actualSpeed = speed * Robot.getConst("Intake Motor Speed Multiplier", 1);
71-
leftIntakeMotor.set(actualSpeed);
72-
rightIntakeMotor.set(actualSpeed);
94+
runLeftIntake(speed);
95+
runRightIntake(speed);
7396
}
7497

7598
/**
@@ -101,9 +124,9 @@ public void lowerIntake() {
101124
}
102125

103126
/**
104-
* Opens the intake
127+
* Closes the intake
105128
*/
106-
public void openIntake() {
129+
public void closeIntake() {
107130
DoubleSolenoid.Value leftSet = Robot.getBool("Intake Left Horizontal Solenoid Inverted", false)
108131
? DoubleSolenoid.Value.kReverse
109132
: DoubleSolenoid.Value.kForward;
@@ -115,9 +138,9 @@ public void openIntake() {
115138
}
116139

117140
/**
118-
* Closes the intake
141+
* Opens the intake
119142
*/
120-
public void closeIntake() {
143+
public void openIntake() {
121144
DoubleSolenoid.Value leftSet = Robot.getBool("Intake Left Horizontal Solenoid Inverted", false)
122145
? DoubleSolenoid.Value.kForward
123146
: DoubleSolenoid.Value.kReverse;

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

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,22 @@ public interface IntakeEjectInterface {
3030
*/
3131
public void stopIntake();
3232

33+
/**
34+
* Sets the left roller to run at the specified speed
35+
*
36+
* @param speed
37+
* Speed the left motor should run at
38+
*/
39+
public void runLeftIntake(double speed);
40+
41+
/**
42+
* Sets the right roller to run at the specified speed
43+
*
44+
* @param speed
45+
* Speed the right motor should run at
46+
*/
47+
public void runRightIntake(double speed);
48+
3349
/**
3450
* Spins the rollers
3551
*

0 commit comments

Comments
 (0)