纯跟踪横向控制和算法仿真实现

文章目录

    • 1. Pure Pursuit
    • 2. 算法原理
    • 3. 算法和仿真实现

1. Pure Pursuit

Pure Pursuit是一种几何跟踪控制算法,也被称为纯跟踪控制算法。他的思想就是基于当前车辆的后轮中心的位置,在参考路径上寻找一个预瞄点,假设车辆可按照一定转弯半径下行驶到该目标点,然后根据车辆当前位置到预瞄点距离、转弯半径和预瞄点与车头朝向夹角的几何关系来计算车辆的前轮转角,即控制车辆的横向跟踪误差。

2. 算法原理

纯跟踪横向控制和算法仿真实现_第1张图片

其中

  • P P P:当前车辆的预瞄点
  • l d l_d ld:辆后轴中心点 A A A F F F的距离,即预瞄距离
  • θ \theta θ l d l_d ld与车轴的夹角
  • φ \varphi φ:车辆的航向角
  • e y e_y ey:预瞄点与车辆横向偏差
  • L L L:轴距
  • R R R:纯跟踪的目标转弯半径
  • δ f \delta_f δf:前轮转角

由图中的三角形几何关系可得

s i n ( 2 θ ) l d = s i n ( π 2 − θ ) R (1) \frac{sin(2\theta)}{l_d} = \frac{sin(\frac{\pi}{2} - \theta)}{R} \tag{1} ldsin(2θ)=Rsin(2πθ)(1)

化简后为

R = l d 2 s i n θ (2) R=\frac{l_d}{2sin\theta} \tag{2} R=2sinθld(2)

由简化的车辆运动学模型和上图中的几何关系可得

t a n δ f = L R (3) tan\delta_f=\frac{L}{R} \tag{3} tanδf=RL(3)

由(2)和(3)可得

δ f = a r c t a n L R = a r c t a n 2 L s i n θ l d (4) \delta_f = arctan\frac{L}{R}=arctan\frac{2Lsin\theta}{l_d} \tag{4} δf=arctanRL=arctanld2Lsinθ(4)

θ \theta θ l d l_d ld与车轴的夹角, e y e_y ey为预瞄点与车辆横向偏差,结合图中几何关系可得

s i n θ = e y l d (5) sin\theta = \frac{e_y}{l_d} \tag{5} sinθ=ldey(5)

因此(4)可转换为

δ f = a r c t a n 2 L s i n θ l d = a r c t a n 2 L e y l d 2 (6) \delta_f =arctan\frac{2Lsin\theta}{l_d} = arctan\frac{2Le_y}{l_d^2} \tag{6} δf=arctanld2Lsinθ=arctanld22Ley(6)

由上式可知,纯跟踪控制的效果取决于预瞄距离 l d l_d ld的选取,预瞄距离越长,前轮转角 δ f \delta_f δf变化会越小,控制效果会越平滑,预瞄距离越短,控制效果会更精确,但也会带来一定的震荡。由于车速越快单位时间内车辆移动距离会越长,我们选取的预瞄距离应该更远,因此对于预瞄距离 l d l_d ld的选取应该与车辆的速度 v v v成正比,一般情况下,我们将预瞄距离与车速的关系选取为以下形式:

l d = k v + l f c (7) l_d=kv+l_{fc} \tag{7} ld=kv+lfc(7)

其中 k k k为预瞄距离系数, l f c l_{fc} lfc为预设距离。

3. 算法和仿真实现

pure_pursuit.py


import numpy as np
import math

k = 0.1  # 预瞄距离系数
Lfc = 3.0  # 初始预瞄距离

class TargetCourse:

    def __init__(self, cx, cy):
        self.cx = cx
        self.cy = cy
        self.old_nearest_point_index = None

    def search_target_index(self, vehicle):

        if self.old_nearest_point_index is None:
            # 搜索距离车辆最近的点
            dx = [vehicle.x - icx for icx in self.cx]
            dy = [vehicle.y - icy for icy in self.cy]
            d = np.hypot(dx, dy)
            ind = np.argmin(d)
            self.old_nearest_point_index = ind
        else:
            ind = self.old_nearest_point_index
            distance_this_index = math.hypot(self.cx[ind] - vehicle.x, self.cy[ind] - vehicle.y)
            while True:
                distance_next_index = math.hypot(self.cx[ind+1] - vehicle.x, self.cy[ind+1] - vehicle.y)
                if distance_this_index < distance_next_index:
                    break
                ind = ind + 1 if (ind + 1) < len(self.cx) else ind
                distance_this_index = distance_next_index
            self.old_nearest_point_index = ind

        Lf = k * vehicle.v + Lfc  # 根据速度更新预瞄距离

        # 搜索预瞄点索引
        while Lf > math.hypot(self.cx[ind] - vehicle.x, self.cy[ind] - vehicle.y):
            if (ind + 1) >= len(self.cx):
                break
            ind += 1

        return ind, Lf


def pure_pursuit_steer_control(vehicle, trajectory, pind):
    ind, Lf = trajectory.search_target_index(vehicle)

    if pind >= ind:
        ind = pind

    if ind < len(trajectory.cx):
        tx = trajectory.cx[ind]
        ty = trajectory.cy[ind]
    else:  # toward goal
        tx = trajectory.cx[-1]
        ty = trajectory.cy[-1]
        ind = len(trajectory.cx) - 1

    alpha = math.atan2(ty - vehicle.y, tx - vehicle.x) - vehicle.yaw
    delta = math.atan2(2.0 * vehicle.L * math.sin(alpha) , Lf)

    return delta, ind

bicycle_model.py

import math
import numpy as np

class Vehicle:
    def __init__(self,
                 x=0.0,
                 y=0.0,
                 yaw=0.0,
                 v=0.0,
                 dt=0.1,
                 l=3.0):
        self.steer = 0
        self.x = x
        self.y = y
        self.yaw = yaw
        self.v = v
        self.dt = dt
        self.L = l  # 轴距
        self.x_front = x + l * math.cos(yaw)
        self.y_front = y + l * math.sin(yaw)

    def update(self, a, delta, max_steer=np.pi):
        delta = np.clip(delta, -max_steer, max_steer)
        self.steer = delta

        self.x = self.x + self.v * math.cos(self.yaw) * self.dt
        self.y = self.y + self.v * math.sin(self.yaw) * self.dt
        self.yaw = self.yaw + self.v / self.L * math.tan(delta) * self.dt

        self.v = self.v + a * self.dt
        self.x_front = self.x + self.L * math.cos(self.yaw)
        self.y_front = self.y + self.L * math.sin(self.yaw)


class VehicleInfo:
    # Vehicle parameter
    L = 3.0  #轴距
    W = 2.0  #宽度
    LF = 3.8  #后轴中心到车头距离
    LB = 0.8  #后轴中心到车尾距离
    MAX_STEER = 0.6  # 最大前轮转角
    TR = 0.5  # 轮子半径
    TW = 0.5  # 轮子宽度
    WD = W  #轮距
    LENGTH = LB + LF  # 车辆长度

def draw_trailer(x, y, yaw, steer, ax, vehicle_info=VehicleInfo, color='black'):
    vehicle_outline = np.array(
        [[-vehicle_info.LB, vehicle_info.LF, vehicle_info.LF, -vehicle_info.LB, -vehicle_info.LB],
         [vehicle_info.W / 2, vehicle_info.W / 2, -vehicle_info.W / 2, -vehicle_info.W / 2, vehicle_info.W / 2]])

    wheel = np.array([[-vehicle_info.TR, vehicle_info.TR, vehicle_info.TR, -vehicle_info.TR, -vehicle_info.TR],
                      [vehicle_info.TW / 2, vehicle_info.TW / 2, -vehicle_info.TW / 2, -vehicle_info.TW / 2, vehicle_info.TW / 2]])

    rr_wheel = wheel.copy() #右后轮
    rl_wheel = wheel.copy() #左后轮
    fr_wheel = wheel.copy() #右前轮
    fl_wheel = wheel.copy() #左前轮
    rr_wheel[1,:] += vehicle_info.WD/2
    rl_wheel[1,:] -= vehicle_info.WD/2

    #方向盘旋转
    rot1 = np.array([[np.cos(steer), -np.sin(steer)],
                     [np.sin(steer), np.cos(steer)]])
    #yaw旋转矩阵
    rot2 = np.array([[np.cos(yaw), -np.sin(yaw)],
                     [np.sin(yaw), np.cos(yaw)]])
    fr_wheel = np.dot(rot1, fr_wheel)
    fl_wheel = np.dot(rot1, fl_wheel)
    fr_wheel += np.array([[vehicle_info.L], [-vehicle_info.WD / 2]])
    fl_wheel += np.array([[vehicle_info.L], [vehicle_info.WD / 2]])

    fr_wheel = np.dot(rot2, fr_wheel)
    fr_wheel[0, :] += x
    fr_wheel[1, :] += y
    fl_wheel = np.dot(rot2, fl_wheel)
    fl_wheel[0, :] += x
    fl_wheel[1, :] += y
    rr_wheel = np.dot(rot2, rr_wheel)
    rr_wheel[0, :] += x
    rr_wheel[1, :] += y
    rl_wheel = np.dot(rot2, rl_wheel)
    rl_wheel[0, :] += x
    rl_wheel[1, :] += y
    vehicle_outline = np.dot(rot2, vehicle_outline)
    vehicle_outline[0, :] += x
    vehicle_outline[1, :] += y

    ax.plot(fr_wheel[0, :], fr_wheel[1, :], color)
    ax.plot(rr_wheel[0, :], rr_wheel[1, :], color)
    ax.plot(fl_wheel[0, :], fl_wheel[1, :], color)
    ax.plot(rl_wheel[0, :], rl_wheel[1, :], color)

    ax.plot(vehicle_outline[0, :], vehicle_outline[1, :], color)
    ax.axis('equal')

main.py

from bicycle_model import Vehicle, VehicleInfo, draw_trailer
from pure_pursuit import pure_pursuit_steer_control, TargetCourse
import numpy as np
import matplotlib.pyplot as plt
import math
import imageio

MAX_SIMULATION_TIME = 200.0  # 程序最大运行时间200*dt

def NormalizeAngle(angle):
    a = math.fmod(angle + np.pi, 2 * np.pi)
    if a < 0.0:
        a += (2.0 * np.pi)
    return a - np.pi

# 计算距离车辆最近的参考点索引,用于计算横向误差
def calNearestPointIndex(vehicle, ref_path):
    dx = [vehicle.x - icx for icx in ref_path[:, 0]]
    dy = [vehicle.y - icy for icy in ref_path[:, 1]]
    d = np.hypot(dx, dy)
    index = np.argmin(d)
    return index
def main():
    # 设置跟踪轨迹
    ref_path = np.zeros((1000, 2))
    ref_path[:, 0] = np.linspace(0, 50, 1000)  # x坐标
    ref_path[:, 1] = 10 * np.sin(ref_path[:, 0] / 20.0)  # y坐标
    ref = TargetCourse(ref_path[:, 0], ref_path[:, 1])
    # 假设车辆初始位置为(0,0),航向角yaw=pi/2,速度为2m/s,时间周期dt为0.1秒
    vehicle = Vehicle(x=0.0,
                      y=0.0,
                      yaw=np.pi/2,
                      v=2.0,
                      dt=0.1,
                      l=VehicleInfo.L)

    ind, target_ind = ref.search_target_index(vehicle)
    time = 0.0  # 初始时间

    # 记录车辆轨迹
    trajectory_x = []
    trajectory_y = []
    lat_err = []  # 记录横向误差

    i = 0
    image_list = []  # 存储图片
    plt.figure(1)

    last_idx = ref_path.shape[0] - 1  # 跟踪轨迹的最后一个点的索引
    while MAX_SIMULATION_TIME >= time and last_idx > target_ind:
        time += vehicle.dt  # 累加一次时间周期

        # 纯跟踪
        delta_f, target_ind = pure_pursuit_steer_control(vehicle, ref, target_ind)

        # 横向误差计算
        nearest_index = calNearestPointIndex(vehicle, ref_path)
        vehicle_positon = np.zeros(2)
        vehicle_positon[0] = vehicle.x
        vehicle_positon[1] = vehicle.y
        alpha = math.atan2(
            ref_path[nearest_index, 1] - vehicle_positon[1], ref_path[nearest_index, 0] - vehicle_positon[0])
        l_d = np.linalg.norm(ref_path[nearest_index] - vehicle_positon)  # 最近点与车定位点距离l_d

        theta_e = NormalizeAngle(alpha - vehicle.yaw)
        e_y = l_d * math.sin(theta_e)  # 计算实际误差,0为目标距离
        lat_err.append(e_y)

        # 更新车辆状态
        vehicle.update(0.0, delta_f, np.pi / 10)  # 由于假设纵向匀速运动,所以加速度a=0.0
        trajectory_x.append(vehicle.x)
        trajectory_y.append(vehicle.y)

        # 显示动图
        plt.cla()
        plt.plot(ref_path[:, 0], ref_path[:, 1], '-.b', linewidth=1.0)
        draw_trailer(vehicle.x, vehicle.y, vehicle.yaw, vehicle.steer, plt)

        plt.plot(trajectory_x, trajectory_y, "-r", label="trajectory")
        plt.plot(ref_path[target_ind, 0], ref_path[target_ind, 1], "go", label="target")
        plt.axis("equal")
        plt.grid(True)
        plt.pause(0.001)
    #     plt.savefig("temp.png")
    #     i += 1
    #     if (i % 50) > 0:
    #         image_list.append(imageio.imread("temp.png"))
    #
    # imageio.mimsave("display.gif", image_list, duration=0.1)

    plt.figure(2)
    plt.subplot(2, 1, 1)
    plt.plot(ref_path[:, 0], ref_path[:, 1], '-.b', linewidth=1.0)
    plt.plot(trajectory_x, trajectory_y, 'r')
    plt.title("actual tracking effect")

    plt.subplot(2, 1, 2)
    plt.plot(lat_err)
    plt.title("lateral error")
    plt.show()


if __name__ == '__main__':
    main()

运行效果:

控制效果和横向误差:
纯跟踪横向控制和算法仿真实现_第2张图片

文章首发公众号:iDoitnow如果喜欢话,可以关注一下

你可能感兴趣的:(自动驾驶-控制,算法,纯跟踪,横向控制,Pure,Pursuit,自动驾驶)