blob: 2380549f6fa9f752a350508b2ec708666e814f08 [file] [log] [blame]
Campbell Crowley33e0e3d2017-12-27 17:55:40 -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
8import glog
9
10class DrivetrainParams(object):
Diana Burgessd0180f12018-03-21 21:24:17 -070011 def __init__(self,
12 J,
13 mass,
14 robot_radius,
15 wheel_radius,
16 G_high,
17 G_low,
18 q_pos_low,
19 q_pos_high,
20 q_vel_low,
21 q_vel_high,
22 efficiency=0.60,
23 has_imu=False,
24 force=False,
25 kf_q_voltage=10.0,
26 motor_type=control_loop.CIM(),
27 num_motors=2,
28 dt=0.00505,
29 controller_poles=[0.90, 0.90],
30 observer_poles=[0.02, 0.02]):
31 """Defines all constants of a drivetrain.
Campbell Crowley33e0e3d2017-12-27 17:55:40 -080032
Diana Burgessd0180f12018-03-21 21:24:17 -070033 Args:
34 J: float, Moment of inertia of drivetrain in kg m^2
35 mass: float, Mass of the robot in kg.
36 robot_radius: float, Radius of the robot, in meters (requires tuning by
37 hand).
38 wheel_radius: float, Radius of the wheels, in meters.
39 G_high: float, Gear ratio for high gear.
40 G_low: float, Gear ratio for low gear.
41 dt: float, Control loop time step.
42 q_pos_low: float, q position low gear.
43 q_pos_high: float, q position high gear.
44 q_vel_low: float, q velocity low gear.
45 q_vel_high: float, q velocity high gear.
46 efficiency: float, gear box effiency.
47 has_imu: bool, true if imu is present.
48 force: bool, true if force.
49 kf_q_voltage: float
50 motor_type: object, class of values defining the motor in drivetrain.
51 num_motors: int, number of motors on one side of drivetrain.
52 controller_poles: array, An array of poles. (See control_loop.py)
53 observer_poles: array, An array of poles. (See control_loop.py)
54 """
Campbell Crowley33e0e3d2017-12-27 17:55:40 -080055
Diana Burgessd0180f12018-03-21 21:24:17 -070056 self.J = J
57 self.mass = mass
58 self.robot_radius = robot_radius
59 self.wheel_radius = wheel_radius
60 self.G_high = G_high
61 self.G_low = G_low
62 self.dt = dt
63 self.q_pos_low = q_pos_low
64 self.q_pos_high = q_pos_high
65 self.q_vel_low = q_vel_low
66 self.q_vel_high = q_vel_high
67 self.efficiency = efficiency
68 self.has_imu = has_imu
69 self.kf_q_voltage = kf_q_voltage
70 self.motor_type = motor_type
71 self.force = force
72 self.num_motors = num_motors
73 self.controller_poles = controller_poles
74 self.observer_poles = observer_poles
75
Campbell Crowley33e0e3d2017-12-27 17:55:40 -080076
77class Drivetrain(control_loop.ControlLoop):
Diana Burgessd0180f12018-03-21 21:24:17 -070078 def __init__(self,
79 drivetrain_params,
80 name="Drivetrain",
81 left_low=True,
82 right_low=True):
83 """Defines a base drivetrain for a robot.
Campbell Crowley33e0e3d2017-12-27 17:55:40 -080084
Diana Burgessd0180f12018-03-21 21:24:17 -070085 Args:
86 drivetrain_params: DrivetrainParams, class of values defining the drivetrain.
87 name: string, Name of this drivetrain.
88 left_low: bool, Whether the left is in high gear.
89 right_low: bool, Whether the right is in high gear.
90 """
91 super(Drivetrain, self).__init__(name)
Campbell Crowley33e0e3d2017-12-27 17:55:40 -080092
Diana Burgessd0180f12018-03-21 21:24:17 -070093 # Moment of inertia of the drivetrain in kg m^2
94 self.J = drivetrain_params.J
95 # Mass of the robot, in kg.
96 self.mass = drivetrain_params.mass
97 # Radius of the robot, in meters (requires tuning by hand)
98 self.robot_radius = drivetrain_params.robot_radius
99 # Radius of the wheels, in meters.
100 self.r = drivetrain_params.wheel_radius
101 self.has_imu = drivetrain_params.has_imu
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800102
Diana Burgessd0180f12018-03-21 21:24:17 -0700103 # Gear ratios
104 self.G_low = drivetrain_params.G_low
105 self.G_high = drivetrain_params.G_high
106 if left_low:
107 self.Gl = self.G_low
108 else:
109 self.Gl = self.G_high
110 if right_low:
111 self.Gr = self.G_low
112 else:
113 self.Gr = self.G_high
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800114
Diana Burgessd0180f12018-03-21 21:24:17 -0700115 # Control loop time step
116 self.dt = drivetrain_params.dt
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800117
Diana Burgessd0180f12018-03-21 21:24:17 -0700118 self.efficiency = drivetrain_params.efficiency
119 self.force = drivetrain_params.force
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800120
Diana Burgessd0180f12018-03-21 21:24:17 -0700121 self.BuildDrivetrain(drivetrain_params.motor_type,
122 drivetrain_params.num_motors)
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800123
Diana Burgessd0180f12018-03-21 21:24:17 -0700124 if left_low or right_low:
125 q_pos = drivetrain_params.q_pos_low
126 q_vel = drivetrain_params.q_vel_low
127 else:
128 q_pos = drivetrain_params.q_pos_high
129 q_vel = drivetrain_params.q_vel_high
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800130
Diana Burgessd0180f12018-03-21 21:24:17 -0700131 self.BuildDrivetrainController(q_pos, q_vel)
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800132
Diana Burgessd0180f12018-03-21 21:24:17 -0700133 self.InitializeState()
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800134
Diana Burgessd0180f12018-03-21 21:24:17 -0700135 def BuildDrivetrain(self, motor, num_motors_per_side):
136 self.motor = motor
137 # Number of motors per side
138 self.num_motors = num_motors_per_side
139 # Stall Torque in N m
140 self.stall_torque = motor.stall_torque * self.num_motors * self.efficiency
141 # Stall Current in Amps
142 self.stall_current = motor.stall_current * self.num_motors
143 # Free Speed in rad/s
144 self.free_speed = motor.free_speed
145 # Free Current in Amps
146 self.free_current = motor.free_current * self.num_motors
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800147
Diana Burgessd0180f12018-03-21 21:24:17 -0700148 # Effective motor resistance in ohms.
149 self.resistance = 12.0 / self.stall_current
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800150
Diana Burgessd0180f12018-03-21 21:24:17 -0700151 # Resistance of the motor, divided by the number of motors.
152 # Motor velocity constant
153 self.Kv = (self.free_speed /
154 (12.0 - self.resistance * self.free_current))
155 # Torque constant
156 self.Kt = self.stall_torque / self.stall_current
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800157
Diana Burgessd0180f12018-03-21 21:24:17 -0700158 # These describe the way that a given side of a robot will be influenced
159 # by the other side. Units of 1 / kg.
160 self.msp = 1.0 / self.mass + self.robot_radius * self.robot_radius / self.J
161 self.msn = 1.0 / self.mass - self.robot_radius * self.robot_radius / self.J
162 # The calculations which we will need for A and B.
163 self.tcl = self.Kt / self.Kv / (
164 self.Gl * self.Gl * self.resistance * self.r * self.r)
165 self.tcr = self.Kt / self.Kv / (
166 self.Gr * self.Gr * self.resistance * self.r * self.r)
167 self.mpl = self.Kt / (self.Gl * self.resistance * self.r)
168 self.mpr = self.Kt / (self.Gr * self.resistance * self.r)
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800169
Diana Burgessd0180f12018-03-21 21:24:17 -0700170 # State feedback matrices
171 # X will be of the format
172 # [[positionl], [velocityl], [positionr], velocityr]]
173 self.A_continuous = numpy.matrix(
174 [[0, 1, 0, 0], [0, -self.msp * self.tcl, 0, -self.msn * self.tcr],
175 [0, 0, 0, 1], [0, -self.msn * self.tcl, 0, -self.msp * self.tcr]])
176 self.B_continuous = numpy.matrix(
177 [[0, 0], [self.msp * self.mpl, self.msn * self.mpr], [0, 0],
178 [self.msn * self.mpl, self.msp * self.mpr]])
179 self.C = numpy.matrix([[1, 0, 0, 0], [0, 0, 1, 0]])
180 self.D = numpy.matrix([[0, 0], [0, 0]])
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800181
Diana Burgessd0180f12018-03-21 21:24:17 -0700182 self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
183 self.B_continuous, self.dt)
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800184
Diana Burgessd0180f12018-03-21 21:24:17 -0700185 def BuildDrivetrainController(self, q_pos, q_vel):
186 # Tune the LQR controller
187 self.Q = numpy.matrix([[(1.0 / (q_pos**2.0)), 0.0, 0.0,
188 0.0], [0.0, (1.0 / (q_vel**2.0)), 0.0, 0.0],
189 [0.0, 0.0, (1.0 / (q_pos**2.0)),
190 0.0], [0.0, 0.0, 0.0, (1.0 / (q_vel**2.0))]])
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800191
Diana Burgessd0180f12018-03-21 21:24:17 -0700192 self.R = numpy.matrix([[(1.0 / (12.0**2.0)), 0.0],
193 [0.0, (1.0 / (12.0**2.0))]])
194 self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800195
Diana Burgessd0180f12018-03-21 21:24:17 -0700196 glog.debug('DT q_pos %f q_vel %s %s', q_pos, q_vel, self._name)
197 glog.debug(str(numpy.linalg.eig(self.A - self.B * self.K)[0]))
198 glog.debug('K %s', repr(self.K))
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800199
Diana Burgessd0180f12018-03-21 21:24:17 -0700200 self.hlp = 0.3
201 self.llp = 0.4
202 self.PlaceObserverPoles([self.hlp, self.hlp, self.llp, self.llp])
203
204 self.U_max = numpy.matrix([[12.0], [12.0]])
205 self.U_min = numpy.matrix([[-12.0], [-12.0]])
206
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800207
208class KFDrivetrain(Drivetrain):
Diana Burgessd0180f12018-03-21 21:24:17 -0700209 def __init__(self,
210 drivetrain_params,
211 name="KFDrivetrain",
212 left_low=True,
213 right_low=True):
214 """Kalman filter values of a drivetrain.
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800215
Diana Burgessd0180f12018-03-21 21:24:17 -0700216 Args:
217 drivetrain_params: DrivetrainParams, class of values defining the drivetrain.
218 name: string, Name of this drivetrain.
219 left_low: bool, Whether the left is in high gear.
220 right_low: bool, Whether the right is in high gear.
221 """
222 super(KFDrivetrain, self).__init__(drivetrain_params, name, left_low,
223 right_low)
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800224
Diana Burgessd0180f12018-03-21 21:24:17 -0700225 self.unaugmented_A_continuous = self.A_continuous
226 self.unaugmented_B_continuous = self.B_continuous
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800227
Diana Burgessd0180f12018-03-21 21:24:17 -0700228 # The practical voltage applied to the wheels is
229 # V_left = U_left + left_voltage_error
230 #
231 # The states are
232 # [left position, left velocity, right position, right velocity,
233 # left voltage error, right voltage error, angular_error]
234 #
235 # The left and right positions are filtered encoder positions and are not
236 # adjusted for heading error.
237 # The turn velocity as computed by the left and right velocities is
238 # adjusted by the gyro velocity.
239 # The angular_error is the angular velocity error between the wheel speed
240 # and the gyro speed.
241 self.A_continuous = numpy.matrix(numpy.zeros((7, 7)))
242 self.B_continuous = numpy.matrix(numpy.zeros((7, 2)))
243 self.A_continuous[0:4, 0:4] = self.unaugmented_A_continuous
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800244
Diana Burgessd0180f12018-03-21 21:24:17 -0700245 if self.force:
246 self.A_continuous[0:4, 4:6] = numpy.matrix(
247 [[0.0, 0.0], [self.msp, self.msn], [0.0, 0.0],
248 [self.msn, self.msp]])
249 q_voltage = drivetrain_params.kf_q_voltage * self.mpl
250 else:
251 self.A_continuous[0:4, 4:6] = self.unaugmented_B_continuous
252 q_voltage = drivetrain_params.kf_q_voltage
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800253
Diana Burgessd0180f12018-03-21 21:24:17 -0700254 self.B_continuous[0:4, 0:2] = self.unaugmented_B_continuous
255 self.A_continuous[0, 6] = 1
256 self.A_continuous[2, 6] = -1
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800257
Diana Burgessd0180f12018-03-21 21:24:17 -0700258 self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
259 self.B_continuous, self.dt)
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800260
Diana Burgessd0180f12018-03-21 21:24:17 -0700261 if self.has_imu:
262 self.C = numpy.matrix(
263 [[1, 0, 0, 0, 0, 0, 0], [0, 0, 1, 0, 0, 0, 0], [
264 0, -0.5 / drivetrain_params.robot_radius, 0,
265 0.5 / drivetrain_params.robot_radius, 0, 0, 0
266 ], [0, 0, 0, 0, 0, 0, 0]])
267 gravity = 9.8
268 self.C[3, 0:6] = 0.5 * (
269 self.A_continuous[1, 0:6] + self.A_continuous[3, 0:6]
270 ) / gravity
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800271
Diana Burgessd0180f12018-03-21 21:24:17 -0700272 self.D = numpy.matrix([[0, 0], [0, 0], [0, 0], [
273 0.5 *
274 (self.B_continuous[1, 0] + self.B_continuous[3, 0]) / gravity,
275 0.5 *
276 (self.B_continuous[1, 1] + self.B_continuous[3, 1]) / gravity
277 ]])
278 else:
279 self.C = numpy.matrix(
280 [[1, 0, 0, 0, 0, 0, 0], [0, 0, 1, 0, 0, 0, 0], [
281 0, -0.5 / drivetrain_params.robot_radius, 0,
282 0.5 / drivetrain_params.robot_radius, 0, 0, 0
283 ]])
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800284
Diana Burgessd0180f12018-03-21 21:24:17 -0700285 self.D = numpy.matrix([[0, 0], [0, 0], [0, 0]])
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800286
Diana Burgessd0180f12018-03-21 21:24:17 -0700287 q_pos = 0.05
288 q_vel = 1.00
289 q_encoder_uncertainty = 2.00
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800290
Diana Burgessd0180f12018-03-21 21:24:17 -0700291 self.Q = numpy.matrix(
292 [[(q_pos**2.0), 0.0, 0.0, 0.0, 0.0, 0.0,
293 0.0], [0.0, (q_vel**2.0), 0.0, 0.0, 0.0, 0.0,
294 0.0], [0.0, 0.0, (q_pos**2.0), 0.0, 0.0, 0.0,
295 0.0], [0.0, 0.0, 0.0, (q_vel**2.0), 0.0, 0.0, 0.0],
296 [0.0, 0.0, 0.0, 0.0, (q_voltage**2.0), 0.0,
297 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, (q_voltage**2.0), 0.0],
298 [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, (q_encoder_uncertainty**2.0)]])
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800299
Diana Burgessd0180f12018-03-21 21:24:17 -0700300 r_pos = 0.0001
301 r_gyro = 0.000001
302 if self.has_imu:
303 r_accelerometer = 7.0
304 self.R = numpy.matrix([[(r_pos**2.0), 0.0, 0.0, 0.0],
305 [0.0, (r_pos**2.0), 0.0, 0.0],
306 [0.0, 0.0, (r_gyro**2.0), 0.0],
307 [0.0, 0.0, 0.0, (r_accelerometer**2.0)]])
308 else:
309 self.R = numpy.matrix([[(r_pos**2.0), 0.0, 0.0],
310 [0.0, (r_pos**2.0), 0.0],
311 [0.0, 0.0, (r_gyro**2.0)]])
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800312
Diana Burgessd0180f12018-03-21 21:24:17 -0700313 # Solving for kf gains.
314 self.KalmanGain, self.Q_steady = controls.kalman(
315 A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800316
Diana Burgessd0180f12018-03-21 21:24:17 -0700317 if not self.has_imu:
318 self.KalmanGain = numpy.hstack((self.KalmanGain, numpy.matrix(numpy.zeros((7, 1)))))
319 self.C = numpy.vstack((self.C, numpy.matrix(numpy.zeros((1, 7)))))
320 self.D = numpy.vstack((self.D, numpy.matrix(numpy.zeros((1, 2)))))
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800321
Diana Burgessd0180f12018-03-21 21:24:17 -0700322 self.L = self.A * self.KalmanGain
323
324 unaug_K = self.K
325
326 # Implement a nice closed loop controller for use by the closed loop
327 # controller.
328 self.K = numpy.matrix(numpy.zeros((self.B.shape[1], self.A.shape[0])))
329 self.K[0:2, 0:4] = unaug_K
330 if self.force:
331 self.K[0, 4] = 1.0 / self.mpl
332 self.K[1, 5] = 1.0 / self.mpr
333 else:
334 self.K[0, 4] = 1.0
335 self.K[1, 5] = 1.0
336
337 self.Qff = numpy.matrix(numpy.zeros((4, 4)))
338 qff_pos = 0.005
339 qff_vel = 1.00
340 self.Qff[0, 0] = 1.0 / qff_pos**2.0
341 self.Qff[1, 1] = 1.0 / qff_vel**2.0
342 self.Qff[2, 2] = 1.0 / qff_pos**2.0
343 self.Qff[3, 3] = 1.0 / qff_vel**2.0
344 self.Kff = numpy.matrix(numpy.zeros((2, 7)))
345 self.Kff[0:2, 0:4] = controls.TwoStateFeedForwards(
346 self.B[0:4, :], self.Qff)
347
348 self.InitializeState()
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800349
350
351def WriteDrivetrain(drivetrain_files, kf_drivetrain_files, year_namespace,
352 drivetrain_params):
353
Diana Burgessd0180f12018-03-21 21:24:17 -0700354 # Write the generated constants out to a file.
355 drivetrain_low_low = Drivetrain(
356 name="DrivetrainLowLow",
357 left_low=True,
358 right_low=True,
359 drivetrain_params=drivetrain_params)
360 drivetrain_low_high = Drivetrain(
361 name="DrivetrainLowHigh",
362 left_low=True,
363 right_low=False,
364 drivetrain_params=drivetrain_params)
365 drivetrain_high_low = Drivetrain(
366 name="DrivetrainHighLow",
367 left_low=False,
368 right_low=True,
369 drivetrain_params=drivetrain_params)
370 drivetrain_high_high = Drivetrain(
371 name="DrivetrainHighHigh",
372 left_low=False,
373 right_low=False,
374 drivetrain_params=drivetrain_params)
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800375
Diana Burgessd0180f12018-03-21 21:24:17 -0700376 kf_drivetrain_low_low = KFDrivetrain(
377 name="KFDrivetrainLowLow",
378 left_low=True,
379 right_low=True,
380 drivetrain_params=drivetrain_params)
381 kf_drivetrain_low_high = KFDrivetrain(
382 name="KFDrivetrainLowHigh",
383 left_low=True,
384 right_low=False,
385 drivetrain_params=drivetrain_params)
386 kf_drivetrain_high_low = KFDrivetrain(
387 name="KFDrivetrainHighLow",
388 left_low=False,
389 right_low=True,
390 drivetrain_params=drivetrain_params)
391 kf_drivetrain_high_high = KFDrivetrain(
392 name="KFDrivetrainHighHigh",
393 left_low=False,
394 right_low=False,
395 drivetrain_params=drivetrain_params)
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800396
Diana Burgessd0180f12018-03-21 21:24:17 -0700397 namespaces = [year_namespace, 'control_loops', 'drivetrain']
398 dog_loop_writer = control_loop.ControlLoopWriter(
399 "Drivetrain", [
400 drivetrain_low_low, drivetrain_low_high, drivetrain_high_low,
401 drivetrain_high_high
402 ],
403 namespaces=namespaces)
404 dog_loop_writer.AddConstant(
405 control_loop.Constant("kDt", "%f", drivetrain_low_low.dt))
406 dog_loop_writer.AddConstant(
407 control_loop.Constant("kStallTorque", "%f",
408 drivetrain_low_low.stall_torque))
409 dog_loop_writer.AddConstant(
410 control_loop.Constant("kStallCurrent", "%f",
411 drivetrain_low_low.stall_current))
412 dog_loop_writer.AddConstant(
413 control_loop.Constant("kFreeSpeed", "%f",
414 drivetrain_low_low.free_speed))
415 dog_loop_writer.AddConstant(
416 control_loop.Constant("kFreeCurrent", "%f",
417 drivetrain_low_low.free_current))
418 dog_loop_writer.AddConstant(
419 control_loop.Constant("kJ", "%f", drivetrain_low_low.J))
420 dog_loop_writer.AddConstant(
421 control_loop.Constant("kMass", "%f", drivetrain_low_low.mass))
422 dog_loop_writer.AddConstant(
423 control_loop.Constant("kRobotRadius", "%f",
424 drivetrain_low_low.robot_radius))
425 dog_loop_writer.AddConstant(
426 control_loop.Constant("kWheelRadius", "%f", drivetrain_low_low.r))
427 dog_loop_writer.AddConstant(
428 control_loop.Constant("kR", "%f", drivetrain_low_low.resistance))
429 dog_loop_writer.AddConstant(
430 control_loop.Constant("kV", "%f", drivetrain_low_low.Kv))
431 dog_loop_writer.AddConstant(
432 control_loop.Constant("kT", "%f", drivetrain_low_low.Kt))
433 dog_loop_writer.AddConstant(
434 control_loop.Constant("kLowGearRatio", "%f", drivetrain_low_low.G_low))
435 dog_loop_writer.AddConstant(
436 control_loop.Constant("kHighGearRatio", "%f",
437 drivetrain_high_high.G_high))
438 dog_loop_writer.AddConstant(
439 control_loop.Constant(
440 "kHighOutputRatio", "%f",
441 drivetrain_high_high.G_high * drivetrain_high_high.r))
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800442
Diana Burgessd0180f12018-03-21 21:24:17 -0700443 dog_loop_writer.Write(drivetrain_files[0], drivetrain_files[1])
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800444
Diana Burgessd0180f12018-03-21 21:24:17 -0700445 kf_loop_writer = control_loop.ControlLoopWriter(
446 "KFDrivetrain", [
447 kf_drivetrain_low_low, kf_drivetrain_low_high,
448 kf_drivetrain_high_low, kf_drivetrain_high_high
449 ],
450 namespaces=namespaces)
451 kf_loop_writer.Write(kf_drivetrain_files[0], kf_drivetrain_files[1])
452
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800453
454def PlotDrivetrainMotions(drivetrain_params):
Diana Burgessd0180f12018-03-21 21:24:17 -0700455 # Simulate the response of the system to a step input.
456 drivetrain = Drivetrain(
457 left_low=False, right_low=False, drivetrain_params=drivetrain_params)
458 simulated_left = []
459 simulated_right = []
460 for _ in xrange(100):
461 drivetrain.Update(numpy.matrix([[12.0], [12.0]]))
462 simulated_left.append(drivetrain.X[0, 0])
463 simulated_right.append(drivetrain.X[2, 0])
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800464
Diana Burgessd0180f12018-03-21 21:24:17 -0700465 pylab.rc('lines', linewidth=4)
466 pylab.plot(range(100), simulated_left, label='left position')
467 pylab.plot(range(100), simulated_right, 'r--', label='right position')
468 pylab.suptitle('Acceleration Test\n12 Volt Step Input')
469 pylab.legend(loc='lower right')
470 pylab.show()
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800471
Diana Burgessd0180f12018-03-21 21:24:17 -0700472 # Simulate forwards motion.
473 drivetrain = Drivetrain(
474 left_low=False, right_low=False, drivetrain_params=drivetrain_params)
475 close_loop_left = []
476 close_loop_right = []
477 left_power = []
478 right_power = []
479 R = numpy.matrix([[1.0], [0.0], [1.0], [0.0]])
480 for _ in xrange(300):
481 U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat), drivetrain.U_min,
482 drivetrain.U_max)
483 drivetrain.UpdateObserver(U)
484 drivetrain.Update(U)
485 close_loop_left.append(drivetrain.X[0, 0])
486 close_loop_right.append(drivetrain.X[2, 0])
487 left_power.append(U[0, 0])
488 right_power.append(U[1, 0])
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800489
Diana Burgessd0180f12018-03-21 21:24:17 -0700490 pylab.plot(range(300), close_loop_left, label='left position')
491 pylab.plot(range(300), close_loop_right, 'm--', label='right position')
492 pylab.plot(range(300), left_power, label='left power')
493 pylab.plot(range(300), right_power, '--', label='right power')
494 pylab.suptitle('Linear Move\nLeft and Right Position going to 1')
495 pylab.legend()
496 pylab.show()
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800497
Diana Burgessd0180f12018-03-21 21:24:17 -0700498 # Try turning in place
499 drivetrain = Drivetrain(drivetrain_params=drivetrain_params)
500 close_loop_left = []
501 close_loop_right = []
502 R = numpy.matrix([[-1.0], [0.0], [1.0], [0.0]])
503 for _ in xrange(200):
504 U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat), drivetrain.U_min,
505 drivetrain.U_max)
506 drivetrain.UpdateObserver(U)
507 drivetrain.Update(U)
508 close_loop_left.append(drivetrain.X[0, 0])
509 close_loop_right.append(drivetrain.X[2, 0])
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800510
Diana Burgessd0180f12018-03-21 21:24:17 -0700511 pylab.plot(range(200), close_loop_left, label='left position')
512 pylab.plot(range(200), close_loop_right, label='right position')
513 pylab.suptitle(
514 'Angular Move\nLeft position going to -1 and right position going to 1'
515 )
516 pylab.legend(loc='center right')
517 pylab.show()
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800518
Diana Burgessd0180f12018-03-21 21:24:17 -0700519 # Try turning just one side.
520 drivetrain = Drivetrain(drivetrain_params=drivetrain_params)
521 close_loop_left = []
522 close_loop_right = []
523 R = numpy.matrix([[0.0], [0.0], [1.0], [0.0]])
524 for _ in xrange(300):
525 U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat), drivetrain.U_min,
526 drivetrain.U_max)
527 drivetrain.UpdateObserver(U)
528 drivetrain.Update(U)
529 close_loop_left.append(drivetrain.X[0, 0])
530 close_loop_right.append(drivetrain.X[2, 0])
Campbell Crowley33e0e3d2017-12-27 17:55:40 -0800531
Diana Burgessd0180f12018-03-21 21:24:17 -0700532 pylab.plot(range(300), close_loop_left, label='left position')
533 pylab.plot(range(300), close_loop_right, label='right position')
534 pylab.suptitle(
535 'Pivot\nLeft position not changing and right position going to 1')
536 pylab.legend(loc='center right')
537 pylab.show()