blob: 454be9e5c3e16a902acfa76dd244bbd4d9771c91 [file] [log] [blame]
Austin Schuh48d60c12017-02-04 21:58:58 -08001#!/usr/bin/python
2
3from aos.common.util.trapezoid_profile import TrapezoidProfile
4from frc971.control_loops.python import control_loop
5from frc971.control_loops.python import controls
6import numpy
7import sys
8import matplotlib
9from matplotlib import pylab
10import gflags
11import glog
12
13FLAGS = gflags.FLAGS
14
15try:
16 gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
17except gflags.DuplicateFlagError:
18 pass
19
20class Turret(control_loop.ControlLoop):
21 def __init__(self, name='Turret'):
22 super(Turret, self).__init__(name)
23 # Stall Torque in N m
24 self.stall_torque = 0.43
25 # Stall Current in Amps
26 self.stall_current = 53
27 # Free Speed in RPM
28 self.free_speed = 13180
29 # Free Current in Amps
30 self.free_current = 1.8
31
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
40 self.G = (1.0 / 7.0) * (1.0 / 5.0) * (16.0 / 92.0)
41
42 # Motor inertia in kg * m^2
43 self.motor_inertia = 0.000006
44
45 # Moment of inertia, measured in CAD.
46 # Extra mass to compensate for friction is added on.
47 self.J = 0.05 + self.motor_inertia * ((1.0 / self.G) ** 2.0)
48
49 # Control loop time step
50 self.dt = 0.005
51
52 # State is [position, velocity]
53 # Input is [Voltage]
54
55 C1 = self.Kt / (self.R * self.J * self.Kv * self.G * self.G)
56 C2 = self.Kt / (self.J * self.R * self.G)
57
58 self.A_continuous = numpy.matrix(
59 [[0, 1],
60 [0, -C1]])
61
62 # Start with the unmodified input
63 self.B_continuous = numpy.matrix(
64 [[0],
65 [C2]])
66
67 self.C = numpy.matrix([[1, 0]])
68 self.D = numpy.matrix([[0]])
69
70 self.A, self.B = self.ContinuousToDiscrete(
71 self.A_continuous, self.B_continuous, self.dt)
72
73 controllability = controls.ctrb(self.A, self.B)
74
75 glog.debug('Free speed is %f',
76 -self.B_continuous[1, 0] / self.A_continuous[1, 1] * 12.0)
77
78 # Calculate the LQR controller gain
79 q_pos = 0.20
80 q_vel = 5.0
81 self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0],
82 [0.0, (1.0 / (q_vel ** 2.0))]])
83
84 self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0))]])
85 self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
86
87 # Calculate the feed forwards gain.
88 q_pos_ff = 0.005
89 q_vel_ff = 1.0
90 self.Qff = numpy.matrix([[(1.0 / (q_pos_ff ** 2.0)), 0.0],
91 [0.0, (1.0 / (q_vel_ff ** 2.0))]])
92
93 self.Kff = controls.TwoStateFeedForwards(self.B, self.Qff)
94
95 glog.debug('K %s', repr(self.K))
96 glog.debug('Poles are %s',
97 repr(numpy.linalg.eig(self.A - self.B * self.K)[0]))
98
99 q_pos = 0.10
100 q_vel = 1.65
101 self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0],
102 [0.0, (q_vel ** 2.0)]])
103
104 r_volts = 0.025
105 self.R = numpy.matrix([[(r_volts ** 2.0)]])
106
107 self.KalmanGain, self.Q_steady = controls.kalman(
108 A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
109
110 glog.debug('Kal %s', repr(self.KalmanGain))
111 self.L = self.A * self.KalmanGain
112 glog.debug('KalL is %s', repr(self.L))
113
114 # The box formed by U_min and U_max must encompass all possible values,
115 # or else Austin's code gets angry.
116 self.U_max = numpy.matrix([[12.0]])
117 self.U_min = numpy.matrix([[-12.0]])
118
119 self.InitializeState()
120
121class IntegralTurret(Turret):
122 def __init__(self, name='IntegralTurret'):
123 super(IntegralTurret, self).__init__(name=name)
124
125 self.A_continuous_unaugmented = self.A_continuous
126 self.B_continuous_unaugmented = self.B_continuous
127
128 self.A_continuous = numpy.matrix(numpy.zeros((3, 3)))
129 self.A_continuous[0:2, 0:2] = self.A_continuous_unaugmented
130 self.A_continuous[0:2, 2] = self.B_continuous_unaugmented
131
132 self.B_continuous = numpy.matrix(numpy.zeros((3, 1)))
133 self.B_continuous[0:2, 0] = self.B_continuous_unaugmented
134
135 self.C_unaugmented = self.C
136 self.C = numpy.matrix(numpy.zeros((1, 3)))
137 self.C[0:1, 0:2] = self.C_unaugmented
138
139 self.A, self.B = self.ContinuousToDiscrete(
140 self.A_continuous, self.B_continuous, self.dt)
141
142 q_pos = 0.12
143 q_vel = 2.00
144 q_voltage = 3.0
145 self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0, 0.0],
146 [0.0, (q_vel ** 2.0), 0.0],
147 [0.0, 0.0, (q_voltage ** 2.0)]])
148
149 r_pos = 0.05
150 self.R = numpy.matrix([[(r_pos ** 2.0)]])
151
152 self.KalmanGain, self.Q_steady = controls.kalman(
153 A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
154 self.L = self.A * self.KalmanGain
155
156 self.K_unaugmented = self.K
157 self.K = numpy.matrix(numpy.zeros((1, 3)))
158 self.K[0, 0:2] = self.K_unaugmented
159 self.K[0, 2] = 1
160
161 self.Kff = numpy.concatenate((self.Kff, numpy.matrix(numpy.zeros((1, 1)))), axis=1)
162
163 self.InitializeState()
164
165class ScenarioPlotter(object):
166 def __init__(self):
167 # Various lists for graphing things.
168 self.t = []
169 self.x = []
170 self.v = []
171 self.a = []
172 self.x_hat = []
173 self.u = []
174 self.offset = []
175
176 def run_test(self, turret, end_goal,
177 controller_turret,
178 observer_turret=None,
179 iterations=200):
180 """Runs the turret plant with an initial condition and goal.
181
182 Args:
183 turret: turret object to use.
184 end_goal: end_goal state.
185 controller_turret: Turret object to get K from, or None if we should
186 use turret.
187 observer_turret: Turret object to use for the observer, or None if we should
188 use the actual state.
189 iterations: Number of timesteps to run the model for.
190 """
191
192 if controller_turret is None:
193 controller_turret = turret
194
195 vbat = 12.0
196
197 if self.t:
198 initial_t = self.t[-1] + turret.dt
199 else:
200 initial_t = 0
201
202 goal = numpy.concatenate((turret.X, numpy.matrix(numpy.zeros((1, 1)))), axis=0)
203
204 profile = TrapezoidProfile(turret.dt)
205 profile.set_maximum_acceleration(100.0)
206 profile.set_maximum_velocity(7.0)
207 profile.SetGoal(goal[0, 0])
208
209 U_last = numpy.matrix(numpy.zeros((1, 1)))
210 for i in xrange(iterations):
211 observer_turret.Y = turret.Y
212 observer_turret.CorrectObserver(U_last)
213
214 self.offset.append(observer_turret.X_hat[2, 0])
215 self.x_hat.append(observer_turret.X_hat[0, 0])
216
217 next_goal = numpy.concatenate(
218 (profile.Update(end_goal[0, 0], end_goal[1, 0]),
219 numpy.matrix(numpy.zeros((1, 1)))),
220 axis=0)
221
222 ff_U = controller_turret.Kff * (next_goal - observer_turret.A * goal)
223
224 U_uncapped = controller_turret.K * (goal - observer_turret.X_hat) + ff_U
225 U_uncapped = controller_turret.K * (end_goal - observer_turret.X_hat)
226 U = U_uncapped.copy()
227 U[0, 0] = numpy.clip(U[0, 0], -vbat, vbat)
228 self.x.append(turret.X[0, 0])
229
230 if self.v:
231 last_v = self.v[-1]
232 else:
233 last_v = 0
234
235 self.v.append(turret.X[1, 0])
236 self.a.append((self.v[-1] - last_v) / turret.dt)
237
238 offset = 0.0
239 if i > 100:
240 offset = 2.0
241 turret.Update(U + offset)
242
243 observer_turret.PredictObserver(U)
244
245 self.t.append(initial_t + i * turret.dt)
246 self.u.append(U[0, 0])
247
248 ff_U -= U_uncapped - U
249 goal = controller_turret.A * goal + controller_turret.B * ff_U
250
251 if U[0, 0] != U_uncapped[0, 0]:
252 profile.MoveCurrentState(
253 numpy.matrix([[goal[0, 0]], [goal[1, 0]]]))
254
255 glog.debug('Time: %f', self.t[-1])
256 glog.debug('goal_error %s', repr(end_goal - goal))
257 glog.debug('error %s', repr(observer_turret.X_hat - end_goal))
258
259 def Plot(self):
260 pylab.subplot(3, 1, 1)
261 pylab.plot(self.t, self.x, label='x')
262 pylab.plot(self.t, self.x_hat, label='x_hat')
263 pylab.legend()
264
265 pylab.subplot(3, 1, 2)
266 pylab.plot(self.t, self.u, label='u')
267 pylab.plot(self.t, self.offset, label='voltage_offset')
268 pylab.legend()
269
270 pylab.subplot(3, 1, 3)
271 pylab.plot(self.t, self.a, label='a')
272 pylab.legend()
273
274 pylab.show()
275
276
277def main(argv):
278 argv = FLAGS(argv)
279 glog.init()
280
281 scenario_plotter = ScenarioPlotter()
282
283 turret = Turret()
284 turret_controller = IntegralTurret()
285 observer_turret = IntegralTurret()
286
287 # Test moving the turret with constant separation.
288 initial_X = numpy.matrix([[0.0], [0.0]])
289 R = numpy.matrix([[numpy.pi/2.0], [0.0], [0.0]])
290 scenario_plotter.run_test(turret, end_goal=R,
291 controller_turret=turret_controller,
292 observer_turret=observer_turret, iterations=200)
293
294 if FLAGS.plot:
295 scenario_plotter.Plot()
296
297 # Write the generated constants out to a file.
298 if len(argv) != 5:
299 glog.fatal('Expected .h file name and .cc file name for the turret and integral turret.')
300 else:
301 namespaces = ['y2017', 'control_loops', 'superstructure', 'turret']
302 turret = Turret('Turret')
303 loop_writer = control_loop.ControlLoopWriter('Turret', [turret],
304 namespaces=namespaces)
305 loop_writer.Write(argv[1], argv[2])
306
307 integral_turret = IntegralTurret('IntegralTurret')
308 integral_loop_writer = control_loop.ControlLoopWriter(
309 'IntegralTurret', [integral_turret],
310 namespaces=namespaces)
311 integral_loop_writer.Write(argv[3], argv[4])
312
313if __name__ == '__main__':
314 sys.exit(main(sys.argv))