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

Commit cd525b2

Browse files
Compute hopefully reasonable defaults for lift PID constants.
1 parent 1320869 commit cd525b2

3 files changed

Lines changed: 40 additions & 12 deletions

File tree

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

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
import edu.wpi.first.wpilibj.SPI;
2424
import edu.wpi.first.wpilibj.SpeedControllerGroup;
2525
import edu.wpi.first.wpilibj.VictorSP;
26+
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
2627
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
2728

2829
/**
@@ -130,11 +131,17 @@ public RobotMap() {
130131
configSRX(liftMotorB);
131132
liftMotorC = new WPI_TalonSRX(getPort("2LiftTalonSRX", 7));
132133
configSRX(liftMotorC);
133-
liftMotors = new SpeedControllerGroup(liftMotorB, liftMotorA, liftMotorC);
134+
// liftMotors = new SpeedControllerGroup(liftMotorB, liftMotorA, liftMotorC);
135+
liftMotors = new SpeedControllerGroup(liftMotorC);
136+
liftMotors.setName("Lift", "CIM Motor");
137+
LiveWindow.add(liftMotors);
138+
134139
liftEncPort1 = new DigitalInput(getPort("1LiftEnc", 4));
135140
liftEncPort2 = new DigitalInput(getPort("2LiftEnc", 5));
136141
liftEnc = new Encoder(liftEncPort1, liftEncPort2);
137142
liftEnc.setPIDSourceType(PIDSourceType.kDisplacement);
143+
liftEnc.setName("Lift", "Encoder");
144+
LiveWindow.add(liftEnc);
138145

139146
leftIntakeMotor = new VictorSP(getPort("IntakeLeftVictorSP", 8));
140147
rightIntakeMotor = new VictorSP(getPort("IntakeRightVictorSP", 9));

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

Lines changed: 16 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
import org.usfirst.frc.team199.Robot2018.commands.UpdateLiftPosition;
66

77
import edu.wpi.first.wpilibj.Encoder;
8+
import edu.wpi.first.wpilibj.PIDController;
89
import edu.wpi.first.wpilibj.SpeedControllerGroup;
910
import edu.wpi.first.wpilibj.command.PIDSubsystem;
1011

@@ -24,8 +25,20 @@ public class Lift extends PIDSubsystem implements LiftInterface {
2425
private final double BAR_DIST;
2526

2627
public Lift() {
27-
super("Lift", Robot.getConst("LiftkP", 0.1), Robot.getConst("LiftkI", 0), Robot.getConst("LiftkD", 0),
28-
Robot.getConst("LiftkF", 0.1));
28+
super("Lift", 0, 0, 0, 0);
29+
30+
double maxSpeed = getLiftMaxSpeed();
31+
32+
double r = Robot.getConst("LiftPidR", 3.0);
33+
double kP = r / getLiftTimeConstant() / maxSpeed;
34+
double kI = 0;
35+
double kD = r / maxSpeed;
36+
double kF = 1 / (maxSpeed * Robot.getConst("Default PID Update Time", 0.05));
37+
38+
PIDController liftController = getPIDController();
39+
40+
liftController.setPID(Robot.getConst("LiftkP", kP), Robot.getConst("LiftkI", kI), Robot.getConst("LiftkD", kD),
41+
Robot.getConst("LiftkF", kF));
2942

3043
setInputRange(0, Robot.getConst("Lift Max Height", 24));
3144
setOutputRange(-1, 1);
@@ -220,6 +233,6 @@ public double getLiftRadius() {
220233
* lift components, NOT cube
221234
*/
222235
public double getLiftedWeight() {
223-
return Robot.getConst("Weight of Lifted Stuff", 342);
236+
return Robot.getConst("Weight of Lifted Stuff", 53.11);
224237
}
225238
}

shuffleboard.json

Lines changed: 16 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -88,8 +88,7 @@
8888
"_type": "Graph",
8989
"_source0": "network_table:///SmartDashboard/Drivetrain/Left VPID Targ",
9090
"_title": "/SmartDashboard/Drivetrain/Left VPID Targ",
91-
"Visible time": 30.0,
92-
"SmartDashboard/Drivetrain/Left VPID Targ visible": true
91+
"Visible time": 30.0
9392
}
9493
},
9594
"4,0": {
@@ -101,8 +100,7 @@
101100
"_type": "Graph",
102101
"_source0": "network_table:///SmartDashboard/Drivetrain/Right VPID Targ",
103102
"_title": "/SmartDashboard/Drivetrain/Right VPID Targ",
104-
"Visible time": 30.0,
105-
"SmartDashboard/Drivetrain/Right VPID Targ visible": true
103+
"Visible time": 30.0
106104
}
107105
},
108106
"4,3": {
@@ -386,8 +384,7 @@
386384
"_type": "Graph",
387385
"_source0": "network_table:///SmartDashboard/Drivetrain/Left VPID Targ",
388386
"_title": "/SmartDashboard/Drivetrain/Left VPID Targ",
389-
"Visible time": 10.0,
390-
"SmartDashboard/Drivetrain/Left VPID Targ visible": true
387+
"Visible time": 10.0
391388
}
392389
},
393390
"5,2": {
@@ -399,8 +396,7 @@
399396
"_type": "Graph",
400397
"_source0": "network_table:///SmartDashboard/Drivetrain/Right VPID Targ",
401398
"_title": "/SmartDashboard/Drivetrain/Right VPID Targ",
402-
"Visible time": 10.0,
403-
"SmartDashboard/Drivetrain/Right VPID Targ visible": true
399+
"Visible time": 10.0
404400
}
405401
},
406402
"5,1": {
@@ -941,6 +937,18 @@
941937
}
942938
}
943939
}
940+
},
941+
{
942+
"title": "Tab 8",
943+
"autoPopulate": false,
944+
"autoPopulatePrefix": "",
945+
"widgetPane": {
946+
"gridSize": 128.0,
947+
"showGrid": true,
948+
"hgap": 16.0,
949+
"vgap": 16.0,
950+
"tiles": {}
951+
}
944952
}
945953
]
946954
}

0 commit comments

Comments
 (0)