blob: 2a623d70f60996a63b0989c4b8e86ce9a5daa19b [file] [log] [blame]
Comran Morshed2ae094e2016-01-23 20:43:20 +00001#!/usr/bin/python
2
3from frc971.control_loops.python import control_loop
4from frc971.control_loops.python import controls
Comran Morshed2ae094e2016-01-23 20:43:20 +00005import numpy
6import sys
7import matplotlib
8from matplotlib import pylab
9import gflags
10import glog
11
12FLAGS = gflags.FLAGS
13
14try:
15 gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
16except gflags.DuplicateFlagError:
17 pass
18
19class Intake(control_loop.ControlLoop):
Austin Schuh07cb5852016-01-31 00:58:46 -080020 def __init__(self, name="Intake"):
Comran Morshed2ae094e2016-01-23 20:43:20 +000021 super(Intake, self).__init__(name)
22 # TODO(constants): Update all of these & retune poles.
23 # Stall Torque in N m
Austin Schuh07cb5852016-01-31 00:58:46 -080024 self.stall_torque = 0.71
Comran Morshed2ae094e2016-01-23 20:43:20 +000025 # Stall Current in Amps
Austin Schuh07cb5852016-01-31 00:58:46 -080026 self.stall_current = 134
Comran Morshed2ae094e2016-01-23 20:43:20 +000027 # Free Speed in RPM
Austin Schuh07cb5852016-01-31 00:58:46 -080028 self.free_speed = 18730
Comran Morshed2ae094e2016-01-23 20:43:20 +000029 # Free Current in Amps
Austin Schuh07cb5852016-01-31 00:58:46 -080030 self.free_current = 0.7
Comran Morshed2ae094e2016-01-23 20:43:20 +000031
32 # Resistance of the motor
33 self.R = 12.0 / self.stall_current
34 # Motor velocity constant
35 self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
36 (12.0 - self.R * self.free_current))
37 # Torque constant
38 self.Kt = self.stall_torque / self.stall_current
39 # Gear ratio
Austin Schuh07cb5852016-01-31 00:58:46 -080040 self.G = (56.0 / 12.0) * (54.0 / 14.0) * (64.0 / 18.0) * (48.0 / 16.0)
Comran Morshed2ae094e2016-01-23 20:43:20 +000041
Austin Schuh07cb5852016-01-31 00:58:46 -080042 self.J = 0.9
Comran Morshed2ae094e2016-01-23 20:43:20 +000043
44 # Control loop time step
45 self.dt = 0.005
46
47 # State is [position, velocity]
48 # Input is [Voltage]
49
50 C1 = self.G * self.G * self.Kt / (self.R * self.J * self.Kv)
51 C2 = self.Kt * self.G / (self.J * self.R)
52
53 self.A_continuous = numpy.matrix(
54 [[0, 1],
55 [0, -C1]])
56
57 # Start with the unmodified input
58 self.B_continuous = numpy.matrix(
59 [[0],
60 [C2]])
61
62 self.C = numpy.matrix([[1, 0]])
63 self.D = numpy.matrix([[0]])
64
65 self.A, self.B = self.ContinuousToDiscrete(
66 self.A_continuous, self.B_continuous, self.dt)
67
68 controllability = controls.ctrb(self.A, self.B)
69
Austin Schuha88c4072016-02-06 14:31:03 -080070 glog.debug("Free speed is %f", self.free_speed * numpy.pi * 2.0 / 60.0 / self.G)
Comran Morshed2ae094e2016-01-23 20:43:20 +000071
Austin Schuh07cb5852016-01-31 00:58:46 -080072 q_pos = 0.20
73 q_vel = 5.5
Comran Morshed2ae094e2016-01-23 20:43:20 +000074 self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0],
75 [0.0, (1.0 / (q_vel ** 2.0))]])
76
77 self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0))]])
78 self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
79
Austin Schuha88c4072016-02-06 14:31:03 -080080 glog.debug('K %s', repr(self.K))
81 glog.debug('Poles are %s',
82 repr(numpy.linalg.eig(self.A - self.B * self.K)[0]))
Comran Morshed2ae094e2016-01-23 20:43:20 +000083
84 self.rpl = 0.30
85 self.ipl = 0.10
86 self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
87 self.rpl - 1j * self.ipl])
88
Austin Schuha88c4072016-02-06 14:31:03 -080089 glog.debug('L is %s', repr(self.L))
Comran Morshed2ae094e2016-01-23 20:43:20 +000090
91 q_pos = 0.05
92 q_vel = 2.65
93 self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0],
94 [0.0, (q_vel ** 2.0)]])
95
96 r_volts = 0.025
97 self.R = numpy.matrix([[(r_volts ** 2.0)]])
98
99 self.KalmanGain, self.Q_steady = controls.kalman(
100 A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
101
Austin Schuha88c4072016-02-06 14:31:03 -0800102 glog.debug('Kal %s', repr(self.KalmanGain))
Comran Morshed2ae094e2016-01-23 20:43:20 +0000103 self.L = self.A * self.KalmanGain
Austin Schuha88c4072016-02-06 14:31:03 -0800104 glog.debug('KalL is %s', repr(self.L))
Comran Morshed2ae094e2016-01-23 20:43:20 +0000105
106 # The box formed by U_min and U_max must encompass all possible values,
107 # or else Austin's code gets angry.
108 self.U_max = numpy.matrix([[12.0]])
109 self.U_min = numpy.matrix([[-12.0]])
110
111 self.InitializeState()
112
113class IntegralIntake(Intake):
Austin Schuh07cb5852016-01-31 00:58:46 -0800114 def __init__(self, name="IntegralIntake"):
115 super(IntegralIntake, self).__init__(name=name)
Comran Morshed2ae094e2016-01-23 20:43:20 +0000116
117 self.A_continuous_unaugmented = self.A_continuous
118 self.B_continuous_unaugmented = self.B_continuous
119
120 self.A_continuous = numpy.matrix(numpy.zeros((3, 3)))
121 self.A_continuous[0:2, 0:2] = self.A_continuous_unaugmented
122 self.A_continuous[0:2, 2] = self.B_continuous_unaugmented
123
124 self.B_continuous = numpy.matrix(numpy.zeros((3, 1)))
125 self.B_continuous[0:2, 0] = self.B_continuous_unaugmented
126
127 self.C_unaugmented = self.C
128 self.C = numpy.matrix(numpy.zeros((1, 3)))
129 self.C[0:1, 0:2] = self.C_unaugmented
130
131 self.A, self.B = self.ContinuousToDiscrete(self.A_continuous, self.B_continuous, self.dt)
132
133 q_pos = 0.08
134 q_vel = 4.00
Austin Schuh07cb5852016-01-31 00:58:46 -0800135 q_voltage = 3.0
Comran Morshed2ae094e2016-01-23 20:43:20 +0000136 self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0, 0.0],
137 [0.0, (q_vel ** 2.0), 0.0],
138 [0.0, 0.0, (q_voltage ** 2.0)]])
139
140 r_pos = 0.05
141 self.R = numpy.matrix([[(r_pos ** 2.0)]])
142
143 self.KalmanGain, self.Q_steady = controls.kalman(
144 A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
145 self.L = self.A * self.KalmanGain
146
147 self.K_unaugmented = self.K
148 self.K = numpy.matrix(numpy.zeros((1, 3)))
149 self.K[0, 0:2] = self.K_unaugmented
150 self.K[0, 2] = 1
151
152 self.InitializeState()
Austin Schuh07cb5852016-01-31 00:58:46 -0800153
Comran Morshed2ae094e2016-01-23 20:43:20 +0000154class ScenarioPlotter(object):
155 def __init__(self):
156 # Various lists for graphing things.
157 self.t = []
158 self.x = []
159 self.v = []
160 self.a = []
161 self.x_hat = []
162 self.u = []
Austin Schuh07cb5852016-01-31 00:58:46 -0800163 self.offset = []
Comran Morshed2ae094e2016-01-23 20:43:20 +0000164
165 def run_test(self, intake, goal, iterations=200, controller_intake=None,
166 observer_intake=None):
167 """Runs the intake plant with an initial condition and goal.
168
169 Test for whether the goal has been reached and whether the separation
170 goes outside of the initial and goal values by more than
171 max_separation_error.
172
173 Prints out something for a failure of either condition and returns
174 False if tests fail.
175 Args:
176 intake: intake object to use.
177 goal: goal state.
178 iterations: Number of timesteps to run the model for.
179 controller_intake: Intake object to get K from, or None if we should
180 use intake.
181 observer_intake: Intake object to use for the observer, or None if we should
182 use the actual state.
183 """
184
185 if controller_intake is None:
186 controller_intake = intake
187
188 vbat = 12.0
189
190 if self.t:
191 initial_t = self.t[-1] + intake.dt
192 else:
193 initial_t = 0
194
195 for i in xrange(iterations):
196 X_hat = intake.X
197
198 if observer_intake is not None:
199 X_hat = observer_intake.X_hat
200 self.x_hat.append(observer_intake.X_hat[0, 0])
201
202 U = controller_intake.K * (goal - X_hat)
203 U[0, 0] = numpy.clip(U[0, 0], -vbat, vbat)
204 self.x.append(intake.X[0, 0])
205
206 if self.v:
207 last_v = self.v[-1]
208 else:
209 last_v = 0
210
211 self.v.append(intake.X[1, 0])
212 self.a.append((self.v[-1] - last_v) / intake.dt)
213
214 if observer_intake is not None:
215 observer_intake.Y = intake.Y
216 observer_intake.CorrectObserver(U)
Austin Schuh07cb5852016-01-31 00:58:46 -0800217 self.offset.append(observer_intake.X_hat[2, 0])
Comran Morshed2ae094e2016-01-23 20:43:20 +0000218
Austin Schuh07cb5852016-01-31 00:58:46 -0800219 intake.Update(U + 2.0)
Comran Morshed2ae094e2016-01-23 20:43:20 +0000220
221 if observer_intake is not None:
222 observer_intake.PredictObserver(U)
223
224 self.t.append(initial_t + i * intake.dt)
225 self.u.append(U[0, 0])
226
227 glog.debug('Time: %f', self.t[-1])
228
229 def Plot(self):
230 pylab.subplot(3, 1, 1)
231 pylab.plot(self.t, self.x, label='x')
232 pylab.plot(self.t, self.x_hat, label='x_hat')
233 pylab.legend()
234
235 pylab.subplot(3, 1, 2)
236 pylab.plot(self.t, self.u, label='u')
Austin Schuh07cb5852016-01-31 00:58:46 -0800237 pylab.plot(self.t, self.offset, label='voltage_offset')
238 pylab.legend()
Comran Morshed2ae094e2016-01-23 20:43:20 +0000239
240 pylab.subplot(3, 1, 3)
241 pylab.plot(self.t, self.a, label='a')
Comran Morshed2ae094e2016-01-23 20:43:20 +0000242 pylab.legend()
Austin Schuh07cb5852016-01-31 00:58:46 -0800243
Comran Morshed2ae094e2016-01-23 20:43:20 +0000244 pylab.show()
245
246
247def main(argv):
248 argv = FLAGS(argv)
Austin Schuha88c4072016-02-06 14:31:03 -0800249 glog.init()
Comran Morshed2ae094e2016-01-23 20:43:20 +0000250
Comran Morshed2ae094e2016-01-23 20:43:20 +0000251 scenario_plotter = ScenarioPlotter()
252
Austin Schuh07cb5852016-01-31 00:58:46 -0800253 intake = Intake()
254 intake_controller = IntegralIntake()
255 observer_intake = IntegralIntake()
Comran Morshed2ae094e2016-01-23 20:43:20 +0000256
257 # Test moving the intake with constant separation.
258 initial_X = numpy.matrix([[0.0], [0.0]])
Austin Schuh07cb5852016-01-31 00:58:46 -0800259 R = numpy.matrix([[numpy.pi/2.0], [0.0], [0.0]])
Comran Morshed2ae094e2016-01-23 20:43:20 +0000260 scenario_plotter.run_test(intake, goal=R, controller_intake=intake_controller,
261 observer_intake=observer_intake, iterations=200)
262
263 if FLAGS.plot:
264 scenario_plotter.Plot()
265
266 # Write the generated constants out to a file.
267 if len(argv) != 5:
268 glog.fatal('Expected .h file name and .cc file name for the intake and integral intake.')
269 else:
270 namespaces = ['y2016', 'control_loops', 'superstructure']
271 intake = Intake("Intake")
272 loop_writer = control_loop.ControlLoopWriter('Intake', [intake],
273 namespaces=namespaces)
274 loop_writer.Write(argv[1], argv[2])
275
Austin Schuh07cb5852016-01-31 00:58:46 -0800276 integral_intake = IntegralIntake("IntegralIntake")
Comran Morshed2ae094e2016-01-23 20:43:20 +0000277 integral_loop_writer = control_loop.ControlLoopWriter("IntegralIntake", [integral_intake],
Austin Schuh07cb5852016-01-31 00:58:46 -0800278 namespaces=namespaces)
Comran Morshed2ae094e2016-01-23 20:43:20 +0000279 integral_loop_writer.Write(argv[3], argv[4])
280
281if __name__ == '__main__':
282 sys.exit(main(sys.argv))