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

Commit a1728d0

Browse files
committed
this is nelson's pull request but ready to merge
just fixed merge conflicts (plus like one change)
2 parents 3c2b3ad + 8ee9a13 commit a1728d0

File tree

9 files changed

+543
-88
lines changed

9 files changed

+543
-88
lines changed

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

Lines changed: 13 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -35,12 +35,15 @@ public class RobotMap {
3535

3636
public static PowerDistributionPanel pdp;
3737

38-
public static WPI_TalonSRX liftMotor;
38+
public static WPI_VictorSPX liftMotorA;
39+
public static WPI_TalonSRX liftMotorB;
40+
public static WPI_TalonSRX liftMotorC;
41+
public static SpeedControllerGroup liftMotors;
3942
public static Encoder liftEnc;
4043
public static DigitalSource liftEncPort1;
4144
public static DigitalSource liftEncPort2;
4245

43-
public static WPI_TalonSRX climberMotor;
46+
//public static WPI_TalonSRX climberMotor;
4447

4548
public static VictorSP leftIntakeMotor;
4649
public static VictorSP rightIntakeMotor;
@@ -120,15 +123,18 @@ private void configSPX(WPI_VictorSPX mc) {
120123

121124
public RobotMap() {
122125
pdp = new PowerDistributionPanel();
123-
124-
liftMotor = new WPI_TalonSRX(getPort("LiftTalonSRX", 7));
125-
configSRX(liftMotor);
126+
127+
liftMotorA = new WPI_VictorSPX(getPort("LiftVictorSPX", 5));
128+
configSPX(liftMotorA);
129+
liftMotorB = new WPI_TalonSRX(getPort("1LiftTalonSRX", 6));
130+
configSRX(liftMotorB);
131+
liftMotorC = new WPI_TalonSRX(getPort("2LiftTalonSRX", 7));
132+
configSRX(liftMotorC);
133+
liftMotors = new SpeedControllerGroup(liftMotorB, liftMotorA, liftMotorC);
126134
liftEncPort1 = new DigitalInput(getPort("1LiftEnc", 4));
127135
liftEncPort2 = new DigitalInput(getPort("2LiftEnc", 5));
128136
liftEnc = new Encoder(liftEncPort1, liftEncPort2);
129137
liftEnc.setPIDSourceType(PIDSourceType.kDisplacement);
130-
climberMotor = new WPI_TalonSRX(getPort("ClimberTalonSRX", 6));
131-
configSRX(climberMotor);
132138

133139
leftIntakeMotor = new VictorSP(getPort("IntakeLeftVictorSP", 8));
134140
rightIntakeMotor = new VictorSP(getPort("IntakeRightVictorSP", 9));

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

Lines changed: 11 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -14,55 +14,40 @@
1414
*/
1515
public class AutoLift extends Command implements PIDOutput{
1616
/**
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
17+
* All distances are measured from bottom of cube and + 3 inches for wiggle room for dropping cubes
18+
* Also, actual distances are divided by 3 because according to cad, the lift will have a 1:3 ratio from winch
1919
* to actual height.
2020
*/
2121

2222
/**
2323
* Distance to switch
2424
* 18.75 inches in starting position (this measurement is the fence that surrounds the switch)
25-
* 9.75 / 3 for ratio = 3.25
25+
* 21.75 / 3 for ratio = 7.25
2626
*/
27-
private final double SWITCH_DIST = 3.25;
27+
private final double SWITCH_DIST = 7.25;
2828
/**
2929
* Distance to scale
3030
* 5 feet starting
31-
* 51 / 3 = 17
31+
* 63 / 3 = 21
3232
*/
33-
private final double SCALE_DIST = 17;
33+
private final double SCALE_DIST = 21;
3434
/**
3535
* Distance to bar
36-
* 72 / 3 = 24
36+
* 87 / 3 = 29
3737
* 7 feet starting; bar distance should be changed because I'm not aware how climber mech will be positioned
3838
*/
39-
private final double BAR_DIST = 24;
39+
private final double BAR_DIST = 29;
4040
private double desiredDist = 0;
41-
private double currDist = 0;
41+
private double currDist;
4242
private LiftInterface lift;
4343
private Position desiredPos;
4444

4545
private PIDController liftController;
4646

4747
public AutoLift(Position stage, LiftInterface lift) {
48-
// Use requires() here to declare subsystem dependencies
49-
// eg. requires(chassis);
5048
this.lift = lift;
5149
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-
}
50+
currDist = lift.getHeight();
6651
switch(stage) {
6752
case GROUND:
6853
desiredDist = -currDist;
@@ -86,7 +71,6 @@ public AutoLift(Position stage, LiftInterface lift) {
8671

8772
// Called just before this Command runs the first time
8873
protected void initialize() {
89-
lift.resetEnc();
9074
// input is in inches
9175
//liftController.setInputRange(-Robot.getConst("Max High Speed", 204), Robot.getConst("Max High Speed", 204));
9276
// output in "motor units" (arcade and tank only accept values [-1, 1]
@@ -104,7 +88,7 @@ protected void execute() {
10488
// Make this return true when this Command no longer needs to run execute()
10589
protected boolean isFinished() {
10690
if(liftController.onTarget()) {
107-
lift.setTargetPosition(desiredPos);
91+
lift.setCurrPosition(desiredPos);
10892
return true;
10993
}
11094
return false;

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@
1111
*/
1212
public class Climber extends Subsystem implements ClimberInterface {
1313

14-
private final WPI_TalonSRX climberMotor = RobotMap.climberMotor;
14+
//private final WPI_TalonSRX climberMotor = RobotMap.climberMotor;
1515

1616

1717
/**
@@ -52,7 +52,7 @@ public void attachToBar() {
5252
* stops the climber
5353
*/
5454
public void stopClimber() {
55-
climberMotor.stopMotor();
55+
//climberMotor.stopMotor();
5656
}
5757

5858

Lines changed: 51 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -1,84 +1,97 @@
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;
4-
import org.usfirst.frc.team199.Robot2018.subsystems.LiftInterface.Position;
5-
6-
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
5+
import org.usfirst.frc.team199.Robot2018.commands.AutoLift;
76

87
import edu.wpi.first.wpilibj.Encoder;
8+
import edu.wpi.first.wpilibj.SpeedControllerGroup;
9+
import edu.wpi.first.wpilibj.command.Command;
910
import edu.wpi.first.wpilibj.command.Subsystem;
1011

1112
/**
1213
*
1314
*/
1415
public class Lift extends Subsystem implements LiftInterface {
1516

16-
private final WPI_TalonSRX liftMotor = RobotMap.liftMotor;
17+
private final SpeedControllerGroup liftMotors = RobotMap.liftMotors;
1718
private final Encoder liftEnc = RobotMap.liftEnc;
18-
private Position targetPosition = Position.GROUND;
19-
19+
private Position currPosition = Position.GROUND;
20+
2021
/**
2122
* Set the default command for a subsystem here.
22-
* */
23-
public void initDefaultCommand() {
24-
// Set the default command for a subsystem here.
25-
//setDefaultCommand(new MySpecialCommand());
26-
}
27-
28-
public void setTargetPosition(Position newPosition) {
29-
targetPosition = newPosition;
30-
}
23+
*/
24+
public void initDefaultCommand() {
25+
// Set the default command for a subsystem here.
26+
// setDefaultCommand(new MySpecialCommand());
27+
int angle = Robot.oi.manipulator.getPOV();
28+
29+
Command com = null;
30+
31+
if (angle == 0) {
32+
com = new AutoLift(Position.GROUND, this);
33+
setDefaultCommand(com);
34+
} else if (angle == 90 || angle == 180 || angle == 270) {
35+
com = new AutoLift(Position.SWITCH, this);
36+
setDefaultCommand(com);
37+
}
38+
}
3139

32-
/**
33-
* Uses (insert sensor here) to detect the current lift position
40+
/**
41+
* Sets the current position in the lift subsystem
42+
*
43+
* @param newPosition
44+
* - the new position meant to be set
45+
*/
46+
public void setCurrPosition(Position newPosition) {
47+
currPosition = newPosition;
48+
}
49+
50+
/**
51+
* Uses (insert sensor here) to detect the current lift position
3452
*/
3553
public double getHeight() {
36-
return -1;
54+
return liftEnc.getDistance() * 3;
3755
}
38-
56+
3957
/**
4058
* stops the lift
4159
*/
4260
public void stopLift() {
43-
liftMotor.stopMotor();
61+
liftMotors.stopMotor();
4462
}
45-
63+
4664
/**
4765
* gets current motor values
4866
*/
4967
public double getLiftSpeed() {
50-
return liftMotor.get();
51-
}
52-
53-
/**
54-
* Goes to specified height
55-
* @param position - ground, switch, scale, bar
56-
* @param offset - distance up or down from the position
57-
*/
58-
public void goToPosition(Position position, double offset) {
59-
68+
return liftMotors.get();
6069
}
70+
6171
/**
62-
* Runs lift motor at specified speed
63-
* @param speed - desired speed to run at
72+
* Runs lift motors at specified speed
73+
*
74+
* @param speed
75+
* - desired speed to run at
6476
*/
6577
public void runMotor(double output) {
66-
liftMotor.set(output);
78+
liftMotors.set(output);
6779
}
68-
80+
6981
/**
7082
* Returns the position the lift is currently at
83+
*
7184
* @return pos - current position
7285
*/
7386
public Position getCurrPos() {
74-
return targetPosition;
87+
return currPosition;
7588
}
89+
7690
/**
7791
* Resets the encoder
7892
*/
7993
public void resetEnc() {
8094
liftEnc.reset();
8195
}
82-
83-
}
8496

97+
}

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

Lines changed: 4 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -31,16 +31,8 @@ public enum Position {
3131
*/
3232
public double getLiftSpeed();
3333

34-
35-
/**
36-
* Goes to specified height
37-
* @param position - ground, switch, scale, bar
38-
* @param offset - distance up or down from position
39-
*/
40-
public void goToPosition(Position position, double offset);
41-
4234
/**
43-
* Runs lift motor at specified speed
35+
* Runs lift motors at specified speed
4436
* @param speed - desired speed to run at
4537
*/
4638
public void runMotor(double speed);
@@ -60,5 +52,7 @@ public enum Position {
6052
* Sets the current position in the lift subsystem
6153
* @param newPosition - the new position meant to be set
6254
*/
63-
public void setTargetPosition(Position newPosition);
55+
public void setCurrPosition(Position newPosition);
56+
57+
6458
}

0 commit comments

Comments
 (0)