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

Commit dd737a3

Browse files
committed
added lift and changed dt solenoid keys
1 parent 5ea98aa commit dd737a3

9 files changed

Lines changed: 261 additions & 53 deletions

File tree

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

Lines changed: 25 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,13 @@
77

88
package org.usfirst.frc.team199.Robot2018;
99

10+
import org.usfirst.frc.team199.Robot2018.commands.CloseIntake;
11+
import org.usfirst.frc.team199.Robot2018.commands.IntakeCube;
12+
import org.usfirst.frc.team199.Robot2018.commands.LowerIntake;
13+
import org.usfirst.frc.team199.Robot2018.commands.OpenIntake;
1014
import org.usfirst.frc.team199.Robot2018.commands.PIDMove;
1115
import org.usfirst.frc.team199.Robot2018.commands.PIDTurn;
16+
import org.usfirst.frc.team199.Robot2018.commands.RaiseIntake;
1217
import org.usfirst.frc.team199.Robot2018.commands.SetDistancePerPulse;
1318
import org.usfirst.frc.team199.Robot2018.commands.ShiftDriveType;
1419
import org.usfirst.frc.team199.Robot2018.commands.ShiftHighGear;
@@ -35,14 +40,20 @@ public class OI {
3540
private JoystickButton updatePIDConstantsButton;
3641
private JoystickButton updateEncoderDPPButton;
3742
public Joystick manipulator;
38-
43+
private JoystickButton closeIntake;
44+
private JoystickButton openIntake;
45+
private JoystickButton raiseIntake;
46+
private JoystickButton lowerIntake;
47+
private JoystickButton intake;
48+
private JoystickButton outake;
49+
3950
public int getButton(String key, int def) {
4051
if (!SmartDashboard.containsKey("Button/" + key)) {
4152
if (!SmartDashboard.putNumber("Button/" + key, def)) {
4253
System.err.println("SmartDashboard Key" + "Button/" + key + "already taken by a different type");
4354
return def;
4455
}
45-
}
56+
}
4657
return (int) SmartDashboard.getNumber("Button/" + key, def);
4758
}
4859

@@ -66,5 +77,17 @@ public OI() {
6677
updateEncoderDPPButton.whenPressed(new SetDistancePerPulse());
6778

6879
manipulator = new Joystick(2);
80+
closeIntake = new JoystickButton(manipulator, getButton("Close Intake Button", 1));
81+
closeIntake.whenPressed(new CloseIntake());
82+
openIntake = new JoystickButton(manipulator, getButton("Open Intake Button", 2));
83+
openIntake.whenPressed(new OpenIntake());
84+
raiseIntake = new JoystickButton(manipulator, getButton("Raise Intake Button", 3));
85+
raiseIntake.whenPressed(new RaiseIntake());
86+
lowerIntake = new JoystickButton(manipulator, getButton("Lower Intake Button", 4));
87+
lowerIntake.whenPressed(new LowerIntake());
88+
intake = new JoystickButton(manipulator, getButton("Intake Button", 5));
89+
intake.whileHeld(new IntakeCube(true));
90+
outake = new JoystickButton(manipulator, getButton("Outake Button", 6));
91+
outake.whileHeld(new IntakeCube(false));
6992
}
7093
}

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

Lines changed: 18 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
import edu.wpi.first.wpilibj.DoubleSolenoid;
2020
import edu.wpi.first.wpilibj.Encoder;
2121
import edu.wpi.first.wpilibj.PIDSourceType;
22+
import edu.wpi.first.wpilibj.PowerDistributionPanel;
2223
import edu.wpi.first.wpilibj.SerialPort;
2324
import edu.wpi.first.wpilibj.SpeedControllerGroup;
2425
import edu.wpi.first.wpilibj.VictorSP;
@@ -33,11 +34,17 @@
3334
*/
3435
public class RobotMap {
3536

37+
public static PowerDistributionPanel pdp;
38+
3639
public static WPI_TalonSRX liftMotor;
3740
public static WPI_TalonSRX climberMotor;
3841

3942
public static VictorSP leftIntakeMotor;
4043
public static VictorSP rightIntakeMotor;
44+
public static DoubleSolenoid leftIntakeVerticalSolenoid;
45+
public static DoubleSolenoid rightIntakeVerticalSolenoid;
46+
public static DoubleSolenoid leftIntakeHorizontalSolenoid;
47+
public static DoubleSolenoid rightIntakeHorizontalSolenoid;
4148

4249
public static DigitalSource leftEncPort1;
4350
public static DigitalSource leftEncPort2;
@@ -104,6 +111,7 @@ private void configSPX(WPI_VictorSPX mc) {
104111
}
105112

106113
public RobotMap() {
114+
pdp = new PowerDistributionPanel();
107115

108116
liftMotor = new WPI_TalonSRX(getPort("LiftTalonSRX", 5));
109117
configSRX(liftMotor);
@@ -112,6 +120,14 @@ public RobotMap() {
112120

113121
leftIntakeMotor = new VictorSP(getPort("IntakeLeftVictorSP", 0));
114122
rightIntakeMotor = new VictorSP(getPort("IntakeRightVictorSP", 1));
123+
leftIntakeHorizontalSolenoid = new DoubleSolenoid(getPort("IntakeLeftHorizontalSolenoidPort1", 2),
124+
getPort("IntakeLeftHorizontalSolenoidPort2", 3));
125+
rightIntakeHorizontalSolenoid = new DoubleSolenoid(getPort("IntakeRightHorizontalSolenoidPort1", 4),
126+
getPort("IntakeRightHorizontalSolenoidPort2", 5));
127+
leftIntakeVerticalSolenoid = new DoubleSolenoid(getPort("IntakeLeftVerticalSolenoidPort1", 6),
128+
getPort("IntakeLeftVerticalSolenoidPort2", 7));
129+
rightIntakeVerticalSolenoid = new DoubleSolenoid(getPort("IntakeRightVerticalSolenoidPort1", 8),
130+
getPort("IntakeRightVerticalSolenoidPort2", 9));
115131

116132
leftEncPort1 = new DigitalInput(getPort("1LeftEnc", 0));
117133
leftEncPort2 = new DigitalInput(getPort("2LeftEnc", 1));
@@ -162,7 +178,8 @@ public RobotMap() {
162178

163179
distEncAvg = new PIDSourceAverage(leftEncDist, rightEncDist);
164180
fancyGyro = new AHRS(SerialPort.Port.kMXP);
165-
dtGear = new DoubleSolenoid(getPort("1dtGearSolenoid", 0), getPort("2dtGearSolenoid", 1));
181+
dtGear = new DoubleSolenoid(getPort("DrivetrainGearSolenoidPort1", 0),
182+
getPort("DrivetrainGearSolenoidPort2", 1));
166183
}
167184

168185
/**
Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
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.InstantCommand;
6+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
7+
8+
/**
9+
*
10+
*/
11+
public class CloseIntake extends InstantCommand {
12+
13+
public CloseIntake() {
14+
super();
15+
// Use requires() here to declare subsystem dependencies
16+
// eg. requires(chassis);
17+
}
18+
19+
// Called once when the command executes
20+
protected void initialize() {
21+
Robot.intakeEject.closeIntake();
22+
SmartDashboard.putBoolean("Intake Open", false);
23+
}
24+
25+
}

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

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,15 +1,19 @@
11
package org.usfirst.frc.team199.Robot2018.commands;
22

3+
import org.usfirst.frc.team199.Robot2018.Robot;
4+
35
import edu.wpi.first.wpilibj.command.Command;
46

57
/**
68
*
79
*/
810
public class IntakeCube extends Command {
911

10-
public IntakeCube() {
12+
boolean in;
13+
public IntakeCube(boolean in) {
1114
// Use requires() here to declare subsystem dependencies
1215
// eg. requires(chassis);
16+
this.in = in;
1317
}
1418

1519
// Called just before this Command runs the first time
@@ -18,6 +22,11 @@ protected void initialize() {
1822

1923
// Called repeatedly when this Command is scheduled to run
2024
protected void execute() {
25+
if(in) {
26+
Robot.intakeEject.runIntake(1);
27+
} else {
28+
Robot.intakeEject.runIntake(-1);
29+
}
2130
}
2231

2332
// Make this return true when this Command no longer needs to run execute()
Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
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.InstantCommand;
6+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
7+
8+
/**
9+
*
10+
*/
11+
public class LowerIntake extends InstantCommand {
12+
13+
public LowerIntake() {
14+
super();
15+
// Use requires() here to declare subsystem dependencies
16+
// eg. requires(chassis);
17+
}
18+
19+
// Called once when the command executes
20+
protected void initialize() {
21+
Robot.intakeEject.lowerIntake();
22+
SmartDashboard.putBoolean("Intake Up", false);
23+
}
24+
25+
}
Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
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.InstantCommand;
6+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
7+
8+
/**
9+
*
10+
*/
11+
public class OpenIntake extends InstantCommand {
12+
13+
public OpenIntake() {
14+
super();
15+
// Use requires() here to declare subsystem dependencies
16+
// eg. requires(chassis);
17+
}
18+
19+
// Called once when the command executes
20+
protected void initialize() {
21+
Robot.intakeEject.openIntake();
22+
SmartDashboard.putBoolean("Intake Open", true);
23+
}
24+
25+
}
Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
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.InstantCommand;
6+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
7+
8+
/**
9+
*
10+
*/
11+
public class RaiseIntake extends InstantCommand {
12+
13+
public RaiseIntake() {
14+
super();
15+
// Use requires() here to declare subsystem dependencies
16+
// eg. requires(chassis);
17+
}
18+
19+
// Called once when the command executes
20+
protected void initialize() {
21+
Robot.intakeEject.raiseIntake();
22+
SmartDashboard.putBoolean("Intake Up", true);
23+
}
24+
25+
}
Lines changed: 72 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -1,67 +1,107 @@
11
package org.usfirst.frc.team199.Robot2018.subsystems;
22

3+
import org.usfirst.frc.team199.Robot2018.Robot;
34
import org.usfirst.frc.team199.Robot2018.RobotMap;
45

5-
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
6-
6+
import edu.wpi.first.wpilibj.DoubleSolenoid;
7+
import edu.wpi.first.wpilibj.PowerDistributionPanel;
8+
import edu.wpi.first.wpilibj.VictorSP;
79
import edu.wpi.first.wpilibj.command.Subsystem;
810

911
/**
1012
*
1113
*/
1214
public class IntakeEject extends Subsystem implements IntakeEjectInterface {
13-
14-
private final WPI_TalonSRX intakeMotor = RobotMap.intakeMotor;
15-
16-
17-
15+
16+
private final PowerDistributionPanel pdp = RobotMap.pdp;
17+
private final VictorSP leftIntakeMotor = RobotMap.leftIntakeMotor;
18+
private final VictorSP rightIntakeMotor = RobotMap.rightIntakeMotor;
19+
private final DoubleSolenoid leftVerticalSolenoid = RobotMap.leftIntakeVerticalSolenoid;
20+
private final DoubleSolenoid rightVerticalSolenoid = RobotMap.rightIntakeVerticalSolenoid;
21+
private final DoubleSolenoid leftHorizontalSolenoid = RobotMap.leftIntakeHorizontalSolenoid;
22+
private final DoubleSolenoid rightHorizontalSolenoid = RobotMap.rightIntakeHorizontalSolenoid;
23+
1824
/**
1925
* Set the default command for a subsystem here.
20-
* */
21-
public void initDefaultCommand() {
22-
// Set the default command for a subsystem here.
23-
//setDefaultCommand(new MySpecialCommand());
24-
}
26+
*/
27+
public void initDefaultCommand() {
28+
}
2529

26-
/**
27-
* returns current motor value
30+
/**
31+
* returns current left motor value
2832
*/
29-
public double getIntakeSpeed() {
30-
return intakeMotor.get();
33+
public double getLeftIntakeSpeed() {
34+
return leftIntakeMotor.get();
3135
}
32-
36+
3337
/**
34-
* Uses (insert sensor here) to detect
35-
* a cube in front of the robot.
38+
* returns current right motor value
3639
*/
37-
public boolean seeCube() {
38-
return false;
40+
public double getRightIntakeSpeed() {
41+
return rightIntakeMotor.get();
3942
}
40-
43+
4144
/**
42-
* Uses (insert sensor here) to detect if
43-
* the cube is currently inside the robot
45+
* Uses current to check if the wheels are blocked aka the cube is inside the
46+
* robot
4447
*
4548
*/
4649
public boolean hasCube() {
47-
return false;
50+
return pdp.getCurrent(Robot.rmap.getPort("PDP Intake Left Channel", 4)) > Robot.getConst("Max Current", 38)
51+
&& pdp.getCurrent(Robot.rmap.getPort("PDP Intake Right Channel", 11)) > Robot.getConst("Max Current",
52+
38);
4853
}
49-
54+
5055
/**
5156
* stops the motors
5257
*
5358
*/
5459
public void stopIntake() {
55-
intakeMotor.stopMotor();
60+
leftIntakeMotor.stopMotor();
61+
rightIntakeMotor.stopMotor();
5662
}
57-
63+
5864
/**
5965
* Spins the rollers
60-
* @param speed - positive -> rollers in, negative -> rollers out
66+
*
67+
* @param speed
68+
* - positive -> rollers in, negative -> rollers out
6169
*/
6270
public void runIntake(double speed) {
63-
71+
double actualSpeed = speed * Robot.getConst("Intake Motor Speed Multiplier", 1);
72+
leftIntakeMotor.set(actualSpeed);
73+
rightIntakeMotor.set(actualSpeed);
74+
}
75+
76+
/**
77+
* Raises the intake
78+
*/
79+
public void raiseIntake() {
80+
leftVerticalSolenoid.set(DoubleSolenoid.Value.kForward);
81+
rightVerticalSolenoid.set(DoubleSolenoid.Value.kForward);
82+
}
83+
84+
/**
85+
* Lowers the intake
86+
*/
87+
public void lowerIntake() {
88+
leftVerticalSolenoid.set(DoubleSolenoid.Value.kReverse);
89+
rightVerticalSolenoid.set(DoubleSolenoid.Value.kReverse);
90+
}
91+
92+
/**
93+
* Opens the intake
94+
*/
95+
public void openIntake() {
96+
leftHorizontalSolenoid.set(DoubleSolenoid.Value.kForward);
97+
rightHorizontalSolenoid.set(DoubleSolenoid.Value.kForward);
6498
}
65-
66-
}
6799

100+
/**
101+
* Closes the intake
102+
*/
103+
public void closeIntake() {
104+
leftHorizontalSolenoid.set(DoubleSolenoid.Value.kForward);
105+
rightHorizontalSolenoid.set(DoubleSolenoid.Value.kForward);
106+
}
107+
}

0 commit comments

Comments
 (0)