blob: e69d874f85bd61f47830cd6519b2b3aeed6bcaab [file] [log] [blame]
Austin Schuh35d19872018-11-30 15:50:47 +11001#!/usr/bin/python
2
3from __future__ import print_function
4
Austin Schuh35d19872018-11-30 15:50:47 +11005from matplotlib import pylab
Austin Schuh35d19872018-11-30 15:50:47 +11006import gflags
Austin Schuh387a6872018-12-01 19:14:33 +11007import glog
8import numpy
9import scipy
10import scipy.integrate
Austin Schuh7b1e9df2018-12-19 18:04:41 +110011import scipy.optimize
Austin Schuh387a6872018-12-01 19:14:33 +110012import sys
Austin Schuh35d19872018-11-30 15:50:47 +110013
Austin Schuh44aa9142018-12-03 21:07:23 +110014from frc971.control_loops.python import polydrivetrain
Austin Schuh8cb98eb2018-12-05 22:06:45 +110015from frc971.control_loops.python import drivetrain
Austin Schuh7b1e9df2018-12-19 18:04:41 +110016from frc971.control_loops.python import controls
17import y2016.control_loops.python.drivetrain
Austin Schuh44aa9142018-12-03 21:07:23 +110018
Austin Schuh387a6872018-12-01 19:14:33 +110019"""This file is my playground for implementing spline following.
20
21All splines here are cubic bezier splines. See
22 https://en.wikipedia.org/wiki/B%C3%A9zier_curve for more details.
23"""
Austin Schuh35d19872018-11-30 15:50:47 +110024
25FLAGS = gflags.FLAGS
26
27
Austin Schuh8cb98eb2018-12-05 22:06:45 +110028def RungeKutta(f, y0, t, h, count=1):
29 """4th order RungeKutta integration of dy/dt = f(t, y) starting at X."""
30 y1 = y0
31 dh = h / float(count)
32 for x in xrange(count):
33 k1 = dh * f(t + dh * x, y1)
34 k2 = dh * f(t + dh * x + dh / 2.0, y1 + k1 / 2.0)
35 k3 = dh * f(t + dh * x + dh / 2.0, y1 + k2 / 2.0)
36 k4 = dh * f(t + dh * x + dh, y1 + k3)
37 y1 += (k1 + 2.0 * k2 + 2.0 * k3 + k4) / 6.0
38 return y1
39
40
Austin Schuh35d19872018-11-30 15:50:47 +110041def spline(alpha, control_points):
Austin Schuh387a6872018-12-01 19:14:33 +110042 """Computes a Cubic Bezier curve.
Austin Schuh35d19872018-11-30 15:50:47 +110043
44 Args:
45 alpha: scalar or list of spline parameters to calculate the curve at.
46 control_points: n x 4 matrix of control points. n[:, 0] is the
47 starting point, and n[:, 3] is the ending point.
48
49 Returns:
50 n x m matrix of spline points. n is the dimension of the control
51 points, and m is the number of points in 'alpha'.
52 """
53 if numpy.isscalar(alpha):
54 alpha = [alpha]
55 alpha_matrix = [[(1.0 - a)**3.0, 3.0 * (1.0 - a)**2.0 * a,
56 3.0 * (1.0 - a) * a**2.0, a**3.0] for a in alpha]
57
58 return control_points * numpy.matrix(alpha_matrix).T
59
60
61def dspline(alpha, control_points):
Austin Schuh387a6872018-12-01 19:14:33 +110062 """Computes the derivative of a Cubic Bezier curve wrt alpha.
Austin Schuh35d19872018-11-30 15:50:47 +110063
64 Args:
65 alpha: scalar or list of spline parameters to calculate the curve at.
66 control_points: n x 4 matrix of control points. n[:, 0] is the
67 starting point, and n[:, 3] is the ending point.
68
69 Returns:
70 n x m matrix of spline point derivatives. n is the dimension of the
71 control points, and m is the number of points in 'alpha'.
72 """
73 if numpy.isscalar(alpha):
74 alpha = [alpha]
75 dalpha_matrix = [[
76 -3.0 * (1.0 - a)**2.0, 3.0 * (1.0 - a)**2.0 + -2.0 * 3.0 *
77 (1.0 - a) * a, -3.0 * a**2.0 + 2.0 * 3.0 * (1.0 - a) * a, 3.0 * a**2.0
78 ] for a in alpha]
79
80 return control_points * numpy.matrix(dalpha_matrix).T
81
82
83def ddspline(alpha, control_points):
Austin Schuh387a6872018-12-01 19:14:33 +110084 """Computes the second derivative of a Cubic Bezier curve wrt alpha.
Austin Schuh35d19872018-11-30 15:50:47 +110085
86 Args:
87 alpha: scalar or list of spline parameters to calculate the curve at.
88 control_points: n x 4 matrix of control points. n[:, 0] is the
89 starting point, and n[:, 3] is the ending point.
90
91 Returns:
92 n x m matrix of spline point second derivatives. n is the dimension of
93 the control points, and m is the number of points in 'alpha'.
94 """
95 if numpy.isscalar(alpha):
96 alpha = [alpha]
97 ddalpha_matrix = [[
98 2.0 * 3.0 * (1.0 - a),
99 -2.0 * 3.0 * (1.0 - a) + -2.0 * 3.0 * (1.0 - a) + 2.0 * 3.0 * a,
100 -2.0 * 3.0 * a + 2.0 * 3.0 * (1.0 - a) - 2.0 * 3.0 * a,
101 2.0 * 3.0 * a
102 ] for a in alpha]
103
104 return control_points * numpy.matrix(ddalpha_matrix).T
105
106
107def dddspline(alpha, control_points):
Austin Schuh387a6872018-12-01 19:14:33 +1100108 """Computes the third derivative of a Cubic Bezier curve wrt alpha.
Austin Schuh35d19872018-11-30 15:50:47 +1100109
110 Args:
111 alpha: scalar or list of spline parameters to calculate the curve at.
112 control_points: n x 4 matrix of control points. n[:, 0] is the
113 starting point, and n[:, 3] is the ending point.
114
115 Returns:
116 n x m matrix of spline point second derivatives. n is the dimension of
117 the control points, and m is the number of points in 'alpha'.
118 """
119 if numpy.isscalar(alpha):
120 alpha = [alpha]
121 ddalpha_matrix = [[
122 -2.0 * 3.0,
123 2.0 * 3.0 + 2.0 * 3.0 + 2.0 * 3.0,
124 -2.0 * 3.0 - 2.0 * 3.0 - 2.0 * 3.0,
125 2.0 * 3.0
126 ] for a in alpha]
127
128 return control_points * numpy.matrix(ddalpha_matrix).T
129
130
131def spline_theta(alpha, control_points, dspline_points=None):
Austin Schuh387a6872018-12-01 19:14:33 +1100132 """Computes the heading of a robot following a Cubic Bezier curve at alpha.
Austin Schuh35d19872018-11-30 15:50:47 +1100133
134 Args:
135 alpha: scalar or list of spline parameters to calculate the heading at.
136 control_points: n x 4 matrix of control points. n[:, 0] is the
137 starting point, and n[:, 3] is the ending point.
138
139 Returns:
140 m array of spline point headings. m is the number of points in 'alpha'.
141 """
142 if dspline_points is None:
Austin Schuh387a6872018-12-01 19:14:33 +1100143 dspline_points = dspline(alpha, control_points)
Austin Schuh35d19872018-11-30 15:50:47 +1100144
145 return numpy.arctan2(
146 numpy.array(dspline_points)[1, :], numpy.array(dspline_points)[0, :])
147
148
Austin Schuh387a6872018-12-01 19:14:33 +1100149def dspline_theta(alpha,
Austin Schuh35d19872018-11-30 15:50:47 +1100150 control_points,
151 dspline_points=None,
152 ddspline_points=None):
Austin Schuh387a6872018-12-01 19:14:33 +1100153 """Computes the derivative of the heading at alpha.
Austin Schuh35d19872018-11-30 15:50:47 +1100154
Austin Schuh387a6872018-12-01 19:14:33 +1100155 This is the derivative of spline_theta wrt alpha.
Austin Schuh35d19872018-11-30 15:50:47 +1100156
157 Args:
158 alpha: scalar or list of spline parameters to calculate the derivative
159 of the heading at.
160 control_points: n x 4 matrix of control points. n[:, 0] is the
161 starting point, and n[:, 3] is the ending point.
162
163 Returns:
164 m array of spline point heading derivatives. m is the number of points
165 in 'alpha'.
166 """
167 if dspline_points is None:
Austin Schuh387a6872018-12-01 19:14:33 +1100168 dspline_points = dspline(alpha, control_points)
Austin Schuh35d19872018-11-30 15:50:47 +1100169
170 if ddspline_points is None:
Austin Schuh387a6872018-12-01 19:14:33 +1100171 ddspline_points = ddspline(alpha, control_points)
Austin Schuh35d19872018-11-30 15:50:47 +1100172
173 dx = numpy.array(dspline_points)[0, :]
174 dy = numpy.array(dspline_points)[1, :]
175
176 ddx = numpy.array(ddspline_points)[0, :]
177 ddy = numpy.array(ddspline_points)[1, :]
178
179 return 1.0 / (dx**2.0 + dy**2.0) * (dx * ddy - dy * ddx)
180
181
Austin Schuh387a6872018-12-01 19:14:33 +1100182def ddspline_theta(alpha,
Austin Schuh35d19872018-11-30 15:50:47 +1100183 control_points,
184 dspline_points=None,
185 ddspline_points=None,
186 dddspline_points=None):
Austin Schuh387a6872018-12-01 19:14:33 +1100187 """Computes the second derivative of the heading at alpha.
Austin Schuh35d19872018-11-30 15:50:47 +1100188
Austin Schuh387a6872018-12-01 19:14:33 +1100189 This is the second derivative of spline_theta wrt alpha.
Austin Schuh35d19872018-11-30 15:50:47 +1100190
191 Args:
192 alpha: scalar or list of spline parameters to calculate the second
193 derivative of the heading at.
194 control_points: n x 4 matrix of control points. n[:, 0] is the
195 starting point, and n[:, 3] is the ending point.
196
197 Returns:
198 m array of spline point heading second derivatives. m is the number of
199 points in 'alpha'.
200 """
201 if dspline_points is None:
Austin Schuh387a6872018-12-01 19:14:33 +1100202 dspline_points = dspline(alpha, control_points)
Austin Schuh35d19872018-11-30 15:50:47 +1100203
204 if ddspline_points is None:
Austin Schuh387a6872018-12-01 19:14:33 +1100205 ddspline_points = ddspline(alpha, control_points)
Austin Schuh35d19872018-11-30 15:50:47 +1100206
207 if dddspline_points is None:
Austin Schuh387a6872018-12-01 19:14:33 +1100208 dddspline_points = dddspline(alpha, control_points)
Austin Schuh35d19872018-11-30 15:50:47 +1100209
Austin Schuh387a6872018-12-01 19:14:33 +1100210 dddspline_points = dddspline(alpha, control_points)
Austin Schuh35d19872018-11-30 15:50:47 +1100211
212 dx = numpy.array(dspline_points)[0, :]
213 dy = numpy.array(dspline_points)[1, :]
214
215 ddx = numpy.array(ddspline_points)[0, :]
216 ddy = numpy.array(ddspline_points)[1, :]
217
218 dddx = numpy.array(dddspline_points)[0, :]
219 dddy = numpy.array(dddspline_points)[1, :]
220
221 return -1.0 / ((dx**2.0 + dy**2.0)**2.0) * (dx * ddy - dy * ddx) * 2.0 * (
222 dy * ddy + dx * ddx) + 1.0 / (dx**2.0 + dy**2.0) * (dx * dddy - dy *
223 dddx)
224
225
Austin Schuh387a6872018-12-01 19:14:33 +1100226class Path(object):
227 """Represents a path to follow."""
228 def __init__(self, control_points):
229 """Constructs a path given the control points."""
230 self._control_points = control_points
231
232 def spline_velocity(alpha):
233 return numpy.linalg.norm(dspline(alpha, self._control_points), axis=0)
234
235 self._point_distances = [0.0]
236 num_alpha = 100
237 # Integrate the xy velocity as a function of alpha for each step in the
238 # table to get an alpha -> distance calculation. Gaussian Quadrature
239 # is quite accurate, so we can get away with fewer points here than we
240 # might think.
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100241 for alpha in numpy.linspace(0.0, 1.0, num_alpha)[1:]:
Austin Schuh387a6872018-12-01 19:14:33 +1100242 self._point_distances.append(
243 scipy.integrate.fixed_quad(spline_velocity, alpha, alpha + 1.0
244 / (num_alpha - 1.0))[0] +
245 self._point_distances[-1])
246
247 def distance_to_alpha(self, distance):
248 """Converts distances along the spline to alphas.
249
250 Args:
251 distance: A scalar or array of distances to convert
252
253 Returns:
254 An array of distances, (1 big if the input was a scalar)
255 """
256 if numpy.isscalar(distance):
257 return numpy.array([self._distance_to_alpha_scalar(distance)])
258 else:
259 return numpy.array([self._distance_to_alpha_scalar(d) for d in distance])
260
261 def _distance_to_alpha_scalar(self, distance):
262 """Helper to compute alpha for a distance for a single scalar."""
263 if distance <= 0.0:
264 return 0.0
265 elif distance >= self.length():
266 return 1.0
267 after_index = numpy.searchsorted(
268 self._point_distances, distance, side='right')
269 before_index = after_index - 1
270
271 # Linearly interpolate alpha from our (sorted) distance table.
272 return (distance - self._point_distances[before_index]) / (
273 self._point_distances[after_index] -
274 self._point_distances[before_index]) * (1.0 / (
275 len(self._point_distances) - 1.0)) + float(before_index) / (
276 len(self._point_distances) - 1.0)
277
278 def length(self):
279 """Returns the length of the spline (in meters)"""
280 return self._point_distances[-1]
281
282 # TODO(austin): need a better name...
283 def xy(self, distance):
284 """Returns the xy position as a function of distance."""
285 return spline(self.distance_to_alpha(distance), self._control_points)
286
287 # TODO(austin): need a better name...
288 def dxy(self, distance):
289 """Returns the xy velocity as a function of distance."""
290 dspline_point = dspline(
291 self.distance_to_alpha(distance), self._control_points)
292 return dspline_point / numpy.linalg.norm(dspline_point, axis=0)
293
294 # TODO(austin): need a better name...
295 def ddxy(self, distance):
296 """Returns the xy acceleration as a function of distance."""
297 alpha = self.distance_to_alpha(distance)
298 dspline_points = dspline(alpha, self._control_points)
299 ddspline_points = ddspline(alpha, self._control_points)
300
301 norm = numpy.linalg.norm(
302 dspline_points, axis=0)**2.0
303
304 return ddspline_points / norm - numpy.multiply(
305 dspline_points, (numpy.array(dspline_points)[0, :] *
306 numpy.array(ddspline_points)[0, :] +
307 numpy.array(dspline_points)[1, :] *
308 numpy.array(ddspline_points)[1, :]) / (norm**2.0))
309
310 def theta(self, distance, dspline_points=None):
311 """Returns the heading as a function of distance."""
312 return spline_theta(
313 self.distance_to_alpha(distance),
314 self._control_points,
315 dspline_points=dspline_points)
316
317 def dtheta(self, distance, dspline_points=None, ddspline_points=None):
318 """Returns the angular velocity as a function of distance."""
319 alpha = self.distance_to_alpha(distance)
320 if dspline_points is None:
321 dspline_points = dspline(alpha, self._control_points)
322 if ddspline_points is None:
323 ddspline_points = ddspline(alpha, self._control_points)
324
325 dtheta_points = dspline_theta(alpha, self._control_points,
326 dspline_points, ddspline_points)
327
328 return dtheta_points / numpy.linalg.norm(dspline_points, axis=0)
329
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100330 def dtheta_dt(self, distance, velocity, dspline_points=None, ddspline_points=None):
331 """Returns the angular velocity as a function of time."""
332 return self.dtheta(distance, dspline_points, ddspline_points) * velocity
333
Austin Schuh387a6872018-12-01 19:14:33 +1100334 def ddtheta(self,
335 distance,
336 dspline_points=None,
337 ddspline_points=None,
338 dddspline_points=None):
339 """Returns the angular acceleration as a function of distance."""
340 alpha = self.distance_to_alpha(distance)
341 if dspline_points is None:
342 dspline_points = dspline(alpha, self._control_points)
343 if ddspline_points is None:
344 ddspline_points = ddspline(alpha, self._control_points)
345 if dddspline_points is None:
346 dddspline_points = dddspline(alpha, self._control_points)
347
348 dtheta_points = dspline_theta(alpha, self._control_points,
349 dspline_points, ddspline_points)
350 ddtheta_points = ddspline_theta(alpha, self._control_points,
351 dspline_points, ddspline_points,
352 dddspline_points)
353
354 # TODO(austin): Factor out the d^alpha/dd^2.
355 return ddtheta_points / numpy.linalg.norm(
356 dspline_points, axis=0)**2.0 - numpy.multiply(
357 dtheta_points, (numpy.array(dspline_points)[0, :] *
358 numpy.array(ddspline_points)[0, :] +
359 numpy.array(dspline_points)[1, :] *
360 numpy.array(ddspline_points)[1, :]) /
361 ((numpy.array(dspline_points)[0, :]**2.0 +
362 numpy.array(dspline_points)[1, :]**2.0)**2.0))
363
364
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100365def integrate_accel_for_distance(f, v, x, dx):
366 # Use a trick from
367 # https://www.johndcook.com/blog/2012/02/21/care-and-treatment-of-singularities/
368 #
369 # We want to calculate:
370 # v0 + (integral of dv/dt = f(x, v) from x to x + dx); noting that dv/dt
371 # is expressed in t, not distance, so we want to do the integral of
372 # dv/dx = f(x, v) / v.
373 #
374 # Because v can be near zero at the start of the integral (but because f is
375 # nonnegative, v will never go to zero), but the integral should still be
376 # valid, we follow the suggestion and instead calculate
377 # v0 + integral((f(x, v) - f(x0, v0)) / v) + integral(f(x0, v0) / v).
378 #
379 # Using a0 = f(x0, v0), we get the second term as
380 # integral((f(x, v) - a0) / v)
381 # where when v is zero we will also be at x0/v0 (because v can only start
382 # at zero, not go to zero).
383 #
384 # The second term, integral(a0 / v) requires an approximation.--in
385 # this case, that dv/dt is constant. Thus, we have
386 # integral(a0 / sqrt(v0^2 + 2*a0*x)) = sqrt(2*a0*dx + v0^2) - sqrt(v0^2)
387 # = sqrt(2 * a0 * dx * v0^2) - v0.
388 #
389 # Because the RungeKutta function returns v0 + the integral, this
390 # gives the statements below.
391
392 a0 = f(x, v)
393
394 def integrablef(t, y):
395 # Since we know that a0 == a(0) and that they are asymptotically the
396 # same at 0, we know that the limit is 0 at 0. This is true because
397 # when starting from a stop, under sane accelerations, we can assume
398 # that we will start with a constant acceleration. So, hard-code it.
399 if numpy.abs(y) < 1e-6:
400 return 0.0
401 return (f(t, y) - a0) / y
402
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100403 return (RungeKutta(integrablef, v, x, dx) - v
404 ) + numpy.sqrt(2.0 * a0 * dx + v * v)
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100405
406
407class Trajectory(object):
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100408 def __init__(self, path, drivetrain, longitudal_accel, lateral_accel,
409 distance_count):
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100410 self._path = path
411 self._drivetrain = drivetrain
412 self.distances = numpy.linspace(0.0,
413 self._path.length(), distance_count)
414 self._longitudal_accel = longitudal_accel
415 self._lateral_accel = lateral_accel
416
417 self._B_inverse = numpy.linalg.inv(self._drivetrain.B_continuous)
418
419 def create_plan(self, vmax):
420 vmax = 10.0
421 plan = numpy.array(numpy.zeros((len(self.distances), )))
422 plan.fill(vmax)
423 return plan
424
425 def lateral_velocity_curvature(self, distance):
426 return numpy.sqrt(self._lateral_accel /
427 numpy.linalg.norm(self._path.ddxy(distance)))
428
429 def lateral_accel_pass(self, plan):
430 plan = plan.copy()
431 # TODO(austin): This appears to be doing nothing.
432 for i, distance in enumerate(self.distances):
433 plan[i] = min(plan[i], self.lateral_velocity_curvature(distance))
434 return plan
435
436 def compute_K345(self, current_dtheta, current_ddtheta):
437 # We've now got the equation:
438 # K2 * d^2x/dt^2 + K1 (dx/dt)^2 = A * K2 * dx/dt + B * U
439 K1 = numpy.matrix(
440 [[-self._drivetrain.robot_radius_l * current_ddtheta],
441 [self._drivetrain.robot_radius_r * current_ddtheta]])
442 K2 = numpy.matrix(
443 [[1.0 - self._drivetrain.robot_radius_l * current_dtheta],
444 [1.0 + self._drivetrain.robot_radius_r * current_dtheta]])
445
446 # Now, rephrase it as K5 a + K3 v^2 + K4 v = U
447 K3 = self._B_inverse * K1
448 K4 = -self._B_inverse * self._drivetrain.A_continuous * K2
449 K5 = self._B_inverse * K2
450 return K3, K4, K5
451
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100452 def forward_acceleration(self, x, v):
453 current_ddtheta = self._path.ddtheta(x)[0]
454 current_dtheta = self._path.dtheta(x)[0]
455 # We've now got the equation:
456 # K2 * d^2x/dt^2 + K1 (dx/dt)^2 = A * K2 * dx/dt + B * U
457 # Now, rephrase it as K5 a + K3 v^2 + K4 v = U
458 K3, K4, K5 = self.compute_K345(current_dtheta, current_ddtheta)
459
460 C = K3 * v * v + K4 * v
461 # Note: K345 are not quite constant over the step, but we are going
462 # to assume they are for now.
463 accelerations = [(12.0 - C[0, 0]) / K5[0, 0], (12.0 - C[1, 0]) /
464 K5[1, 0], (-12.0 - C[0, 0]) / K5[0, 0],
465 (-12.0 - C[1, 0]) / K5[1, 0]]
Austin Schuhec7f06d2019-01-04 07:47:15 +1100466 maxa = -float('inf')
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100467 for a in accelerations:
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100468 U = K5 * a + K3 * v * v + K4 * v
469 if not (numpy.abs(U) > 12.0 + 1e-6).any():
470 maxa = max(maxa, a)
471
472 lateral_accel = v * v * numpy.linalg.norm(self._path.ddxy(x))
473 # Constrain the longitudinal acceleration to keep in a pseudo friction
474 # circle. This will make it so we don't floor it while in a turn and
475 # cause extra wheel slip.
476 long_accel = numpy.sqrt(1.0 - (lateral_accel / self._lateral_accel)**
477 2.0) * self._longitudal_accel
478 return min(long_accel, maxa)
479
480 def forward_pass(self, plan):
481 plan = plan.copy()
482 for i, distance in enumerate(self.distances):
483 if i == len(self.distances) - 1:
484 break
485
486 plan[i + 1] = min(
487 plan[i + 1],
488 integrate_accel_for_distance(
489 self.forward_acceleration, plan[i], self.distances[i],
490 self.distances[i + 1] - self.distances[i]))
491 return plan
492
493 def backward_acceleration(self, x, v):
494 # TODO(austin): Forwards and backwards are quite similar. Can we
495 # factor this out?
496 current_ddtheta = self._path.ddtheta(x)[0]
497 current_dtheta = self._path.dtheta(x)[0]
498 # We've now got the equation:
499 # K2 * d^2x/dt^2 + K1 (dx/dt)^2 = A * K2 * dx/dt + B * U
500 # Now, rephrase it as K5 a + K3 v^2 + K4 v = U
501 K3, K4, K5 = self.compute_K345(current_dtheta, current_ddtheta)
502
503 C = K3 * v * v + K4 * v
504 # Note: K345 are not quite constant over the step, but we are going
505 # to assume they are for now.
506 accelerations = [(12.0 - C[0, 0]) / K5[0, 0], (12.0 - C[1, 0]) /
507 K5[1, 0], (-12.0 - C[0, 0]) / K5[0, 0],
508 (-12.0 - C[1, 0]) / K5[1, 0]]
Austin Schuhec7f06d2019-01-04 07:47:15 +1100509 mina = float('inf')
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100510 for a in accelerations:
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100511 U = K5 * a + K3 * v * v + K4 * v
512 if not (numpy.abs(U) > 12.0 + 1e-6).any():
513 mina = min(mina, a)
514
515 lateral_accel = v * v * numpy.linalg.norm(self._path.ddxy(x))
516 # Constrain the longitudinal acceleration to keep in a pseudo friction
517 # circle. This will make it so we don't floor it while in a turn and
518 # cause extra wheel slip.
519 long_accel = -numpy.sqrt(1.0 - (lateral_accel / self._lateral_accel)**
520 2.0) * self._longitudal_accel
521 return max(long_accel, mina)
522
523 def backward_pass(self, plan):
524 plan = plan.copy()
525 for i, distance in reversed(list(enumerate(self.distances))):
526 if i == 0:
527 break
528
529 plan[i - 1] = min(
530 plan[i - 1],
531 integrate_accel_for_distance(
532 self.backward_acceleration, plan[i], self.distances[i],
533 self.distances[i - 1] - self.distances[i]))
534 return plan
535
536 # TODO(austin): The plan should probably not be passed in...
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100537 def ff_accel(self, plan, distance):
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100538 if distance < self.distances[1]:
539 after_index = 1
540 before_index = after_index - 1
541 if distance < self.distances[0]:
542 distance = 0.0
543 elif distance > self.distances[-2]:
544 after_index = len(self.distances) - 1
545 before_index = after_index - 1
546 if distance > self.distances[-1]:
547 distance = self.distances[-1]
548 else:
549 after_index = numpy.searchsorted(
550 self.distances, distance, side='right')
551 before_index = after_index - 1
552
553 vforwards = integrate_accel_for_distance(
554 self.forward_acceleration, plan[before_index],
555 self.distances[before_index],
556 distance - self.distances[before_index])
557 vbackward = integrate_accel_for_distance(
558 self.backward_acceleration, plan[after_index],
559 self.distances[after_index],
560 distance - self.distances[after_index])
561
562 vcurvature = self.lateral_velocity_curvature(distance)
563
564 if vcurvature < vforwards and vcurvature < vbackward:
565 accel = 0
566 velocity = vcurvature
567 elif vforwards < vbackward:
568 velocity = vforwards
569 accel = self.forward_acceleration(distance, velocity)
570 else:
571 velocity = vbackward
572 accel = self.backward_acceleration(distance, velocity)
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100573 return (distance, velocity, accel)
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100574
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100575 def ff_voltage(self, plan, distance):
576 _, velocity, accel = self.ff_accel(plan, distance)
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100577 current_ddtheta = self._path.ddtheta(distance)[0]
578 current_dtheta = self._path.dtheta(distance)[0]
579 # TODO(austin): Factor these out.
580 # We've now got the equation:
581 # K2 * d^2x/dt^2 + K1 (dx/dt)^2 = A * K2 * dx/dt + B * U
582 # Now, rephrase it as K5 a + K3 v^2 + K4 v = U
583 K3, K4, K5 = self.compute_K345(current_dtheta, current_ddtheta)
584
585 U = K5 * accel + K3 * velocity * velocity + K4 * velocity
586 return U
Austin Schuh387a6872018-12-01 19:14:33 +1100587
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100588 def goal_state(self, distance, velocity):
589 width = (
590 self._drivetrain.robot_radius_l + self._drivetrain.robot_radius_r)
591 goal = numpy.matrix(numpy.zeros((5, 1)))
592
593 goal[0:2, :] = self._path.xy(distance)
594 goal[2, :] = self._path.theta(distance)
595
596 Ter = numpy.linalg.inv(numpy.matrix([[0.5, 0.5], [-1.0 / width, 1.0 / width]]))
597 goal[3:5, :] = Ter * numpy.matrix(
598 [[velocity], [self._path.dtheta_dt(distance, velocity)]])
599 return goal
600
601
Austin Schuh35d19872018-11-30 15:50:47 +1100602def main(argv):
603 # Build up the control point matrix
604 start = numpy.matrix([[0.0, 0.0]]).T
605 c1 = numpy.matrix([[0.5, 0.0]]).T
606 c2 = numpy.matrix([[0.5, 1.0]]).T
607 end = numpy.matrix([[1.0, 1.0]]).T
608 control_points = numpy.hstack((start, c1, c2, end))
609
610 # The alphas to plot
611 alphas = numpy.linspace(0.0, 1.0, 1000)
612
613 # Compute x, y and the 3 derivatives
614 spline_points = spline(alphas, control_points)
615 dspline_points = dspline(alphas, control_points)
616 ddspline_points = ddspline(alphas, control_points)
617 dddspline_points = dddspline(alphas, control_points)
618
619 # Compute theta and the two derivatives
620 theta = spline_theta(alphas, control_points, dspline_points=dspline_points)
Austin Schuh387a6872018-12-01 19:14:33 +1100621 dtheta = dspline_theta(
622 alphas, control_points, dspline_points=dspline_points)
Austin Schuh35d19872018-11-30 15:50:47 +1100623 ddtheta = ddspline_theta(
624 alphas,
625 control_points,
626 dspline_points=dspline_points,
627 dddspline_points=dddspline_points)
628
629 # Plot the control points and the spline.
630 pylab.figure()
631 pylab.plot(
632 numpy.array(control_points)[0, :],
633 numpy.array(control_points)[1, :],
634 '-o',
635 label='control')
636 pylab.plot(
637 numpy.array(spline_points)[0, :],
638 numpy.array(spline_points)[1, :],
639 label='spline')
640 pylab.legend()
641
642 # For grins, confirm that the double integral of the acceleration (with
643 # respect to the spline parameter) matches the position. This lets us
644 # confirm that the derivatives are consistent.
645 xint_plot = numpy.matrix(numpy.zeros((2, len(alphas))))
646 dxint_plot = xint_plot.copy()
647 xint = spline_points[:, 0].copy()
648 dxint = dspline_points[:, 0].copy()
649 xint_plot[:, 0] = xint
650 dxint_plot[:, 0] = dxint
651 for i in range(len(alphas) - 1):
652 xint += (alphas[i + 1] - alphas[i]) * dxint
653 dxint += (alphas[i + 1] - alphas[i]) * ddspline_points[:, i]
654 xint_plot[:, i + 1] = xint
655 dxint_plot[:, i + 1] = dxint
656
657 # Integrate up the spline velocity and heading to confirm that given a
658 # velocity (as a function of the spline parameter) and angle, we will move
659 # from the starting point to the ending point.
660 thetaint_plot = numpy.zeros((len(alphas),))
661 thetaint = theta[0]
662 dthetaint_plot = numpy.zeros((len(alphas),))
663 dthetaint = dtheta[0]
664 thetaint_plot[0] = thetaint
665 dthetaint_plot[0] = dthetaint
666
667 txint_plot = numpy.matrix(numpy.zeros((2, len(alphas))))
668 txint = spline_points[:, 0].copy()
669 txint_plot[:, 0] = txint
670 for i in range(len(alphas) - 1):
671 dalpha = alphas[i + 1] - alphas[i]
672 txint += dalpha * numpy.linalg.norm(
673 dspline_points[:, i]) * numpy.matrix(
674 [[numpy.cos(theta[i])], [numpy.sin(theta[i])]])
675 txint_plot[:, i + 1] = txint
676 thetaint += dalpha * dtheta[i]
677 dthetaint += dalpha * ddtheta[i]
678 thetaint_plot[i + 1] = thetaint
679 dthetaint_plot[i + 1] = dthetaint
680
681
682 # Now plot x, dx/dalpha, ddx/ddalpha, dddx/dddalpha, and integrals thereof
683 # to perform consistency checks.
684 pylab.figure()
685 pylab.plot(alphas, numpy.array(spline_points)[0, :], label='x')
686 pylab.plot(alphas, numpy.array(xint_plot)[0, :], label='ix')
687 pylab.plot(alphas, numpy.array(dspline_points)[0, :], label='dx')
688 pylab.plot(alphas, numpy.array(dxint_plot)[0, :], label='idx')
689 pylab.plot(alphas, numpy.array(txint_plot)[0, :], label='tix')
690 pylab.plot(alphas, numpy.array(ddspline_points)[0, :], label='ddx')
691 pylab.plot(alphas, numpy.array(dddspline_points)[0, :], label='dddx')
692 pylab.legend()
693
694 # Now do the same for y.
695 pylab.figure()
696 pylab.plot(alphas, numpy.array(spline_points)[1, :], label='y')
697 pylab.plot(alphas, numpy.array(xint_plot)[1, :], label='iy')
698 pylab.plot(alphas, numpy.array(dspline_points)[1, :], label='dy')
699 pylab.plot(alphas, numpy.array(dxint_plot)[1, :], label='idy')
700 pylab.plot(alphas, numpy.array(txint_plot)[1, :], label='tiy')
701 pylab.plot(alphas, numpy.array(ddspline_points)[1, :], label='ddy')
702 pylab.plot(alphas, numpy.array(dddspline_points)[1, :], label='dddy')
703 pylab.legend()
704
705 # And for theta.
706 pylab.figure()
707 pylab.plot(alphas, theta, label='theta')
708 pylab.plot(alphas, dtheta, label='dtheta')
709 pylab.plot(alphas, ddtheta, label='ddtheta')
710 pylab.plot(alphas, thetaint_plot, label='thetai')
711 pylab.plot(alphas, dthetaint_plot, label='dthetai')
Austin Schuh387a6872018-12-01 19:14:33 +1100712 pylab.plot(
713 alphas,
714 numpy.linalg.norm(
715 numpy.array(dspline_points), axis=0),
716 label='velocity')
717
718 # Now, repeat as a function of path length as opposed to alpha
719 path = Path(control_points)
720 distance_count = 1000
721 position = path.xy(0.0)
722 velocity = path.dxy(0.0)
723 theta = path.theta(0.0)
724 omega = path.dtheta(0.0)
725
726 iposition_plot = numpy.matrix(numpy.zeros((2, distance_count)))
727 ivelocity_plot = numpy.matrix(numpy.zeros((2, distance_count)))
728 iposition_plot[:, 0] = position.copy()
729 ivelocity_plot[:, 0] = velocity.copy()
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100730 itheta_plot = numpy.zeros((distance_count, ))
731 iomega_plot = numpy.zeros((distance_count, ))
Austin Schuh387a6872018-12-01 19:14:33 +1100732 itheta_plot[0] = theta
733 iomega_plot[0] = omega
734
735 distances = numpy.linspace(0.0, path.length(), distance_count)
736
737 for i in xrange(len(distances) - 1):
738 position += velocity * (distances[i + 1] - distances[i])
739 velocity += path.ddxy(distances[i]) * (distances[i + 1] - distances[i])
740 iposition_plot[:, i + 1] = position
741 ivelocity_plot[:, i + 1] = velocity
742
743 theta += omega * (distances[i + 1] - distances[i])
744 omega += path.ddtheta(distances[i]) * (distances[i + 1] - distances[i])
745 itheta_plot[i + 1] = theta
746 iomega_plot[i + 1] = omega
747
748 pylab.figure()
749 pylab.plot(distances, numpy.array(path.xy(distances))[0, :], label='x')
750 pylab.plot(distances, numpy.array(iposition_plot)[0, :], label='ix')
751 pylab.plot(distances, numpy.array(path.dxy(distances))[0, :], label='dx')
752 pylab.plot(distances, numpy.array(ivelocity_plot)[0, :], label='idx')
753 pylab.plot(distances, numpy.array(path.ddxy(distances))[0, :], label='ddx')
754 pylab.legend()
755
756 pylab.figure()
757 pylab.plot(distances, numpy.array(path.xy(distances))[1, :], label='y')
758 pylab.plot(distances, numpy.array(iposition_plot)[1, :], label='iy')
759 pylab.plot(distances, numpy.array(path.dxy(distances))[1, :], label='dy')
760 pylab.plot(distances, numpy.array(ivelocity_plot)[1, :], label='idy')
761 pylab.plot(distances, numpy.array(path.ddxy(distances))[1, :], label='ddy')
762 pylab.legend()
763
764 pylab.figure()
765 pylab.plot(distances, path.theta(distances), label='theta')
766 pylab.plot(distances, itheta_plot, label='itheta')
767 pylab.plot(distances, path.dtheta(distances), label='omega')
768 pylab.plot(distances, iomega_plot, label='iomega')
769 pylab.plot(distances, path.ddtheta(distances), label='alpha')
770 pylab.legend()
Austin Schuh35d19872018-11-30 15:50:47 +1100771
772 # TODO(austin): Start creating a velocity plan now that we have all the
773 # derivitives of our spline.
774
Austin Schuh44aa9142018-12-03 21:07:23 +1100775 velocity_drivetrain = polydrivetrain.VelocityDrivetrainModel(
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100776 y2016.control_loops.python.drivetrain.kDrivetrain)
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100777 position_drivetrain = drivetrain.Drivetrain(
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100778 y2016.control_loops.python.drivetrain.kDrivetrain)
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100779
780 longitudal_accel = 3.0
781 lateral_accel = 2.0
782
783 trajectory = Trajectory(
784 path,
785 drivetrain=velocity_drivetrain,
786 longitudal_accel=longitudal_accel,
787 lateral_accel=lateral_accel,
788 distance_count=500)
Austin Schuh44aa9142018-12-03 21:07:23 +1100789
790 vmax = numpy.inf
791 vmax = 10.0
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100792 lateral_accel_plan = trajectory.lateral_accel_pass(
793 trajectory.create_plan(vmax))
Austin Schuh44aa9142018-12-03 21:07:23 +1100794
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100795 forward_accel_plan = lateral_accel_plan.copy()
796 # Start and end the path stopped.
797 forward_accel_plan[0] = 0.0
798 forward_accel_plan[-1] = 0.0
Austin Schuh44aa9142018-12-03 21:07:23 +1100799
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100800 forward_accel_plan = trajectory.forward_pass(forward_accel_plan)
Austin Schuh44aa9142018-12-03 21:07:23 +1100801
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100802 backward_accel_plan = trajectory.backward_pass(forward_accel_plan)
Austin Schuh44aa9142018-12-03 21:07:23 +1100803
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100804 # And now, calculate the left, right voltage as a function of distance.
Austin Schuh44aa9142018-12-03 21:07:23 +1100805
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100806 # TODO(austin): Factor out the accel and decel functions so we can use them
807 # to calculate voltage as a function of distance.
Austin Schuh44aa9142018-12-03 21:07:23 +1100808
809 pylab.figure()
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100810 pylab.plot(trajectory.distances, lateral_accel_plan, label='accel pass')
811 pylab.plot(trajectory.distances, forward_accel_plan, label='forward pass')
812 pylab.plot(trajectory.distances, backward_accel_plan, label='forward pass')
Austin Schuh44aa9142018-12-03 21:07:23 +1100813 pylab.xlabel("distance along spline (m)")
814 pylab.ylabel("velocity (m/s)")
815 pylab.legend()
816
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100817 dt = 0.005
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100818 # Now, let's integrate up the path centric coordinates to get a distance,
819 # velocity, and acceleration as a function of time to follow the path.
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100820
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100821 length_plan_t = [0.0]
822 length_plan_x = [numpy.matrix(numpy.zeros((2, 1)))]
823 length_plan_v = [0.0]
824 length_plan_a = [trajectory.ff_accel(backward_accel_plan, 0.0)[2]]
825 t = 0.0
826 spline_state = length_plan_x[-1][0:2, :]
827
828 while spline_state[0, 0] < path.length():
829 t += dt
830 def along_spline_diffeq(t, x):
831 _, v, a = trajectory.ff_accel(backward_accel_plan, x[0, 0])
832 return numpy.matrix([[x[1, 0]], [a]])
833
834 spline_state = RungeKutta(along_spline_diffeq,
835 spline_state.copy(), t, dt)
836
837 d, v, a = trajectory.ff_accel(backward_accel_plan, length_plan_x[-1][0, 0])
838
839 length_plan_v.append(v)
840 length_plan_a.append(a)
841 length_plan_t.append(t)
842 length_plan_x.append(spline_state.copy())
843 spline_state[1, 0] = v
844
845 xva_plan = numpy.matrix(numpy.zeros((3, len(length_plan_t))))
846 u_plan = numpy.matrix(numpy.zeros((2, len(length_plan_t))))
847 state_plan = numpy.matrix(numpy.zeros((5, len(length_plan_t))))
848
849 state = numpy.matrix(numpy.zeros((5, 1)))
850 state[3, 0] = 0.1
851 state[4, 0] = 0.1
852 states = numpy.matrix(numpy.zeros((5, len(length_plan_t))))
853 full_us = numpy.matrix(numpy.zeros((2, len(length_plan_t))))
854 x_es = []
855 y_es = []
856 theta_es = []
857 vel_es = []
858 omega_es = []
859 omega_rs = []
860 omega_cs = []
861
862 width = (velocity_drivetrain.robot_radius_l +
863 velocity_drivetrain.robot_radius_r)
864 Ter = numpy.matrix([[0.5, 0.5], [-1.0 / width, 1.0 / width]])
865
866 for i in xrange(len(length_plan_t)):
867 xva_plan[0, i] = length_plan_x[i][0, 0]
868 xva_plan[1, i] = length_plan_v[i]
869 xva_plan[2, i] = length_plan_a[i]
870
871 xy_r = path.xy(xva_plan[0, i])
872 x_r = xy_r[0, 0]
873 y_r = xy_r[1, 0]
874 theta_r = path.theta(xva_plan[0, i])[0]
875 vel_omega_r = numpy.matrix(
876 [[xva_plan[1, i]],
877 [path.dtheta_dt(xva_plan[0, i], xva_plan[1, i])[0]]])
878 vel_lr = numpy.linalg.inv(Ter) * vel_omega_r
879
880 state_plan[:, i] = numpy.matrix(
881 [[x_r], [y_r], [theta_r], [vel_lr[0, 0]], [vel_lr[1, 0]]])
882 u_plan[:, i] = trajectory.ff_voltage(backward_accel_plan, xva_plan[0, i])
883
884 Q = numpy.matrix(
885 numpy.diag([
886 1.0 / (0.05**2), 1.0 / (0.05**2), 1.0 / (0.2**2), 1.0 / (0.5**2),
887 1.0 / (0.5**2)
888 ]))
889 R = numpy.matrix(numpy.diag([1.0 / (12.0**2), 1.0 / (12.0**2)]))
890 kMinVelocity = 0.1
891
892 for i in xrange(len(length_plan_t)):
893 states[:, i] = state
894
895 theta = state[2, 0]
896 sintheta = numpy.sin(theta)
897 costheta = numpy.cos(theta)
898 linear_velocity = (state[3, 0] + state[4, 0]) / 2.0
899 if abs(linear_velocity) < kMinVelocity / 100.0:
900 linear_velocity = 0.1
901 elif abs(linear_velocity) > kMinVelocity:
902 pass
903 elif linear_velocity > 0:
904 linear_velocity = kMinVelocity
905 elif linear_velocity < 0:
906 linear_velocity = -kMinVelocity
907
908 width = (velocity_drivetrain.robot_radius_l +
909 velocity_drivetrain.robot_radius_r)
910 A_linearized_continuous = numpy.matrix([[
911 0.0, 0.0, -sintheta * linear_velocity, 0.5 * costheta, 0.5 *
912 costheta
913 ], [
914 0.0, 0.0, costheta * linear_velocity, 0.5 * sintheta, 0.5 *
915 sintheta
916 ], [0.0, 0.0, 0.0, -1.0 / width, 1.0 / width],
917 [0.0, 0.0, 0.0, 0.0, 0.0],
918 [0.0, 0.0, 0.0, 0.0, 0.0]])
919 A_linearized_continuous[3:5, 3:5] = velocity_drivetrain.A_continuous
920 B_linearized_continuous = numpy.matrix(numpy.zeros((5, 2)))
921 B_linearized_continuous[3:5, :] = velocity_drivetrain.B_continuous
922
923 A, B = controls.c2d(A_linearized_continuous, B_linearized_continuous,
924 dt)
925
926 if i >= 0:
927 K = controls.dlqr(A, B, Q, R)
928 print("K", K)
929 print("eig", numpy.linalg.eig(A - B * K)[0])
930 goal_state = trajectory.goal_state(xva_plan[0, i], xva_plan[1, i])
931 state_error = goal_state - state
932
933 U = (trajectory.ff_voltage(backward_accel_plan, xva_plan[0, i]) + K *
934 (state_error))
935
936 def spline_diffeq(U, t, x):
937 velocity = x[3:5, :]
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100938 theta = x[2, 0]
939 linear_velocity = (velocity[0, 0] + velocity[1, 0]) / 2.0
940 angular_velocity = (velocity[1, 0] - velocity[0, 0]) / (
941 velocity_drivetrain.robot_radius_l +
942 velocity_drivetrain.robot_radius_r)
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100943 accel = (velocity_drivetrain.A_continuous * velocity +
944 velocity_drivetrain.B_continuous * U)
945 return numpy.matrix(
946 [[numpy.cos(theta) * linear_velocity],
947 [numpy.sin(theta) * linear_velocity], [angular_velocity],
948 [accel[0, 0]], [accel[1, 0]]])
949
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100950 full_us[:, i] = U
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100951
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100952 state = RungeKutta(lambda t, x: spline_diffeq(U, t, x),
953 state, i * dt, dt)
954
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100955 pylab.figure()
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100956 pylab.plot(length_plan_t, numpy.array(xva_plan)[0, :], label='x')
957 pylab.plot(length_plan_t, [x[1, 0] for x in length_plan_x], label='v')
958 pylab.plot(length_plan_t, numpy.array(xva_plan)[1, :], label='planv')
959 pylab.plot(length_plan_t, numpy.array(xva_plan)[2, :], label='a')
960
961 pylab.plot(length_plan_t, numpy.array(full_us)[0, :], label='vl')
962 pylab.plot(length_plan_t, numpy.array(full_us)[1, :], label='vr')
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100963 pylab.legend()
964
965 pylab.figure()
966 pylab.plot(
Austin Schuh7b1e9df2018-12-19 18:04:41 +1100967 numpy.array(states)[0, :],
968 numpy.array(states)[1, :],
969 label='robot')
970 pylab.plot(
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100971 numpy.array(spline_points)[0, :],
972 numpy.array(spline_points)[1, :],
973 label='spline')
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100974 pylab.legend()
975
Austin Schuh8cb98eb2018-12-05 22:06:45 +1100976
977 def a(_, x):
978 return 2.0
979 return 2.0 + 0.0001 * x
980
981 v = 0.0
982 for _ in xrange(10):
983 dx = 4.0 / 10.0
984 v = integrate_accel_for_distance(a, v, 0.0, dx)
985 print('v', v)
986
Austin Schuh35d19872018-11-30 15:50:47 +1100987 pylab.show()
988
989
990if __name__ == '__main__':
991 argv = FLAGS(sys.argv)
992 sys.exit(main(argv))