Skip to content

Commit eeb8855

Browse files
author
Tyler Duckworth
committed
fixed errors
1 parent e0a8806 commit eeb8855

File tree

7 files changed

+69
-65
lines changed

7 files changed

+69
-65
lines changed

.DS_Store

-8 KB
Binary file not shown.

examples/can-arcade-drive/robot.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,3 @@
1-
#!/usr/bin/env python3
21
# ----------------------------------------------------------------------------
32
# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
43
# Open Source Software - may be modified and shared by FRC teams. The code

examples/get-set-params/robot.py

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,3 @@
1-
#!/usr/bin/env python3
21
# ----------------------------------------------------------------------------
32
# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
43
# Open Source Software - may be modified and shared by FRC teams. The code
@@ -31,18 +30,18 @@ def robotInit(self):
3130
# CANError.kOk
3231
# CANError.kError
3332
# CANError.kTimeout
34-
if self.motor.setIdleMode(rev.IdleMode.kCoast) != rev.CANError.kOK:
33+
if self.motor.setIdleMode(rev.IdleMode.kCoast) is not rev.CANError.kOK:
3534
wpilib.SmartDashboard.putString("Idle Mode", "Error")
3635

3736
# Similarly, parameters will have a get() method which allows you to
3837
# retrieve their values from the controller
39-
if self.motor.getIdleMode() == rev.IdleMode.kCoast:
38+
if self.motor.getIdleMode() is rev.IdleMode.kCoast:
4039
wpilib.SmartDashboard.putString("Idle Mode", "Coast")
4140
else:
4241
wpilib.SmartDashboard.putString("Idle Mode", "Brake")
4342

4443
# Set ramp rate to 0
45-
if self.motor.setOpenLoopRampRate(0) != rev.CANError.kOK:
44+
if self.motor.setOpenLoopRampRate(0) is not rev.CANError.kOK:
4645
wpilib.SmartDashboard.putString("Ramp Rate", "Error")
4746

4847
# Read back ramp value

examples/limit-switch/robot.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,3 @@
1-
#!/usr/bin/env python3
21
# ----------------------------------------------------------------------------
32
# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
43
# Open Source Software - may be modified and shared by FRC teams. The code

examples/position-pid-control/robot.py

Lines changed: 31 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,3 @@
1-
#!/usr/bin/env python3
21
# ----------------------------------------------------------------------------
32
# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
43
# Open Source Software - may be modified and shared by FRC teams. The code
@@ -24,30 +23,34 @@ def robotInit(self):
2423
self.encoder = self.motor.getEncoder()
2524

2625
# PID Coefficents and Controller Output Range
27-
self.coeff = {"p": 0.1, "i": 1e-4, "d": 0, "iz": 0, "ff": 0}
26+
self.kP = 0.1
27+
self.kI = 1e-4
28+
self.kD = 0
29+
self.kIz = 0
30+
self.kFF = 0
2831
self.kMinOutput = -1
2932
self.kMaxOutput = 1
3033

3134
# The restoreFactoryDefaults() method can be used to reset the
3235
# configuration parameters in the SPARK MAX to their factory default
3336
# state. If no argument is passed, these parameters will not persist
3437
# between power cycles
35-
self.motor.restoreFactoryDefaults()
38+
# self.motor.restoreFactoryDefaults()
3639

37-
# Set PID Coefficents
38-
self.pidController.setP(self.coeff["p"])
39-
self.pidController.setI(self.coeff["i"])
40-
self.pidController.setD(self.coeff["d"])
41-
self.pidController.setIZone(self.coeff["iz"])
42-
self.pidController.setFF(self.coeff["ff"])
40+
# Set PID Constants
41+
self.pidController.setP(self.kP)
42+
self.pidController.setI(self.kI)
43+
self.pidController.setD(self.kD)
44+
self.pidController.setIZone(self.kIz)
45+
self.pidController.setFF(self.kFF)
4346
self.pidController.setOutputRange(self.kMinOutput, self.kMaxOutput)
4447

4548
# Push PID Coefficients to SmartDashboard
46-
wpilib.SmartDashboard.putNumber("P Gain", self.coeff["p"])
47-
wpilib.SmartDashboard.putNumber("I Gain", self.coeff["i"])
48-
wpilib.SmartDashboard.putNumber("D Gain", self.coeff["d"])
49-
wpilib.SmartDashboard.putNumber("I Zone", self.coeff["iz"])
50-
wpilib.SmartDashboard.putNumber("Feed Forward", self.coeff["ff"])
49+
wpilib.SmartDashboard.putNumber("P Gain", self.kP)
50+
wpilib.SmartDashboard.putNumber("I Gain", self.kI)
51+
wpilib.SmartDashboard.putNumber("D Gain", self.kD)
52+
wpilib.SmartDashboard.putNumber("I Zone", self.kIz)
53+
wpilib.SmartDashboard.putNumber("Feed Forward", self.kFF)
5154
wpilib.SmartDashboard.putNumber("Min Output", self.kMinOutput)
5255
wpilib.SmartDashboard.putNumber("Max Output", self.kMaxOutput)
5356
wpilib.SmartDashboard.putNumber("Set Rotations", 0)
@@ -64,24 +67,25 @@ def teleopPeriodic(self):
6467
rotations = wpilib.SmartDashboard.getNumber("Set Rotations", 0)
6568

6669
# Update PIDController datapoints with the latest from SmartDashboard
67-
if p is not self.coeff["p"]:
70+
if p != self.kP:
6871
self.pidController.setP(p)
69-
self.coeff["p"] = p
70-
if i is not self.coeff["i"]:
71-
self.pidController.setI(pi)
72-
self.coeff["i"] = i
73-
if d is not self.coeff["d"]:
72+
self.kP = p
73+
if i != self.kI:
74+
self.pidController.setI(i)
75+
self.kI = i
76+
if d != self.kD:
7477
self.pidController.setD(d)
75-
self.coeff["d"] = d
76-
if iz is not self.coeff["iz"]:
78+
self.kD = d
79+
if iz != self.kIz:
7780
self.pidController.setIZone(iz)
78-
self.coeff["iz"] = iz
79-
if ff is not self.coeff["ff"]:
81+
self.kIz = iz
82+
if ff != self.kFF:
8083
self.pidController.setFF(ff)
81-
self.coeff["ff"] = ff
82-
if (min_out is not self.kMinOutput) or (max_out is not self.kMaxOutput):
84+
self.kFF = ff
85+
if (min_out != self.kMinOutput) or (max_out != self.kMaxOutput):
8386
self.pidController.setOutputRange(min_out, max_out)
84-
self.kMinOutput = min_out, self.kMaxOutput = max_out
87+
self.kMinOutput = min_out
88+
self.kMaxOutput = max_out
8589

8690
# PIDController objects are commanded to a set point using the
8791
# setReference() method.

examples/read-encoder-values/robot.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,3 @@
1-
#!/usr/bin/env python3
21
# ----------------------------------------------------------------------------
32
# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
43
# Open Source Software - may be modified and shared by FRC teams. The code

examples/velocity-pid-control/robot.py

Lines changed: 35 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,3 @@
1-
#!/usr/bin/env python3
21
# ----------------------------------------------------------------------------
32
# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
43
# Open Source Software - may be modified and shared by FRC teams. The code
@@ -26,9 +25,13 @@ def robotInit(self):
2625
self.joystick = wpilib.Joystick(0)
2726

2827
# PID Coefficents and Controller Output Range
29-
self.coeff = {"p": 0.1, "i": 1e-4, "d": 0, "iz": 0, "ff": 0}
28+
self.kP = 0.1
29+
self.kI = 1e-4
30+
self.kD = 0
31+
self.kIz = 0
32+
self.kFF = 0
3033
self.kMinOutput = -1
31-
self.kMaxOutput = 1
34+
self.kMaxOutput = 1
3235

3336
# Motor max RPM
3437
self.maxRPM = 5700
@@ -37,22 +40,22 @@ def robotInit(self):
3740
# configuration parameters in the SPARK MAX to their factory default
3841
# state. If no argument is passed, these parameters will not persist
3942
# between power cycles
40-
self.motor.restoreFactoryDefaults()
41-
42-
# Set PID Coefficents
43-
self.pidController.setP(self.coeff["p"])
44-
self.pidController.setI(self.coeff["i"])
45-
self.pidController.setD(self.coeff["d"])
46-
self.pidController.setIZone(self.coeff["iz"])
47-
self.pidController.setFF(self.coeff["ff"])
43+
# self.motor.restoreFactoryDefaults()
44+
45+
# Set PID Constants
46+
self.pidController.setP(self.kP)
47+
self.pidController.setI(self.kI)
48+
self.pidController.setD(self.kD)
49+
self.pidController.setIZone(self.kIz)
50+
self.pidController.setFF(self.kFF)
4851
self.pidController.setOutputRange(self.kMinOutput, self.kMaxOutput)
4952

5053
# Push PID Coefficients to SmartDashboard
51-
wpilib.SmartDashboard.putNumber("P Gain", self.coeff["p"])
52-
wpilib.SmartDashboard.putNumber("I Gain", self.coeff["i"])
53-
wpilib.SmartDashboard.putNumber("D Gain", self.coeff["d"])
54-
wpilib.SmartDashboard.putNumber("I Zone", self.coeff["iz"])
55-
wpilib.SmartDashboard.putNumber("Feed Forward", self.coeff["ff"])
54+
wpilib.SmartDashboard.putNumber("P Gain", self.kP)
55+
wpilib.SmartDashboard.putNumber("I Gain", self.kI)
56+
wpilib.SmartDashboard.putNumber("D Gain", self.kD)
57+
wpilib.SmartDashboard.putNumber("I Zone", self.kIz)
58+
wpilib.SmartDashboard.putNumber("Feed Forward", self.kFF)
5659
wpilib.SmartDashboard.putNumber("Min Output", self.kMinOutput)
5760
wpilib.SmartDashboard.putNumber("Max Output", self.kMaxOutput)
5861

@@ -67,24 +70,25 @@ def teleopPeriodic(self):
6770
max_out = wpilib.SmartDashboard.getNumber("Max Output", 0)
6871

6972
# Update PIDController datapoints with the latest from SmartDashboard
70-
if p is not self.coeff["p"]:
73+
if p != self.kP:
7174
self.pidController.setP(p)
72-
self.coeff["p"] = p
73-
if i is not self.coeff["i"]:
74-
self.pidController.setI(pi)
75-
self.coeff["i"] = i
76-
if d is not self.coeff["d"]:
75+
self.kP = p
76+
if i != self.kI:
77+
self.pidController.setI(i)
78+
self.kI = i
79+
if d != self.kD:
7780
self.pidController.setD(d)
78-
self.coeff["d"] = d
79-
if iz is not self.coeff["iz"]:
81+
self.kD = d
82+
if iz != self.kIz:
8083
self.pidController.setIZone(iz)
81-
self.coeff["iz"] = iz
82-
if ff is not self.coeff["ff"]:
84+
self.kIz = iz
85+
if ff != self.kFF:
8386
self.pidController.setFF(ff)
84-
self.coeff["ff"] = ff
85-
if (min_out is not self.kMinOutput) or (max_out is not self.kMaxOutput):
87+
self.kFF = ff
88+
if (min_out != self.kMinOutput) or (max_out != self.kMaxOutput):
8689
self.pidController.setOutputRange(min_out, max_out)
87-
self.kMinOutput = min_out, self.kMaxOutput = max_out
90+
self.kMinOutput = min_out
91+
self.kMaxOutput = max_out
8892

8993
self.setpoint = self.maxRPM * self.joystick.getY()
9094

@@ -103,10 +107,10 @@ def teleopPeriodic(self):
103107
#
104108
# For more information on what these types are, refer to the Spark Max
105109
# documentation.
106-
self.pidController.setReference(rotations, rev.ControlType.kVelocity)
110+
self.pidController.setReference(self.setpoint, rev.ControlType.kVelocity)
107111

108112
# Push Setpoint and the motor's current position to SmartDashboard.
109-
wpilib.SmartDashboard.putNumber("Setpoint", rotations)
113+
wpilib.SmartDashboard.putNumber("Setpoint", self.setpoint)
110114
wpilib.SmartDashboard.putNumber("Process Variable", self.encoder.getPosition())
111115

112116

0 commit comments

Comments
 (0)