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

Commit 1aa9f75

Browse files
nelly-yylhmcgann
authored andcommitted
Conflicts: Robot2018/src/org/usfirst/frc/team199/Robot2018/OI.java Robot2018/src/org/usfirst/frc/team199/Robot2018/RobotMap.java
2 parents 5212a32 + 417f627 commit 1aa9f75

9 files changed

Lines changed: 248 additions & 8 deletions

File tree

Binary file not shown.
Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,2 +1,2 @@
1-
#Sat Feb 17 17:04:37 PST 2018
1+
#Sun Feb 18 11:01:27 PST 2018
22
C\:\\Users\\dean\\git\\RobotCode2018\\Robot2018\\lib\\libpathfinderjava.so=4087ee38c338446b8305f67716260df4

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

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
import org.usfirst.frc.team199.Robot2018.commands.PIDTurn;
1717
import org.usfirst.frc.team199.Robot2018.commands.RaiseIntake;
1818
import org.usfirst.frc.team199.Robot2018.commands.ResetEncoders;
19+
import org.usfirst.frc.team199.Robot2018.commands.RunLift;
1920
import org.usfirst.frc.team199.Robot2018.commands.SetDistancePerPulse;
2021
import org.usfirst.frc.team199.Robot2018.commands.ShiftDriveType;
2122
import org.usfirst.frc.team199.Robot2018.commands.ShiftHighGear;
@@ -39,6 +40,8 @@ public class OI {
3940
private JoystickButton PIDMoveButton;
4041
private JoystickButton PIDTurnButton;
4142
private JoystickButton resetEncButton;
43+
private JoystickButton MoveLiftUpButton;
44+
private JoystickButton MoveLiftDownButton;
4245
public Joystick rightJoy;
4346
private JoystickButton updatePIDConstantsButton;
4447
private JoystickButton updateEncoderDPPButton;
@@ -84,6 +87,10 @@ public OI() {
8487
updatePIDConstantsButton.whenPressed(new UpdatePIDConstants());
8588
updateEncoderDPPButton = new JoystickButton(rightJoy, getButton("Get Encoder Dist Per Pulse", 9));
8689
updateEncoderDPPButton.whenPressed(new SetDistancePerPulse());
90+
MoveLiftUpButton = new JoystickButton(rightJoy, getButton("Run Lift Motor Up", 10));
91+
MoveLiftDownButton = new JoystickButton(rightJoy, getButton("Run Lift Motor Down", 11));
92+
MoveLiftUpButton.whileHeld(new RunLift(Robot.lift, true));
93+
MoveLiftDownButton.whileHeld(new RunLift(Robot.lift, false));
8794

8895
manipulator = new Joystick(2);
8996
closeIntake = new JoystickButton(manipulator, getButton("Close Intake Button", 1));

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

Lines changed: 12 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,10 @@ public class RobotMap {
3737
public static PowerDistributionPanel pdp;
3838

3939
public static WPI_TalonSRX liftMotor;
40+
public static Encoder liftEnc;
41+
public static DigitalSource liftEncPort1;
42+
public static DigitalSource liftEncPort2;
43+
4044
public static WPI_TalonSRX climberMotor;
4145

4246
public static VictorSP leftIntakeMotor;
@@ -115,12 +119,14 @@ private void configSPX(WPI_VictorSPX mc) {
115119
public RobotMap() {
116120
pdp = new PowerDistributionPanel();
117121

118-
// intakeMotor = new WPI_TalonSRX(getPort("IntakeTalonSRX", 4));
119-
// configSRX(intakeMotor);
120-
// liftMotor = new WPI_TalonSRX(getPort("LiftTalonSRX", 5));
121-
// configSRX(liftMotor);
122-
// climberMotor = new WPI_TalonSRX(getPort("ClimberTalonSRX", 6));
123-
// configSRX(climberMotor);
122+
liftMotor = new WPI_TalonSRX(getPort("LiftTalonSRX", 7));
123+
configSRX(liftMotor);
124+
liftEncPort1 = new DigitalInput(getPort("1LiftEnc", 4));
125+
liftEncPort2 = new DigitalInput(getPort("2LiftEnc", 5));
126+
liftEnc = new Encoder(liftEncPort1, liftEncPort2);
127+
liftEnc.setPIDSourceType(PIDSourceType.kDisplacement);
128+
climberMotor = new WPI_TalonSRX(getPort("ClimberTalonSRX", 6));
129+
configSRX(climberMotor);
124130

125131
leftIntakeMotor = new VictorSP(getPort("IntakeLeftVictorSP", 9));
126132
rightIntakeMotor = new VictorSP(getPort("IntakeRightVictorSP", 8));
Lines changed: 130 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,130 @@
1+
package org.usfirst.frc.team199.Robot2018.commands;
2+
3+
import org.usfirst.frc.team199.Robot2018.Robot;
4+
import org.usfirst.frc.team199.Robot2018.RobotMap;
5+
import org.usfirst.frc.team199.Robot2018.subsystems.LiftInterface;
6+
import org.usfirst.frc.team199.Robot2018.subsystems.LiftInterface.Position;
7+
8+
import edu.wpi.first.wpilibj.PIDController;
9+
import edu.wpi.first.wpilibj.PIDOutput;
10+
import edu.wpi.first.wpilibj.command.Command;
11+
12+
/**
13+
*
14+
*/
15+
public class AutoLift extends Command implements PIDOutput{
16+
/**
17+
* All distances are - 1 foot for initial height of intake and + 3 inches for wiggle room for dropping cubes
18+
* Also, acutal distances are divided by 3 because according to cad, the lift will have a 1:3 ratio from winch
19+
* to actual height.
20+
*/
21+
22+
/**
23+
* Distance to switch
24+
* 18.75 inches in starting position (this measurement is the fence that surrounds the switch)
25+
* 9.75 / 3 for ratio = 3.25
26+
*/
27+
private final double SWITCH_DIST = 3.25;
28+
/**
29+
* Distance to scale
30+
* 5 feet starting
31+
* 51 / 3 = 17
32+
*/
33+
private final double SCALE_DIST = 17;
34+
/**
35+
* Distance to bar
36+
* 72 / 3 = 24
37+
* 7 feet starting; bar distance should be changed because I'm not aware how climber mech will be positioned
38+
*/
39+
private final double BAR_DIST = 24;
40+
private double desiredDist = 0;
41+
private double currDist = 0;
42+
private LiftInterface lift;
43+
private Position desiredPos;
44+
45+
private PIDController liftController;
46+
47+
public AutoLift(Position stage, LiftInterface lift) {
48+
// Use requires() here to declare subsystem dependencies
49+
// eg. requires(chassis);
50+
this.lift = lift;
51+
requires(Robot.lift);
52+
switch(lift.getCurrPos()) {
53+
case GROUND:
54+
currDist = 0;
55+
break;
56+
case SWITCH:
57+
currDist = SWITCH_DIST;
58+
break;
59+
case SCALE:
60+
currDist = SCALE_DIST;
61+
break;
62+
case BAR:
63+
currDist = BAR_DIST;
64+
break;
65+
}
66+
switch(stage) {
67+
case GROUND:
68+
desiredDist = -currDist;
69+
break;
70+
case SWITCH:
71+
desiredDist = SWITCH_DIST - currDist;
72+
break;
73+
case SCALE:
74+
desiredDist = SCALE_DIST - currDist;
75+
break;
76+
case BAR:
77+
desiredDist = BAR_DIST - currDist;
78+
break;
79+
}
80+
81+
liftController = new PIDController(Robot.getConst("LiftkP", 1), Robot.getConst("LiftkI", 0),
82+
Robot.getConst("LiftkD", 0),RobotMap.liftEnc, this);
83+
84+
desiredPos = stage;
85+
}
86+
87+
// Called just before this Command runs the first time
88+
protected void initialize() {
89+
lift.resetEnc();
90+
// input is in inches
91+
//liftController.setInputRange(-Robot.getConst("Max High Speed", 204), Robot.getConst("Max High Speed", 204));
92+
// output in "motor units" (arcade and tank only accept values [-1, 1]
93+
liftController.setOutputRange(-1.0, 1.0);
94+
liftController.setContinuous(false);
95+
//liftController.setAbsoluteTolerance(Robot.getConst("MoveTolerance", 2));
96+
liftController.setSetpoint(desiredDist);
97+
liftController.enable();
98+
}
99+
100+
// Called repeatedly when this Command is scheduled to run
101+
protected void execute() {
102+
}
103+
104+
// Make this return true when this Command no longer needs to run execute()
105+
protected boolean isFinished() {
106+
if(liftController.onTarget()) {
107+
lift.setTargetPosition(desiredPos);
108+
return true;
109+
}
110+
return false;
111+
}
112+
113+
// Called once after isFinished returns true
114+
protected void end() {
115+
liftController.disable();
116+
liftController.free();
117+
}
118+
119+
// Called when another command which requires one or more of the same
120+
// subsystems is scheduled to run
121+
protected void interrupted() {
122+
end();
123+
}
124+
125+
@Override
126+
public void pidWrite(double output) {
127+
lift.runMotor(output);
128+
}
129+
130+
}
Lines changed: 52 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
1+
package org.usfirst.frc.team199.Robot2018.commands;
2+
3+
import org.usfirst.frc.team199.Robot2018.Robot;
4+
import org.usfirst.frc.team199.Robot2018.subsystems.LiftInterface;
5+
6+
import edu.wpi.first.wpilibj.command.Command;
7+
8+
/**
9+
*
10+
*/
11+
public class RunLift extends Command {
12+
13+
private LiftInterface lift;
14+
private final double SPEED = 0.05;
15+
private int dir;
16+
17+
public RunLift(LiftInterface lift, boolean up) {
18+
// Use requires() here to declare subsystem dependencies
19+
// eg. requires(chassis);
20+
this.lift = lift;
21+
requires(Robot.lift);
22+
if (up)
23+
dir = 1;
24+
else
25+
dir = -1;
26+
}
27+
28+
// Called just before this Command runs the first time
29+
protected void initialize() {
30+
}
31+
32+
// Called repeatedly when this Command is scheduled to run
33+
protected void execute() {
34+
lift.runMotor(SPEED * dir);
35+
}
36+
37+
// Make this return true when this Command no longer needs to run execute()
38+
protected boolean isFinished() {
39+
return false;
40+
}
41+
42+
// Called once after isFinished returns true
43+
protected void end() {
44+
lift.stopLift();
45+
}
46+
47+
// Called when another command which requires one or more of the same
48+
// subsystems is scheduled to run
49+
protected void interrupted() {
50+
end();
51+
}
52+
}

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

Lines changed: 23 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,11 @@
11
package org.usfirst.frc.team199.Robot2018.subsystems;
22

33
import org.usfirst.frc.team199.Robot2018.RobotMap;
4+
import org.usfirst.frc.team199.Robot2018.subsystems.LiftInterface.Position;
45

56
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
67

8+
import edu.wpi.first.wpilibj.Encoder;
79
import edu.wpi.first.wpilibj.command.Subsystem;
810

911
/**
@@ -12,7 +14,7 @@
1214
public class Lift extends Subsystem implements LiftInterface {
1315

1416
private final WPI_TalonSRX liftMotor = RobotMap.liftMotor;
15-
17+
private final Encoder liftEnc = RobotMap.liftEnc;
1618
private Position targetPosition = Position.GROUND;
1719

1820
/**
@@ -56,7 +58,27 @@ public double getLiftSpeed() {
5658
public void goToPosition(Position position, double offset) {
5759

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

69+
/**
70+
* Returns the position the lift is currently at
71+
* @return pos - current position
72+
*/
73+
public Position getCurrPos() {
74+
return targetPosition;
75+
}
76+
/**
77+
* Resets the encoder
78+
*/
79+
public void resetEnc() {
80+
liftEnc.reset();
81+
}
6082

6183
}
6284

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

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
package org.usfirst.frc.team199.Robot2018.subsystems;
22

3+
import org.usfirst.frc.team199.Robot2018.subsystems.LiftInterface.Position;
4+
35
public interface LiftInterface {
46

57
/**
@@ -37,5 +39,26 @@ public enum Position {
3739
*/
3840
public void goToPosition(Position position, double offset);
3941

42+
/**
43+
* Runs lift motor at specified speed
44+
* @param speed - desired speed to run at
45+
*/
46+
public void runMotor(double speed);
47+
48+
/**
49+
* Returns the position the lift is currently at
50+
* @return pos - current position
51+
*/
52+
public Position getCurrPos();
4053

54+
/**
55+
* Resets the encoder
56+
*/
57+
public void resetEnc();
58+
59+
/**
60+
* Sets the current position in the lift subsystem
61+
* @param newPosition - the new position meant to be set
62+
*/
63+
public void setTargetPosition(Position newPosition);
4164
}

Robot2018/test/org/usfirst/frc/team199/Robot2018/LiftTester.java

Whitespace-only changes.

0 commit comments

Comments
 (0)