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

Commit 5212a32

Browse files
Conflicts: Robot2018/src/org/usfirst/frc/team199/Robot2018/OI.java Robot2018/src/org/usfirst/frc/team199/Robot2018/RobotMap.java Robot2018/src/org/usfirst/frc/team199/Robot2018/commands/PIDTurn.java Robot2018/src/org/usfirst/frc/team199/Robot2018/commands/RunScript.java Robot2018/src/org/usfirst/frc/team199/Robot2018/subsystems/IntakeEject.java
2 parents 8980ef6 + 305b8e3 commit 5212a32

15 files changed

Lines changed: 373 additions & 62 deletions
Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,2 +1,2 @@
1-
#Sat Feb 17 16:36:54 PST 2018
1+
#Sat Feb 17 17:04:37 PST 2018
22
C\:\\Users\\dean\\git\\RobotCode2018\\Robot2018\\lib\\libpathfinderjava.so=4087ee38c338446b8305f67716260df4

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

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,14 @@
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;
14+
import org.usfirst.frc.team199.Robot2018.commands.OutakeCube;
1015
import org.usfirst.frc.team199.Robot2018.commands.PIDMove;
1116
import org.usfirst.frc.team199.Robot2018.commands.PIDTurn;
17+
import org.usfirst.frc.team199.Robot2018.commands.RaiseIntake;
1218
import org.usfirst.frc.team199.Robot2018.commands.ResetEncoders;
1319
import org.usfirst.frc.team199.Robot2018.commands.SetDistancePerPulse;
1420
import org.usfirst.frc.team199.Robot2018.commands.ShiftDriveType;
@@ -37,6 +43,12 @@ public class OI {
3743
private JoystickButton updatePIDConstantsButton;
3844
private JoystickButton updateEncoderDPPButton;
3945
public Joystick manipulator;
46+
private JoystickButton closeIntake;
47+
private JoystickButton openIntake;
48+
private JoystickButton raiseIntake;
49+
private JoystickButton lowerIntake;
50+
private JoystickButton intake;
51+
private JoystickButton outake;
4052

4153
public int getButton(String key, int def) {
4254
if (!SmartDashboard.containsKey("Button/" + key)) {
@@ -74,5 +86,17 @@ public OI() {
7486
updateEncoderDPPButton.whenPressed(new SetDistancePerPulse());
7587

7688
manipulator = new Joystick(2);
89+
closeIntake = new JoystickButton(manipulator, getButton("Close Intake Button", 1));
90+
closeIntake.whenPressed(new CloseIntake());
91+
openIntake = new JoystickButton(manipulator, getButton("Open Intake Button", 2));
92+
openIntake.whenPressed(new OpenIntake());
93+
raiseIntake = new JoystickButton(manipulator, getButton("Raise Intake Button", 3));
94+
raiseIntake.whenPressed(new RaiseIntake());
95+
lowerIntake = new JoystickButton(manipulator, getButton("Lower Intake Button", 4));
96+
lowerIntake.whenPressed(new LowerIntake());
97+
intake = new JoystickButton(manipulator, getButton("Intake Button", 5));
98+
intake.whenPressed(new IntakeCube());
99+
outake = new JoystickButton(manipulator, getButton("Outake Button", 6));
100+
outake.whenPressed(new OutakeCube());
77101
}
78102
}

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

Lines changed: 25 additions & 3 deletions
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.SPI;
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;
@@ -106,6 +113,7 @@ private void configSPX(WPI_VictorSPX mc) {
106113
}
107114

108115
public RobotMap() {
116+
pdp = new PowerDistributionPanel();
109117

110118
// intakeMotor = new WPI_TalonSRX(getPort("IntakeTalonSRX", 4));
111119
// configSRX(intakeMotor);
@@ -114,8 +122,20 @@ public RobotMap() {
114122
// climberMotor = new WPI_TalonSRX(getPort("ClimberTalonSRX", 6));
115123
// configSRX(climberMotor);
116124

117-
leftIntakeMotor = new VictorSP(getPort("IntakeLeftVictorSP", 0));
118-
rightIntakeMotor = new VictorSP(getPort("IntakeRightVictorSP", 1));
125+
leftIntakeMotor = new VictorSP(getPort("IntakeLeftVictorSP", 9));
126+
rightIntakeMotor = new VictorSP(getPort("IntakeRightVictorSP", 8));
127+
// leftIntakeHorizontalSolenoid = new
128+
// DoubleSolenoid(getPort("IntakeLeftHorizontalSolenoidPort1", 2),
129+
// getPort("IntakeLeftHorizontalSolenoidPort2", 3));
130+
// rightIntakeHorizontalSolenoid = new
131+
// DoubleSolenoid(getPort("IntakeRightHorizontalSolenoidPort1", 4),
132+
// getPort("IntakeRightHorizontalSolenoidPort2", 5));
133+
// leftIntakeVerticalSolenoid = new
134+
// DoubleSolenoid(getPort("IntakeLeftVerticalSolenoidPort1", 6),
135+
// getPort("IntakeLeftVerticalSolenoidPort2", 7));
136+
// rightIntakeVerticalSolenoid = new
137+
// DoubleSolenoid(getPort("IntakeRightVerticalSolenoidPort1", 8),
138+
// getPort("IntakeRightVerticalSolenoidPort2", 9));
119139

120140
leftEncPort1 = new DigitalInput(getPort("1LeftEnc", 2));
121141
leftEncPort2 = new DigitalInput(getPort("2LeftEnc", 3));
@@ -211,7 +231,9 @@ public double calcDefkD(double maxSpeed) {
211231
* half of the drivetrain only has to support half of the robot), and radius of
212232
* the drivetrain wheels squared. It's inversely proportional to the stall
213233
* torque of the shaft, which is found by multiplying the stall torque of the
214-
* motor with the gear reduction by the amount of motors.
234+
* motor with the gear reduction by the amount of motors. The omegaMax needs to
235+
* be converted from rpm to radians per second, so divide by 60 and multiply to
236+
* get radians.
215237
*/
216238
double gearReduction = Robot.getBool("High Gear", false) ? Robot.getConst("High Gear Gear Reduction", 5.392)
217239
: Robot.getConst("Low Gear Gear Reduction", 12.255);
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+
}
Lines changed: 29 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -1,36 +1,39 @@
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() {
11-
// Use requires() here to declare subsystem dependencies
12-
// eg. requires(chassis);
13-
}
14-
15-
// Called just before this Command runs the first time
16-
protected void initialize() {
17-
}
18-
19-
// Called repeatedly when this Command is scheduled to run
20-
protected void execute() {
21-
}
22-
23-
// Make this return true when this Command no longer needs to run execute()
24-
protected boolean isFinished() {
25-
return false;
26-
}
27-
28-
// Called once after isFinished returns true
29-
protected void end() {
30-
}
31-
32-
// Called when another command which requires one or more of the same
33-
// subsystems is scheduled to run
34-
protected void interrupted() {
35-
}
12+
public IntakeCube() {
13+
// Use requires() here to declare subsystem dependencies
14+
// eg. requires(chassis);
15+
}
16+
17+
// Called just before this Command runs the first time
18+
protected void initialize() {
19+
}
20+
21+
// Called repeatedly when this Command is scheduled to run
22+
protected void execute() {
23+
Robot.intakeEject.runIntake(1);
24+
}
25+
26+
// Make this return true when this Command no longer needs to run execute()
27+
protected boolean isFinished() {
28+
return Robot.intakeEject.hasCube();
29+
}
30+
31+
// Called once after isFinished returns true
32+
protected void end() {
33+
}
34+
35+
// Called when another command which requires one or more of the same
36+
// subsystems is scheduled to run
37+
protected void interrupted() {
38+
}
3639
}
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: 43 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,43 @@
1+
package org.usfirst.frc.team199.Robot2018.commands;
2+
3+
import org.usfirst.frc.team199.Robot2018.Robot;
4+
5+
import edu.wpi.first.wpilibj.Timer;
6+
import edu.wpi.first.wpilibj.command.Command;
7+
8+
/**
9+
*
10+
*/
11+
public class OutakeCube extends Command {
12+
13+
Timer tim;
14+
15+
public OutakeCube() {
16+
// Use requires() here to declare subsystem dependencies
17+
// eg. requires(chassis);
18+
}
19+
20+
// Called just before this Command runs the first time
21+
protected void initialize() {
22+
tim = new Timer();
23+
}
24+
25+
// Called repeatedly when this Command is scheduled to run
26+
protected void execute() {
27+
Robot.intakeEject.runIntake(-1);
28+
}
29+
30+
// Make this return true when this Command no longer needs to run execute()
31+
protected boolean isFinished() {
32+
return tim.get() > Robot.getConst("Outake Time", 1);
33+
}
34+
35+
// Called once after isFinished returns true
36+
protected void end() {
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+
}
43+
}

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

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,9 @@ protected void execute() {
9292
*/
9393
@Override
9494
protected boolean isFinished() {
95-
return moveController.onTarget();
95+
return moveController.onTarget()
96+
&& Math.abs(dt.getLeftEncRate()) <= Robot.getConst("Maximum Velocity When Stop", 1)
97+
&& Math.abs(dt.getRightEncRate()) <= Robot.getConst("Maximum Velocity When Stop", 1);
9698
}
9799

98100
/**

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

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -118,6 +118,11 @@ protected void execute() {
118118
protected boolean isFinished() {
119119
System.out.println("isFinished");
120120
return (turnController.onTarget() && Math.abs(dt.getGyroRate()) < 1);
121+
// return turnController.onTarget()
122+
// && Math.abs(dt.getLeftEncRate()) <= Robot.getConst("Maximum Velocity When
123+
// Stop", 1)
124+
// && Math.abs(dt.getRightEncRate()) <= Robot.getConst("Maximum Velocity When
125+
// Stop", 1);
121126
}
122127

123128
/**

0 commit comments

Comments
 (0)