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