blob: d2a389ef2fa89337db70b5a81cc99af31aeb8f1f [file] [log] [blame]
Diana Vandenberg223703d2017-01-28 17:39:53 -08001#!/usr/bin/python
2
3from frc971.control_loops.python import control_loop
4from frc971.control_loops.python import controls
5import numpy
6import sys
7from matplotlib import pylab
8
9import gflags
10import glog
11
12FLAGS = gflags.FLAGS
13
14gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
15
16
17class Drivetrain(control_loop.ControlLoop):
18 def __init__(self, name="Drivetrain", left_low=True, right_low=True):
19 super(Drivetrain, self).__init__(name)
20 # Number of motors per side
21 self.num_motors = 2
22 # Stall Torque in N m
23 self.stall_torque = 2.42 * self.num_motors * 0.60
24 # Stall Current in Amps
25 self.stall_current = 133.0 * self.num_motors
Brian Silverman052e69d2017-02-12 16:19:55 -080026 self.free_speed_rpm = 5500.0
27 # Free Speed in rotations/second.
28 self.free_speed = self.free_speed_rpm / 60
Diana Vandenberg223703d2017-01-28 17:39:53 -080029 # Free Current in Amps
30 self.free_current = 4.7 * self.num_motors
31 # Moment of inertia of the drivetrain in kg m^2
Austin Schuhfbceb1c2017-03-11 22:10:57 -080032 self.J = 6.0
Diana Vandenberg223703d2017-01-28 17:39:53 -080033 # Mass of the robot, in kg.
Austin Schuhfbceb1c2017-03-11 22:10:57 -080034 self.m = 52
Diana Vandenberg223703d2017-01-28 17:39:53 -080035 # Radius of the robot, in meters (requires tuning by hand)
Austin Schuh48d60c12017-02-04 21:58:58 -080036 self.rb = 0.59055 / 2.0
Diana Vandenberg223703d2017-01-28 17:39:53 -080037 # Radius of the wheels, in meters.
Austin Schuh48d60c12017-02-04 21:58:58 -080038 self.r = 0.08255 / 2.0
Diana Vandenberg223703d2017-01-28 17:39:53 -080039 # Resistance of the motor, divided by the number of motors.
40 self.resistance = 12.0 / self.stall_current
41 # Motor velocity constant
Brian Silverman052e69d2017-02-12 16:19:55 -080042 self.Kv = ((self.free_speed * 2.0 * numpy.pi) /
Diana Vandenberg223703d2017-01-28 17:39:53 -080043 (12.0 - self.resistance * self.free_current))
44 # Torque constant
45 self.Kt = self.stall_torque / self.stall_current
46 # Gear ratios
47 self.G_low = 12.0 / 54.0
48 self.G_high = 12.0 / 54.0
49 if left_low:
50 self.Gl = self.G_low
51 else:
52 self.Gl = self.G_high
53 if right_low:
54 self.Gr = self.G_low
55 else:
56 self.Gr = self.G_high
57
58 # Control loop time step
59 self.dt = 0.005
60
61 # These describe the way that a given side of a robot will be influenced
62 # by the other side. Units of 1 / kg.
63 self.msp = 1.0 / self.m + self.rb * self.rb / self.J
64 self.msn = 1.0 / self.m - self.rb * self.rb / self.J
65 # The calculations which we will need for A and B.
66 self.tcl = -self.Kt / self.Kv / (self.Gl * self.Gl * self.resistance * self.r * self.r)
67 self.tcr = -self.Kt / self.Kv / (self.Gr * self.Gr * self.resistance * self.r * self.r)
68 self.mpl = self.Kt / (self.Gl * self.resistance * self.r)
69 self.mpr = self.Kt / (self.Gr * self.resistance * self.r)
70
71 # State feedback matrices
72 # X will be of the format
73 # [[positionl], [velocityl], [positionr], velocityr]]
74 self.A_continuous = numpy.matrix(
75 [[0, 1, 0, 0],
76 [0, self.msp * self.tcl, 0, self.msn * self.tcr],
77 [0, 0, 0, 1],
78 [0, self.msn * self.tcl, 0, self.msp * self.tcr]])
79 self.B_continuous = numpy.matrix(
80 [[0, 0],
81 [self.msp * self.mpl, self.msn * self.mpr],
82 [0, 0],
83 [self.msn * self.mpl, self.msp * self.mpr]])
84 self.C = numpy.matrix([[1, 0, 0, 0],
85 [0, 0, 1, 0]])
86 self.D = numpy.matrix([[0, 0],
87 [0, 0]])
88
89 self.A, self.B = self.ContinuousToDiscrete(
90 self.A_continuous, self.B_continuous, self.dt)
91
92 if left_low or right_low:
93 q_pos = 0.12
94 q_vel = 1.0
95 else:
96 q_pos = 0.14
97 q_vel = 0.95
98
99 # Tune the LQR controller
100 self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0, 0.0, 0.0],
101 [0.0, (1.0 / (q_vel ** 2.0)), 0.0, 0.0],
102 [0.0, 0.0, (1.0 / (q_pos ** 2.0)), 0.0],
103 [0.0, 0.0, 0.0, (1.0 / (q_vel ** 2.0))]])
104
105 self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0)), 0.0],
106 [0.0, (1.0 / (12.0 ** 2.0))]])
107 self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
108
109 glog.debug('DT q_pos %f q_vel %s %s', q_pos, q_vel, name)
110 glog.debug(str(numpy.linalg.eig(self.A - self.B * self.K)[0]))
111 glog.debug('K %s', repr(self.K))
112
113 self.hlp = 0.3
114 self.llp = 0.4
115 self.PlaceObserverPoles([self.hlp, self.hlp, self.llp, self.llp])
116
117 self.U_max = numpy.matrix([[12.0], [12.0]])
118 self.U_min = numpy.matrix([[-12.0], [-12.0]])
119
120 self.InitializeState()
121
122
123class KFDrivetrain(Drivetrain):
124 def __init__(self, name="KFDrivetrain", left_low=True, right_low=True):
125 super(KFDrivetrain, self).__init__(name, left_low, right_low)
126
127 self.unaugmented_A_continuous = self.A_continuous
128 self.unaugmented_B_continuous = self.B_continuous
129
130 # The practical voltage applied to the wheels is
131 # V_left = U_left + left_voltage_error
132 #
133 # The states are
134 # [left position, left velocity, right position, right velocity,
135 # left voltage error, right voltage error, angular_error]
136 #
137 # The left and right positions are filtered encoder positions and are not
138 # adjusted for heading error.
139 # The turn velocity as computed by the left and right velocities is
140 # adjusted by the gyro velocity.
141 # The angular_error is the angular velocity error between the wheel speed
142 # and the gyro speed.
143 self.A_continuous = numpy.matrix(numpy.zeros((7, 7)))
144 self.B_continuous = numpy.matrix(numpy.zeros((7, 2)))
145 self.A_continuous[0:4,0:4] = self.unaugmented_A_continuous
146 self.A_continuous[0:4,4:6] = self.unaugmented_B_continuous
147 self.B_continuous[0:4,0:2] = self.unaugmented_B_continuous
148 self.A_continuous[0,6] = 1
149 self.A_continuous[2,6] = -1
150
151 self.A, self.B = self.ContinuousToDiscrete(
152 self.A_continuous, self.B_continuous, self.dt)
153
154 self.C = numpy.matrix([[1, 0, 0, 0, 0, 0, 0],
155 [0, 0, 1, 0, 0, 0, 0],
156 [0, -0.5 / self.rb, 0, 0.5 / self.rb, 0, 0, 0]])
157
158 self.D = numpy.matrix([[0, 0],
159 [0, 0],
160 [0, 0]])
161
162 q_pos = 0.05
163 q_vel = 1.00
164 q_voltage = 10.0
165 q_encoder_uncertainty = 2.00
166
167 self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
168 [0.0, (q_vel ** 2.0), 0.0, 0.0, 0.0, 0.0, 0.0],
169 [0.0, 0.0, (q_pos ** 2.0), 0.0, 0.0, 0.0, 0.0],
170 [0.0, 0.0, 0.0, (q_vel ** 2.0), 0.0, 0.0, 0.0],
171 [0.0, 0.0, 0.0, 0.0, (q_voltage ** 2.0), 0.0, 0.0],
172 [0.0, 0.0, 0.0, 0.0, 0.0, (q_voltage ** 2.0), 0.0],
173 [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, (q_encoder_uncertainty ** 2.0)]])
174
175 r_pos = 0.0001
176 r_gyro = 0.000001
177 self.R = numpy.matrix([[(r_pos ** 2.0), 0.0, 0.0],
178 [0.0, (r_pos ** 2.0), 0.0],
179 [0.0, 0.0, (r_gyro ** 2.0)]])
180
181 # Solving for kf gains.
182 self.KalmanGain, self.Q_steady = controls.kalman(
183 A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
184
185 self.L = self.A * self.KalmanGain
186
187 unaug_K = self.K
188
189 # Implement a nice closed loop controller for use by the closed loop
190 # controller.
191 self.K = numpy.matrix(numpy.zeros((self.B.shape[1], self.A.shape[0])))
192 self.K[0:2, 0:4] = unaug_K
193 self.K[0, 4] = 1.0
194 self.K[1, 5] = 1.0
195
196 self.Qff = numpy.matrix(numpy.zeros((4, 4)))
197 qff_pos = 0.005
198 qff_vel = 1.00
199 self.Qff[0, 0] = 1.0 / qff_pos ** 2.0
200 self.Qff[1, 1] = 1.0 / qff_vel ** 2.0
201 self.Qff[2, 2] = 1.0 / qff_pos ** 2.0
202 self.Qff[3, 3] = 1.0 / qff_vel ** 2.0
203 self.Kff = numpy.matrix(numpy.zeros((2, 7)))
204 self.Kff[0:2, 0:4] = controls.TwoStateFeedForwards(self.B[0:4,:], self.Qff)
205
206 self.InitializeState()
207
208
209def main(argv):
210 argv = FLAGS(argv)
211 glog.init()
212
213 # Simulate the response of the system to a step input.
214 drivetrain = Drivetrain(left_low=False, right_low=False)
215 simulated_left = []
216 simulated_right = []
217 for _ in xrange(100):
218 drivetrain.Update(numpy.matrix([[12.0], [12.0]]))
219 simulated_left.append(drivetrain.X[0, 0])
220 simulated_right.append(drivetrain.X[2, 0])
221
222 if FLAGS.plot:
223 pylab.plot(range(100), simulated_left)
224 pylab.plot(range(100), simulated_right)
225 pylab.suptitle('Acceleration Test')
226 pylab.show()
227
228 # Simulate forwards motion.
229 drivetrain = Drivetrain(left_low=False, right_low=False)
230 close_loop_left = []
231 close_loop_right = []
232 left_power = []
233 right_power = []
234 R = numpy.matrix([[1.0], [0.0], [1.0], [0.0]])
235 for _ in xrange(300):
236 U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
237 drivetrain.U_min, drivetrain.U_max)
238 drivetrain.UpdateObserver(U)
239 drivetrain.Update(U)
240 close_loop_left.append(drivetrain.X[0, 0])
241 close_loop_right.append(drivetrain.X[2, 0])
242 left_power.append(U[0, 0])
243 right_power.append(U[1, 0])
244
245 if FLAGS.plot:
246 pylab.plot(range(300), close_loop_left, label='left position')
247 pylab.plot(range(300), close_loop_right, label='right position')
248 pylab.plot(range(300), left_power, label='left power')
249 pylab.plot(range(300), right_power, label='right power')
250 pylab.suptitle('Linear Move')
251 pylab.legend()
252 pylab.show()
253
254 # Try turning in place
255 drivetrain = Drivetrain()
256 close_loop_left = []
257 close_loop_right = []
258 R = numpy.matrix([[-1.0], [0.0], [1.0], [0.0]])
259 for _ in xrange(100):
260 U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
261 drivetrain.U_min, drivetrain.U_max)
262 drivetrain.UpdateObserver(U)
263 drivetrain.Update(U)
264 close_loop_left.append(drivetrain.X[0, 0])
265 close_loop_right.append(drivetrain.X[2, 0])
266
267 if FLAGS.plot:
268 pylab.plot(range(100), close_loop_left)
269 pylab.plot(range(100), close_loop_right)
270 pylab.suptitle('Angular Move')
271 pylab.show()
272
273 # Try turning just one side.
274 drivetrain = Drivetrain()
275 close_loop_left = []
276 close_loop_right = []
277 R = numpy.matrix([[0.0], [0.0], [1.0], [0.0]])
278 for _ in xrange(100):
279 U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
280 drivetrain.U_min, drivetrain.U_max)
281 drivetrain.UpdateObserver(U)
282 drivetrain.Update(U)
283 close_loop_left.append(drivetrain.X[0, 0])
284 close_loop_right.append(drivetrain.X[2, 0])
285
286 if FLAGS.plot:
287 pylab.plot(range(100), close_loop_left)
288 pylab.plot(range(100), close_loop_right)
289 pylab.suptitle('Pivot')
290 pylab.show()
291
292 # Write the generated constants out to a file.
293 drivetrain_low_low = Drivetrain(
294 name="DrivetrainLowLow", left_low=True, right_low=True)
295 drivetrain_low_high = Drivetrain(
296 name="DrivetrainLowHigh", left_low=True, right_low=False)
297 drivetrain_high_low = Drivetrain(
298 name="DrivetrainHighLow", left_low=False, right_low=True)
299 drivetrain_high_high = Drivetrain(
300 name="DrivetrainHighHigh", left_low=False, right_low=False)
301
302 kf_drivetrain_low_low = KFDrivetrain(
303 name="KFDrivetrainLowLow", left_low=True, right_low=True)
304 kf_drivetrain_low_high = KFDrivetrain(
305 name="KFDrivetrainLowHigh", left_low=True, right_low=False)
306 kf_drivetrain_high_low = KFDrivetrain(
307 name="KFDrivetrainHighLow", left_low=False, right_low=True)
308 kf_drivetrain_high_high = KFDrivetrain(
309 name="KFDrivetrainHighHigh", left_low=False, right_low=False)
310
311 if len(argv) != 5:
312 print "Expected .h file name and .cc file name"
313 else:
314 namespaces = ['y2017', 'control_loops', 'drivetrain']
315 dog_loop_writer = control_loop.ControlLoopWriter(
316 "Drivetrain", [drivetrain_low_low, drivetrain_low_high,
317 drivetrain_high_low, drivetrain_high_high],
318 namespaces = namespaces)
319 dog_loop_writer.AddConstant(control_loop.Constant("kDt", "%f",
320 drivetrain_low_low.dt))
321 dog_loop_writer.AddConstant(control_loop.Constant("kStallTorque", "%f",
322 drivetrain_low_low.stall_torque))
323 dog_loop_writer.AddConstant(control_loop.Constant("kStallCurrent", "%f",
324 drivetrain_low_low.stall_current))
Brian Silverman052e69d2017-02-12 16:19:55 -0800325 dog_loop_writer.AddConstant(control_loop.Constant("kFreeSpeed", "%f",
Diana Vandenberg223703d2017-01-28 17:39:53 -0800326 drivetrain_low_low.free_speed))
327 dog_loop_writer.AddConstant(control_loop.Constant("kFreeCurrent", "%f",
328 drivetrain_low_low.free_current))
329 dog_loop_writer.AddConstant(control_loop.Constant("kJ", "%f",
330 drivetrain_low_low.J))
331 dog_loop_writer.AddConstant(control_loop.Constant("kMass", "%f",
332 drivetrain_low_low.m))
333 dog_loop_writer.AddConstant(control_loop.Constant("kRobotRadius", "%f",
334 drivetrain_low_low.rb))
335 dog_loop_writer.AddConstant(control_loop.Constant("kWheelRadius", "%f",
336 drivetrain_low_low.r))
337 dog_loop_writer.AddConstant(control_loop.Constant("kR", "%f",
338 drivetrain_low_low.resistance))
339 dog_loop_writer.AddConstant(control_loop.Constant("kV", "%f",
340 drivetrain_low_low.Kv))
341 dog_loop_writer.AddConstant(control_loop.Constant("kT", "%f",
342 drivetrain_low_low.Kt))
343 dog_loop_writer.AddConstant(control_loop.Constant("kLowGearRatio", "%f",
344 drivetrain_low_low.G_low))
345 dog_loop_writer.AddConstant(control_loop.Constant("kHighGearRatio", "%f",
346 drivetrain_high_high.G_high))
Brian Silverman052e69d2017-02-12 16:19:55 -0800347 dog_loop_writer.AddConstant(control_loop.Constant("kHighOutputRatio", "%f",
348 drivetrain_high_high.G_high * drivetrain_high_high.r))
Diana Vandenberg223703d2017-01-28 17:39:53 -0800349
350 dog_loop_writer.Write(argv[1], argv[2])
351
352 kf_loop_writer = control_loop.ControlLoopWriter(
353 "KFDrivetrain", [kf_drivetrain_low_low, kf_drivetrain_low_high,
354 kf_drivetrain_high_low, kf_drivetrain_high_high],
355 namespaces = namespaces)
356 kf_loop_writer.Write(argv[3], argv[4])
357
358if __name__ == '__main__':
359 sys.exit(main(sys.argv))