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

Commit 5854469

Browse files
committed
Implemented lift functionalities onto right joystick
The command is mapped via button 10 and 11 on right joystick, the command is executed with a whileHeld()
1 parent 4937c90 commit 5854469

4 files changed

Lines changed: 70 additions & 2 deletions

File tree

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

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99

1010
import org.usfirst.frc.team199.Robot2018.commands.PIDMove;
1111
import org.usfirst.frc.team199.Robot2018.commands.PIDTurn;
12+
import org.usfirst.frc.team199.Robot2018.commands.RunLift;
1213
import org.usfirst.frc.team199.Robot2018.commands.SetDistancePerPulse;
1314
import org.usfirst.frc.team199.Robot2018.commands.ShiftDriveType;
1415
import org.usfirst.frc.team199.Robot2018.commands.ShiftHighGear;
@@ -31,6 +32,8 @@ public class OI {
3132
private JoystickButton shiftDriveTypeButton;
3233
private JoystickButton PIDMoveButton;
3334
private JoystickButton PIDTurnButton;
35+
private JoystickButton MoveLiftUpButton;
36+
private JoystickButton MoveLiftDownButton;
3437
public Joystick rightJoy;
3538
private JoystickButton updatePIDConstantsButton;
3639
private JoystickButton updateEncoderDPPButton;
@@ -55,6 +58,11 @@ public OI() {
5558
PIDMoveButton.whenPressed(new PIDMove(40, Robot.dt, RobotMap.distEncAvg));
5659
PIDTurnButton = new JoystickButton(leftJoy, getButton("PID Turn", 8));
5760
PIDTurnButton.whenPressed(new PIDTurn(30, Robot.dt, RobotMap.fancyGyro));
61+
62+
MoveLiftUpButton = new JoystickButton(rightJoy, getButton("Run Lift Motor Up",10));
63+
MoveLiftDownButton = new JoystickButton(rightJoy, getButton("Run Lift Motor Down",11));
64+
MoveLiftUpButton.whileHeld(new RunLift(Robot.lift,true));
65+
MoveLiftDownButton.whileHeld(new RunLift(Robot.lift,false));
5866

5967
rightJoy = new Joystick(1);
6068
updatePIDConstantsButton = new JoystickButton(rightJoy, getButton("Get PID Constants", 8));
Lines changed: 50 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,50 @@
1+
package org.usfirst.frc.team199.Robot2018.commands;
2+
3+
import org.usfirst.frc.team199.Robot2018.subsystems.LiftInterface;
4+
5+
import edu.wpi.first.wpilibj.command.Command;
6+
7+
/**
8+
*
9+
*/
10+
public class RunLift extends Command {
11+
12+
private LiftInterface lift;
13+
private final double SPEED = 0.05;
14+
private int dir;
15+
16+
public RunLift(LiftInterface lift, boolean up) {
17+
// Use requires() here to declare subsystem dependencies
18+
// eg. requires(chassis);
19+
this.lift = lift;
20+
if(up)
21+
dir = 1;
22+
else
23+
dir = -1;
24+
}
25+
26+
// Called just before this Command runs the first time
27+
protected void initialize() {
28+
}
29+
30+
// Called repeatedly when this Command is scheduled to run
31+
protected void execute() {
32+
lift.runMotor(SPEED * dir);
33+
}
34+
35+
// Make this return true when this Command no longer needs to run execute()
36+
protected boolean isFinished() {
37+
return false;
38+
}
39+
40+
// Called once after isFinished returns true
41+
protected void end() {
42+
lift.stopLift();
43+
}
44+
45+
// Called when another command which requires one or more of the same
46+
// subsystems is scheduled to run
47+
protected void interrupted() {
48+
end();
49+
}
50+
}

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

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,13 @@ public double getLiftSpeed() {
5656
public void goToPosition(Position position, double offset) {
5757

5858
}
59-
59+
/**
60+
* Runs lift motor at specified speed
61+
* @param speed - desired speed to run at
62+
*/
63+
public void runMotor(double output) {
64+
liftMotor.set(output);
65+
}
6066

6167
}
6268

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

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,10 @@ public enum Position {
3636
* @param offset - distance up or down from position
3737
*/
3838
public void goToPosition(Position position, double offset);
39-
39+
/**
40+
* Runs lift motor at specified speed
41+
* @param speed - desired speed to run at
42+
*/
43+
public void runMotor(double speed);
4044

4145
}

0 commit comments

Comments
 (0)