1
- #!/usr/bin/env python3
2
1
# ----------------------------------------------------------------------------
3
2
# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
4
3
# Open Source Software - may be modified and shared by FRC teams. The code
@@ -26,9 +25,13 @@ def robotInit(self):
26
25
self .joystick = wpilib .Joystick (0 )
27
26
28
27
# 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
30
33
self .kMinOutput = - 1
31
- self .kMaxOutput = 1
34
+ self .kMaxOutput = 1
32
35
33
36
# Motor max RPM
34
37
self .maxRPM = 5700
@@ -37,22 +40,22 @@ def robotInit(self):
37
40
# configuration parameters in the SPARK MAX to their factory default
38
41
# state. If no argument is passed, these parameters will not persist
39
42
# 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 )
48
51
self .pidController .setOutputRange (self .kMinOutput , self .kMaxOutput )
49
52
50
53
# 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 )
56
59
wpilib .SmartDashboard .putNumber ("Min Output" , self .kMinOutput )
57
60
wpilib .SmartDashboard .putNumber ("Max Output" , self .kMaxOutput )
58
61
@@ -67,24 +70,25 @@ def teleopPeriodic(self):
67
70
max_out = wpilib .SmartDashboard .getNumber ("Max Output" , 0 )
68
71
69
72
# Update PIDController datapoints with the latest from SmartDashboard
70
- if p is not self .coeff [ "p" ] :
73
+ if p != self .kP :
71
74
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 :
77
80
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 :
80
83
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 :
83
86
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 ):
86
89
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
88
92
89
93
self .setpoint = self .maxRPM * self .joystick .getY ()
90
94
@@ -103,10 +107,10 @@ def teleopPeriodic(self):
103
107
#
104
108
# For more information on what these types are, refer to the Spark Max
105
109
# documentation.
106
- self .pidController .setReference (rotations , rev .ControlType .kVelocity )
110
+ self .pidController .setReference (self . setpoint , rev .ControlType .kVelocity )
107
111
108
112
# Push Setpoint and the motor's current position to SmartDashboard.
109
- wpilib .SmartDashboard .putNumber ("Setpoint" , rotations )
113
+ wpilib .SmartDashboard .putNumber ("Setpoint" , self . setpoint )
110
114
wpilib .SmartDashboard .putNumber ("Process Variable" , self .encoder .getPosition ())
111
115
112
116
0 commit comments