blob: 311cf176d08f2fa4a2a18e10a1e69c56a32426e8 [file] [log] [blame]
Comran Morshed2ae094e2016-01-23 20:43:20 +00001#!/usr/bin/python
2
Austin Schuh2fc10fa2016-02-08 00:44:34 -08003from aos.common.util.trapezoid_profile import TrapizoidProfile
Comran Morshed2ae094e2016-01-23 20:43:20 +00004from frc971.control_loops.python import control_loop
5from frc971.control_loops.python import controls
Comran Morshed2ae094e2016-01-23 20:43:20 +00006import 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 Intake(control_loop.ControlLoop):
Austin Schuh07cb5852016-01-31 00:58:46 -080021 def __init__(self, name="Intake"):
Comran Morshed2ae094e2016-01-23 20:43:20 +000022 super(Intake, self).__init__(name)
23 # TODO(constants): Update all of these & retune poles.
24 # Stall Torque in N m
Austin Schuh07cb5852016-01-31 00:58:46 -080025 self.stall_torque = 0.71
Comran Morshed2ae094e2016-01-23 20:43:20 +000026 # Stall Current in Amps
Austin Schuh07cb5852016-01-31 00:58:46 -080027 self.stall_current = 134
Comran Morshed2ae094e2016-01-23 20:43:20 +000028 # Free Speed in RPM
Austin Schuh07cb5852016-01-31 00:58:46 -080029 self.free_speed = 18730
Comran Morshed2ae094e2016-01-23 20:43:20 +000030 # Free Current in Amps
Austin Schuh07cb5852016-01-31 00:58:46 -080031 self.free_current = 0.7
Comran Morshed2ae094e2016-01-23 20:43:20 +000032
33 # Resistance of the motor
34 self.R = 12.0 / self.stall_current
35 # Motor velocity constant
36 self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
37 (12.0 - self.R * self.free_current))
38 # Torque constant
39 self.Kt = self.stall_torque / self.stall_current
40 # Gear ratio
Austin Schuh07cb5852016-01-31 00:58:46 -080041 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 +000042
Austin Schuh07cb5852016-01-31 00:58:46 -080043 self.J = 0.9
Comran Morshed2ae094e2016-01-23 20:43:20 +000044
45 # Control loop time step
46 self.dt = 0.005
47
48 # State is [position, velocity]
49 # Input is [Voltage]
50
51 C1 = self.G * self.G * self.Kt / (self.R * self.J * self.Kv)
52 C2 = self.Kt * self.G / (self.J * self.R)
53
54 self.A_continuous = numpy.matrix(
55 [[0, 1],
56 [0, -C1]])
57
58 # Start with the unmodified input
59 self.B_continuous = numpy.matrix(
60 [[0],
61 [C2]])
62
63 self.C = numpy.matrix([[1, 0]])
64 self.D = numpy.matrix([[0]])
65
66 self.A, self.B = self.ContinuousToDiscrete(
67 self.A_continuous, self.B_continuous, self.dt)
68
69 controllability = controls.ctrb(self.A, self.B)
70
Austin Schuha88c4072016-02-06 14:31:03 -080071 glog.debug("Free speed is %f", self.free_speed * numpy.pi * 2.0 / 60.0 / self.G)
Comran Morshed2ae094e2016-01-23 20:43:20 +000072
Austin Schuh07cb5852016-01-31 00:58:46 -080073 q_pos = 0.20
74 q_vel = 5.5
Comran Morshed2ae094e2016-01-23 20:43:20 +000075 self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0],
76 [0.0, (1.0 / (q_vel ** 2.0))]])
77
78 self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0))]])
79 self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
80
Austin Schuh2fc10fa2016-02-08 00:44:34 -080081 q_pos_ff = 0.005
82 q_vel_ff = 1.0
83 self.Qff = numpy.matrix([[(1.0 / (q_pos_ff ** 2.0)), 0.0],
84 [0.0, (1.0 / (q_vel_ff ** 2.0))]])
85
86 self.Kff = controls.TwoStateFeedForwards(self.B, self.Qff)
87
Austin Schuha88c4072016-02-06 14:31:03 -080088 glog.debug('K %s', repr(self.K))
89 glog.debug('Poles are %s',
90 repr(numpy.linalg.eig(self.A - self.B * self.K)[0]))
Comran Morshed2ae094e2016-01-23 20:43:20 +000091
92 self.rpl = 0.30
93 self.ipl = 0.10
94 self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
95 self.rpl - 1j * self.ipl])
96
Austin Schuha88c4072016-02-06 14:31:03 -080097 glog.debug('L is %s', repr(self.L))
Comran Morshed2ae094e2016-01-23 20:43:20 +000098
99 q_pos = 0.05
100 q_vel = 2.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
Austin Schuha88c4072016-02-06 14:31:03 -0800110 glog.debug('Kal %s', repr(self.KalmanGain))
Comran Morshed2ae094e2016-01-23 20:43:20 +0000111 self.L = self.A * self.KalmanGain
Austin Schuha88c4072016-02-06 14:31:03 -0800112 glog.debug('KalL is %s', repr(self.L))
Comran Morshed2ae094e2016-01-23 20:43:20 +0000113
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 IntegralIntake(Intake):
Austin Schuh07cb5852016-01-31 00:58:46 -0800122 def __init__(self, name="IntegralIntake"):
123 super(IntegralIntake, self).__init__(name=name)
Comran Morshed2ae094e2016-01-23 20:43:20 +0000124
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(self.A_continuous, self.B_continuous, self.dt)
140
141 q_pos = 0.08
142 q_vel = 4.00
Austin Schuh07cb5852016-01-31 00:58:46 -0800143 q_voltage = 3.0
Comran Morshed2ae094e2016-01-23 20:43:20 +0000144 self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0, 0.0],
145 [0.0, (q_vel ** 2.0), 0.0],
146 [0.0, 0.0, (q_voltage ** 2.0)]])
147
148 r_pos = 0.05
149 self.R = numpy.matrix([[(r_pos ** 2.0)]])
150
151 self.KalmanGain, self.Q_steady = controls.kalman(
152 A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
153 self.L = self.A * self.KalmanGain
154
155 self.K_unaugmented = self.K
156 self.K = numpy.matrix(numpy.zeros((1, 3)))
157 self.K[0, 0:2] = self.K_unaugmented
158 self.K[0, 2] = 1
159
Austin Schuh2fc10fa2016-02-08 00:44:34 -0800160 self.Kff = numpy.concatenate((self.Kff, numpy.matrix(numpy.zeros((1, 1)))), axis=1)
161
Comran Morshed2ae094e2016-01-23 20:43:20 +0000162 self.InitializeState()
Austin Schuh07cb5852016-01-31 00:58:46 -0800163
Comran Morshed2ae094e2016-01-23 20:43:20 +0000164class ScenarioPlotter(object):
165 def __init__(self):
166 # Various lists for graphing things.
167 self.t = []
168 self.x = []
169 self.v = []
170 self.a = []
171 self.x_hat = []
172 self.u = []
Austin Schuh07cb5852016-01-31 00:58:46 -0800173 self.offset = []
Comran Morshed2ae094e2016-01-23 20:43:20 +0000174
Austin Schuh2fc10fa2016-02-08 00:44:34 -0800175 def run_test(self, intake, end_goal,
176 controller_intake,
177 observer_intake=None,
178 iterations=200):
Comran Morshed2ae094e2016-01-23 20:43:20 +0000179 """Runs the intake plant with an initial condition and goal.
180
Comran Morshed2ae094e2016-01-23 20:43:20 +0000181 Args:
182 intake: intake object to use.
Austin Schuh2fc10fa2016-02-08 00:44:34 -0800183 end_goal: end_goal state.
Comran Morshed2ae094e2016-01-23 20:43:20 +0000184 controller_intake: Intake object to get K from, or None if we should
185 use intake.
186 observer_intake: Intake object to use for the observer, or None if we should
187 use the actual state.
Austin Schuh2fc10fa2016-02-08 00:44:34 -0800188 iterations: Number of timesteps to run the model for.
Comran Morshed2ae094e2016-01-23 20:43:20 +0000189 """
190
191 if controller_intake is None:
192 controller_intake = intake
193
194 vbat = 12.0
195
196 if self.t:
197 initial_t = self.t[-1] + intake.dt
198 else:
199 initial_t = 0
200
Austin Schuh2fc10fa2016-02-08 00:44:34 -0800201 goal = numpy.concatenate((intake.X, numpy.matrix(numpy.zeros((1, 1)))), axis=0)
202
203 profile = TrapizoidProfile(intake.dt)
204 profile.set_maximum_acceleration(70.0)
205 profile.set_maximum_velocity(10.0)
206 profile.SetGoal(goal[0, 0])
207
208 U_last = numpy.matrix(numpy.zeros((1, 1)))
Comran Morshed2ae094e2016-01-23 20:43:20 +0000209 for i in xrange(iterations):
Austin Schuh2fc10fa2016-02-08 00:44:34 -0800210 observer_intake.Y = intake.Y
211 observer_intake.CorrectObserver(U_last)
Comran Morshed2ae094e2016-01-23 20:43:20 +0000212
Austin Schuh2fc10fa2016-02-08 00:44:34 -0800213 self.offset.append(observer_intake.X_hat[2, 0])
214 self.x_hat.append(observer_intake.X_hat[0, 0])
Comran Morshed2ae094e2016-01-23 20:43:20 +0000215
Austin Schuh2fc10fa2016-02-08 00:44:34 -0800216 next_goal = numpy.concatenate(
217 (profile.Update(end_goal[0, 0], end_goal[1, 0]),
218 numpy.matrix(numpy.zeros((1, 1)))),
219 axis=0)
220
221 ff_U = controller_intake.Kff * (next_goal - observer_intake.A * goal)
222
223 U_uncapped = controller_intake.K * (goal - observer_intake.X_hat) + ff_U
224 U = U_uncapped.copy()
Comran Morshed2ae094e2016-01-23 20:43:20 +0000225 U[0, 0] = numpy.clip(U[0, 0], -vbat, vbat)
226 self.x.append(intake.X[0, 0])
227
228 if self.v:
229 last_v = self.v[-1]
230 else:
231 last_v = 0
232
233 self.v.append(intake.X[1, 0])
234 self.a.append((self.v[-1] - last_v) / intake.dt)
235
Austin Schuh2fc10fa2016-02-08 00:44:34 -0800236 intake.Update(U + 0.0)
Comran Morshed2ae094e2016-01-23 20:43:20 +0000237
Austin Schuh2fc10fa2016-02-08 00:44:34 -0800238 observer_intake.PredictObserver(U)
Comran Morshed2ae094e2016-01-23 20:43:20 +0000239
240 self.t.append(initial_t + i * intake.dt)
241 self.u.append(U[0, 0])
242
Austin Schuh2fc10fa2016-02-08 00:44:34 -0800243 ff_U -= U_uncapped - U
244 goal = controller_intake.A * goal + controller_intake.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_intake.X_hat - end_goal))
Comran Morshed2ae094e2016-01-23 20:43:20 +0000253
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')
Austin Schuh07cb5852016-01-31 00:58:46 -0800262 pylab.plot(self.t, self.offset, label='voltage_offset')
263 pylab.legend()
Comran Morshed2ae094e2016-01-23 20:43:20 +0000264
265 pylab.subplot(3, 1, 3)
266 pylab.plot(self.t, self.a, label='a')
Comran Morshed2ae094e2016-01-23 20:43:20 +0000267 pylab.legend()
Austin Schuh07cb5852016-01-31 00:58:46 -0800268
Comran Morshed2ae094e2016-01-23 20:43:20 +0000269 pylab.show()
270
271
272def main(argv):
273 argv = FLAGS(argv)
Austin Schuha88c4072016-02-06 14:31:03 -0800274 glog.init()
Comran Morshed2ae094e2016-01-23 20:43:20 +0000275
Comran Morshed2ae094e2016-01-23 20:43:20 +0000276 scenario_plotter = ScenarioPlotter()
277
Austin Schuh07cb5852016-01-31 00:58:46 -0800278 intake = Intake()
279 intake_controller = IntegralIntake()
280 observer_intake = IntegralIntake()
Comran Morshed2ae094e2016-01-23 20:43:20 +0000281
282 # Test moving the intake with constant separation.
283 initial_X = numpy.matrix([[0.0], [0.0]])
Austin Schuh07cb5852016-01-31 00:58:46 -0800284 R = numpy.matrix([[numpy.pi/2.0], [0.0], [0.0]])
Austin Schuh2fc10fa2016-02-08 00:44:34 -0800285 scenario_plotter.run_test(intake, end_goal=R,
286 controller_intake=intake_controller,
Comran Morshed2ae094e2016-01-23 20:43:20 +0000287 observer_intake=observer_intake, 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 intake and integral intake.')
295 else:
296 namespaces = ['y2016', 'control_loops', 'superstructure']
297 intake = Intake("Intake")
298 loop_writer = control_loop.ControlLoopWriter('Intake', [intake],
299 namespaces=namespaces)
300 loop_writer.Write(argv[1], argv[2])
301
Austin Schuh07cb5852016-01-31 00:58:46 -0800302 integral_intake = IntegralIntake("IntegralIntake")
Comran Morshed2ae094e2016-01-23 20:43:20 +0000303 integral_loop_writer = control_loop.ControlLoopWriter("IntegralIntake", [integral_intake],
Austin Schuh07cb5852016-01-31 00:58:46 -0800304 namespaces=namespaces)
Comran Morshed2ae094e2016-01-23 20:43:20 +0000305 integral_loop_writer.Write(argv[3], argv[4])
306
307if __name__ == '__main__':
308 sys.exit(main(sys.argv))