当前位置:   article > 正文

自动驾驶算法详解(3): LQR算法进行轨迹跟踪,lqr_speed_steering_control( )的python实现

自动驾驶算法详解(3): LQR算法进行轨迹跟踪,lqr_speed_steering_control( )的python实现

前言:

LQR算法在自动驾驶应用中,一般用在NOP、TJA、LCC这些算法的横向控制中,一般与曲率的前馈控制一起使用,来实现轨迹跟踪的目标,通过控制方向盘转角来实现横向控制。

本文将使用python来实现 lqr_speed_steering_control( ) 轨迹跟踪算法的demo,通过同时控制转角与加速度来实现轨迹跟踪。

如果对自动驾驶规划、控制、apollo算法细节、感知融合算法感兴趣,可以关注我的主页:

https://blog.csdn.net/nn243823163/category_11685852.htmlhttps://blog.csdn.net/nn243823163/category_11685852.html

最新免费文章推荐:

prescan联合simulink进行FCW的仿真_自动驾驶 Player的博客-CSDN博客

Apollo Planning决策规划代码详细解析 (1):Scenario选择

自动驾驶算法详解 (1) : Apollo路径规划 Piecewise Jerk Path Optimizer的python实现

自动驾驶算法详解(5): 贝塞尔曲线进行路径规划的python实现

使用Vscode断点调试apollo的方法_自动驾驶 Player的博客-CSDN博客

Apollo规划决策算法仿真调试(1): 使用Vscode断点调试apollo的方法

Apollo规划决策算法仿真调试(4):动态障碍物绕行_自动驾驶 Player的博客-CSDN博客

正文如下:

一、LQR问题模型建立:

理论部分比较成熟,这里只介绍demo所使用的建模方程:

使用离散代数黎卡提方程求解

 

LQR控制的步骤:

选择参数矩阵Q,R
求解Riccati方程得到矩阵P
根据P计算 K = R − 1 B T P K=R^{-1}B^{T}P K=R−1BTP
计算控制量 u = − K x u=-Kx u=−Kx

系统状态矩阵:

 输入矩阵:

 A矩阵:

 B矩阵:

 二、代码实现

  1. # 导入相关包
  2. import math
  3. import sys
  4. import os
  5. import matplotlib.pyplot as plt
  6. import numpy as np
  7. import scipy.linalg as la
  8. # cubic_spline_planner为自己实现的三次样条插值方法
  9. try:
  10.     from cubic_spline_planner import *
  11. except ImportError:
  12.     raise

设置轨迹途经点并生成轨迹:

  1. # 设置轨迹会经过的点
  2. ax = [0.0, 6.0, 12.5, 10.0, 17.5, 20.0, 25.0]
  3. ay = [0.0, -3.0, -5.0, 6.5, 3.0, 0.0, 0.0]
  4. goal = [ax[-1], ay[-1]]
  5. # 使用三次样条插值方法,根据途经点生成轨迹,x、y、yaw、曲率k,距离s
  6. cx, cy, cyaw, ck, s = calc_spline_course(
  7.         ax, ay, ds=0.1)
  8. # 绘制规划好的轨迹
  9. plt.plot(ax, ay, "xb", label="waypoints")
  10. plt.plot(cx, cy, "-r", label="target course")

生成的轨迹如下:

  

设置期望速度:

  1. # 设置目标速度
  2. target_speed = 10.0 / 3.6  # simulation parameter km/h -> m/s
  3. speed_profile = [target_speed] * len(cyaw)
  4. direction = 1.0
  5. # 转弯幅度较大时将速度设置为0,并将速度方向翻转
  6. # Set stop point
  7. for i in range(len(cyaw) - 1):
  8.     dyaw = abs(cyaw[i + 1] - cyaw[i])
  9.     switch = math.pi / 4.0 <= dyaw < math.pi / 2.0
  10.     if switch:
  11.         direction *= -1
  12.     if direction != 1.0:
  13.         speed_profile[i] = - target_speed
  14.     else:
  15.         speed_profile[i] = target_speed
  16.     if switch:
  17.         speed_profile[i] = 0.0
  18. # 靠近目的地时,速度降低       
  19. # speed down
  20. for i in range(40):
  21.     speed_profile[-i] = target_speed / (50 - i)
  22.     if speed_profile[-i] <= 1.0 / 3.6:
  23.         speed_profile[-i] = 1.0 / 3.6
  24. plt.plot(speed_profile, "-b", label="speed_profile")

期望速度如下:

 定义求解所需要的数据结构与方法:

  1. # 定义LQR 计算所需要的数据结构,以及DLQR的求解方法
  2. # State 对象表示自车的状态,位置x、y,以及横摆角yaw、速度v
  3. class State:
  4.     def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0):
  5.         self.x = x
  6.         self.y = y
  7.         self.yaw = yaw
  8.         self.v = v
  9. # 更新自车的状态,采样时间足够小,则认为这段时间内速度相同,加速度相同,使用匀速模型更新位置
  10. def update(state, a, delta):
  11.     if delta >= max_steer:
  12.         delta = max_steer
  13.     if delta <= - max_steer:
  14.         delta = - max_steer
  15.     state.x = state.x + state.v * math.cos(state.yaw) * dt
  16.     state.y = state.y + state.v * math.sin(state.yaw) * dt
  17.     state.yaw = state.yaw + state.v / L * math.tan(delta) * dt
  18.     state.v = state.v + a * dt
  19.     return state
  20. def pi_2_pi(angle):
  21.     return (angle + math.pi) % (2 * math.pi) - math.pi
  22. # 实现离散Riccati equation 的求解方法
  23. def solve_dare(A, B, Q, R):
  24.     """
  25.     solve a discrete time_Algebraic Riccati equation (DARE)
  26.     """
  27.     x = Q
  28.     x_next = Q
  29.     max_iter = 150
  30.     eps = 0.01
  31.     for i in range(max_iter):
  32.         x_next = A.T @ x @ A - A.T @ x @ B @ \
  33.                 la.inv(R + B.T @ x @ B) @ B.T @ x @ A + Q
  34.         if (abs(x_next - x)).max() < eps:
  35.             break
  36.         x = x_next
  37.     return x_next
  38. # 返回值K 即为LQR 问题求解方法中系数K的解
  39. def dlqr(A, B, Q, R):
  40.     """Solve the discrete time lqr controller.
  41.     x[k+1] = A x[k] + B u[k]
  42.     cost = sum x[k].T*Q*x[k] + u[k].T*R*u[k]
  43.     # ref Bertsekas, p.151
  44.     """
  45.     # first, try to solve the ricatti equation
  46.     X = solve_dare(A, B, Q, R)
  47.     # compute the LQR gain
  48.     K = la.inv(B.T @ X @ B + R) @ (B.T @ X @ A)
  49.     eig_result = la.eig(A - B @ K)
  50.     return K, X, eig_result[0]
  51. # 计算距离自车当前位置最近的参考点
  52. def calc_nearest_index(state, cx, cy, cyaw):
  53.     dx = [state.x - icx for icx in cx]
  54.     dy = [state.y - icy for icy in cy]
  55.     d = [idx ** 2 + idy ** 2 for (idx, idy) in zip(dx, dy)]
  56.     mind = min(d)
  57.     ind = d.index(mind)
  58.     mind = math.sqrt(mind)
  59.     dxl = cx[ind] - state.x
  60.     dyl = cy[ind] - state.y
  61.     angle = pi_2_pi(cyaw[ind] - math.atan2(dyl, dxl))
  62.     if angle < 0:
  63.         mind *= -1
  64.     return ind, mind

设置起点参数:

  1. # 设置起点的参数
  2. T = 500.0  # max simulation time
  3. goal_dis = 0.3
  4. stop_speed = 0.05
  5. state = State(x=-0.0, y=-0.0, yaw=0.0, v=0.0)
  6. time = 0.0
  7. x = [state.x]
  8. y = [state.y]
  9. yaw = [state.yaw]
  10. v = [state.v]
  11. t = [0.0]
  12. pe, pth_e = 0.0, 0.0

使用LQR算法计算轨迹跟踪需要的加速度与前轮转角:

  1. # 配置LQR 的参数
  2. # === Parameters =====
  3. # LQR parameter
  4. lqr_Q = np.eye(5)
  5. lqr_R = np.eye(2)
  6. dt = 0.1  # time tick[s],采样时间
  7. L = 0.5  # Wheel base of the vehicle [m],车辆轴距
  8. max_steer = np.deg2rad(45.0# maximum steering angle[rad]
  9. show_animation = True
  10. while T >= time:
  11.     ind, e = calc_nearest_index(state, cx, cy, cyaw)
  12.     sp = speed_profile
  13.     tv = sp[ind]
  14.     k = ck[ind]
  15.     v_state = state.v
  16.     th_e = pi_2_pi(state.yaw - cyaw[ind])
  17.     # 构建LQR表达式,X(k+1) = A * X(k) + B * u(k), 使用Riccati equation 求解LQR问题
  18. #    dt表示采样周期,v表示当前自车的速度
  19. #    A = [1.0, dt, 0.0, 0.0, 0.0
  20. #          0.0, 0.0, v, 0.0, 0.0]
  21. #          0.0, 0.0, 1.0, dt, 0.0]
  22. #          0.0, 0.0, 0.0, 0.0, 0.0]
  23. #          0.0, 0.0, 0.0, 0.0, 1.0]
  24.     A = np.zeros((5, 5))
  25.     A[0, 0] = 1.0
  26.     A[0, 1] = dt
  27.     A[1, 2] = v_state
  28.     A[2, 2] = 1.0
  29.     A[2, 3] = dt
  30.     A[4, 4] = 1.0
  31.     # 构建B矩阵,L是自车的轴距
  32.     # B = [0.0, 0.0
  33.     #    0.0, 0.0
  34.     #    0.0, 0.0
  35.     #    v/L, 0.0
  36.     #    0.0, dt]
  37.     B = np.zeros((5, 2))
  38.     B[3, 0] = v_state / L
  39.     B[4, 1] = dt
  40.     K, _, _ = dlqr(A, B, lqr_Q, lqr_R)
  41.     # state vector,构建状态矩阵
  42.     # x = [e, dot_e, th_e, dot_th_e, delta_v]
  43.     # e: lateral distance to the path, e是自车到轨迹的距离
  44.     # dot_e: derivative of e, dot_e是自车到轨迹的距离的变化率
  45.     # th_e: angle difference to the path, th_e是自车与期望轨迹的角度偏差
  46.     # dot_th_e: derivative of th_e, dot_th_e是自车与期望轨迹的角度偏差的变化率
  47.     # delta_v: difference between current speed and target speed,delta_v是当前车速与期望车速的偏差
  48.     X = np.zeros((5, 1))
  49.     X[0, 0] = e
  50.     X[1, 0] = (e - pe) / dt
  51.     X[2, 0] = th_e
  52.     X[3, 0] = (th_e - pth_e) / dt
  53.     X[4, 0] = v_state - tv
  54.     # input vector,构建输入矩阵u
  55.     # u = [delta, accel]
  56.     # delta: steering angle,前轮转角
  57.     # accel: acceleration,自车加速度
  58.     ustar = -K @ X
  59.     # calc steering input
  60.     ff = math.atan2(L * k, 1# feedforward steering angle
  61.     fb = pi_2_pi(ustar[0, 0])  # feedback steering angle
  62.     delta = ff + fb
  63.     # calc accel input
  64.     accel = ustar[1, 0]
  65.     dl, target_ind, pe, pth_e, ai = delta, ind, e, th_e, accel
  66.     state = update(state, ai, dl)
  67.     if abs(state.v) <= stop_speed:
  68.         target_ind += 1
  69.     time = time + dt
  70.     # check goal
  71.     dx = state.x - goal[0]
  72.     dy = state.y - goal[1]
  73.     if math.hypot(dx, dy) <= goal_dis:
  74.         print("Goal")
  75.         break
  76.     x.append(state.x)
  77.     y.append(state.y)
  78.     yaw.append(state.yaw)
  79.     v.append(state.v)
  80.     t.append(time)
  81.     if target_ind % 100 == 0 and show_animation:
  82.         plt.cla()
  83.         # for stopping simulation with the esc key.
  84.         plt.gcf().canvas.mpl_connect('key_release_event',
  85.                 lambda event: [exit(0) if event.key == 'escape' else None])
  86.         plt.plot(cx, cy, "-r", label="course")
  87.         plt.plot(x, y, "ob", label="trajectory")
  88.         plt.plot(cx[target_ind], cy[target_ind], "xg", label="target")
  89.         plt.axis("equal")
  90.         plt.grid(True)
  91.         plt.title("speed[km/h]:" + str(round(state.v * 3.6, 2))
  92.                   + ",target index:" + str(target_ind) + ", time si: " + str(time))
  93.         plt.pause(0.1)

结果可视化:

  1. if show_animation:  # pragma: no cover
  2.         plt.close()
  3.         plt.subplots(1)
  4.         plt.plot(ax, ay, "xb", label="waypoints")
  5.         plt.plot(cx, cy, "-r", label="target course")
  6.         plt.plot(x, y, "-g", label="tracking")
  7.         plt.grid(True)
  8.         plt.axis("equal")
  9.         plt.xlabel("x[m]")
  10.         plt.ylabel("y[m]")
  11.         plt.legend()
  12.         plt.subplots(1)
  13.         plt.plot(s, [np.rad2deg(iyaw) for iyaw in cyaw], "-r", label="yaw")
  14.         plt.grid(True)
  15.         plt.legend()
  16.         plt.xlabel("line length[m]")
  17.         plt.ylabel("yaw angle[deg]")
  18.         plt.subplots(1)
  19.         plt.plot(s, ck, "-r", label="curvature")
  20.         plt.grid(True)
  21.         plt.legend()
  22.         plt.xlabel("line length[m]")
  23.         plt.ylabel("curvature [1/m]")
  24.         plt.show()

轨迹跟踪结果:

 三、结果分析

LQR算法一般用在NOP、TJA、LCC这些功能的横向控制,几种典型工况的轨迹跟踪效果如下:

1、正常变道工况 

2、转弯工况

 3、轴距对控制效果的影响

L = 0.5

 L = 2.5

声明:本文内容由网友自发贡献,不代表【wpsshop博客】立场,版权归原作者所有,本站不承担相应法律责任。如您发现有侵权的内容,请联系我们。转载请注明出处:https://www.wpsshop.cn/w/小丑西瓜9/article/detail/510270
推荐阅读
相关标签
  

闽ICP备14008679号