论文解读 - 城市自动驾驶车辆运动规划与控制技术综述 (第5部分,完结篇)

news2024/12/26 21:10:45

文章目录

  • 🚗 V. Vehicle Control(车辆控制)
    • 🔴 A. Path Stabilization for the Kinematic Model(基于运动学模型的路径稳定)
      • 🟥 1)Pure Pursuit(纯追踪)
      • 🟧 2)Rear wheel position based feedback(基于后轮位置的反馈)
      • 🟨 3)Front wheel position based feedback(基于前轮位置的反馈)
    • 🟠 B. Trajectory Tracking Control for the Kinematic Model(基于运动学模型的轨迹跟踪控制)
      • 🟥 1)Control Lyapunov based design(基于控制李雅普诺夫函数的设计)
      • 🟧 2)Output feedback linearization(输出反馈线性化)
    • 🟡 C. Predictive Control Approaches(预测控制方法)
    • 🟢 D. Linear Parameter Varying Controllers(线性变参数控制)
  • 🚚 VI. Conclusions(结论)

🚗 V. Vehicle Control(车辆控制)

Solutions to Problem IV.1 or IV.2 are provided by the motion planning process. The role of the feedback controller is to stabilize to the reference path or trajectory in the presence of modeling error and other forms of uncertainty. Depending on the reference provided by the motion planner, the control objective may be path stabilization or trajectory stabilization. More formally, the path stabilization problem is stated as follows:
运动规划过程提供了问题IV.1或IV.2的解。反馈控制器的作用是,在存在建模误差和其他形式的不确定性的情况下,稳定于参考路径或轨迹。根据运动规划器提供的参考,控制目标可以是路径稳定或轨迹稳定。更正式地说,路径稳定问题表述如下:

Problem V.1. (Path stabilization) Given a controlled differential equation x ˙ = f ( x , u ) \dot{x}=f(x, u) x˙=f(x,u), reference path x ref  : R → R n x_{\text {ref }}: \mathbb{R} \rightarrow \mathbb{R}^n xref :RRn, and velocity v ref  :   R → R v_{\text {ref }}: \ \mathbb{R} \rightarrow \mathbb{R} vref : RR, find a feedback law, u ( x ) u(x) u(x), such that solutions to x ˙ = f ( x , u ( x ) ) \dot{x}=f(x, u(x)) x˙=f(x,u(x))satisfy the following: ∀ ϵ > 0 , t 1 < t 2 \forall \epsilon>0, t_1<t_2 ϵ>0,t1<t2, there exists a δ > 0 \delta>0 δ>0 and a differentiable S : R → R S: \mathbb{R} \rightarrow \mathbb{R} S:RR such that
问题 V.1 路径稳定:
给定受控微分方程 x ˙ = f ( x , u ) \dot{x}=f(x, u) x˙=f(x,u) ,参考路径 x ref  : R → R n x_{\text {ref }}: \mathbb{R} \rightarrow \mathbb{R}^n xref :RRn,以及参考速度 v ref  :   R → R v_{\text {ref }}: \ \mathbb{R} \rightarrow \mathbb{R} vref : RR ,找到一个反馈律 u ( x ) u(x) u(x),使得 x ˙ = f ( x , u ( x ) ) \dot{x}=f(x, u(x)) x˙=f(x,u(x)) 的解满足如下命题:对于 ∀ ϵ > 0 , t 1 < t 2 \forall \epsilon>0, t_1<t_2 ϵ>0,t1<t2 ,总是存在 δ > 0 \delta>0 δ>0 以及可微分的 S : R → R S: \mathbb{R} \rightarrow \mathbb{R} S:RR ,使得
1 ) → ∥ x ( t 1 ) − x ref  ( s ( t 1 ) ) ∥ ≤ δ ⟹ ∥ x ( t 2 ) − x ref  ( s ( t 2 ) ) ∥ ≤ ϵ 2 ) → lim ⁡ t → ∞ ∥ x ( t ) − x ref  ( s ( t ) ) ∥ = 0 3 ) → lim ⁡ t → ∞ s ˙ ( t ) = v ref  ( s ( t ) ) \begin{aligned} & 1) \rightarrow\left\|x\left(t_1\right)-x_{\text {ref }}\left(s\left(t_1\right)\right)\right\| \leq \delta \quad \Longrightarrow\left\|x\left(t_2\right)-x_{\text {ref }}\left(s\left(t_2\right)\right)\right\| \leq \epsilon \\ & 2) \rightarrow \lim _{t \rightarrow \infty}\left\|x(t)-x_{\text {ref }}(s(t))\right\|=0 \\ & 3) \rightarrow \lim _{t \rightarrow \infty} \dot{s}(t)=v_{\text {ref }}(s(t))\end{aligned} 1)x(t1)xref (s(t1))δx(t2)xref (s(t2))ϵ2)tlimx(t)xref (s(t))=03)tlims˙(t)=vref (s(t))

Qualitatively, these conditions are that (1) a small initial tracking error will remain small, (2) the tracking error must converge to zero, and (3) progress along the reference path tends to a nominal rate.
定性地说,上述的条件表示:(1) 小的初始跟踪误差仍将保持小,(2) 跟踪误差必须收敛到零,(3) 沿着参考路径的行驶趋近于规定速率。

Many of the proposed vehicle control laws, including several discussed in this section, use a feedback law of the form
许多已被提出的车辆控制律,包括本节将要讨论的几个,都使用以下形式的反馈律:
u ( x ) = f ( arg ⁡ min ⁡ γ ∥ x − x r e f ( γ ) ∥ ) ( V . 1 ) u(x)=f\left(\arg \min _\gamma\left\|x-x_{r e f}(\gamma)\right\|\right) \quad(V.1) u(x)=f(argγminxxref(γ))(V.1)
where the feedback is a function of the nearest point on the reference path. An important issue with controls of this form is that the closed loop vector field f ( x , u ( x ) ) f(x, u(x)) f(x,u(x)) will not be continuous. If the path is self intersecting or not differentiable at some point, a discontinuity in which f ( x , u ( x ) ) f(x, u(x)) f(x,u(x)) is will lie directly on the path. This leads to unpredictable behavior if the executed trajectory encounters the discontinuity. This
discontinuity is illustrated in Figure V.1. A backstepping control design which does not use a feedback law of the form (V.1) is presented in [135].
其中反馈是参考路径上距车辆最近的点的函数。该形式的控制的一个重要问题是闭环向量场 f ( x , u ( x ) ) f(x, u(x)) f(x,u(x))非连续。如果路径是自相交的或在某一点不可微分,则 f ( x , u ( x ) ) f(x, u(x)) f(x,u(x)) 存在的不连续性将直接出现在路径上。若执行的轨迹存在不连续性,则将导致不可预测的行为。这种不连续性如图V.1所示。文章[135]提出了一种反推控制设计,其不使用公式(V.1)的反馈律。
在这里插入图片描述

图V.1:(V.5)的可视化,黑线表示参考路径的样例。平面上每个点的 s s s 值用颜色表示,这描绘了(V.5)中的不连续性。

The trajectory stabilization problem is more straightforward, but these controllers are prone to performance limitations [136].
轨迹稳定问题更加简单,但是这些控制器容易受到性能限制[136]。

Problem V.2. (Trajectory stabilization) Given a controlled differential equation x ˙ = f ( x , u ) \dot{x}=f(x, u) x˙=f(x,u) and a reference trajectory x r e f ( t ) x_{r e f}(t) xref(t), find π ( x ) \pi(x) π(x) such that solutions to x ˙ = f ( x , π ( x ) ) \dot{x}=f(x, \pi(x)) x˙=f(x,π(x)) satisfy the following: ∀ ϵ > 0 , t 1 < t 2 \forall \epsilon>0, t_1<t_2 ϵ>0,t1<t2, there exists a δ > 0 \delta>0 δ>0 such that
给定受控微分方程 x ˙ = f ( x , u ) \dot{x}=f(x, u) x˙=f(x,u) 和参考轨迹 x r e f ( t ) x_{r e f}(t) xref(t) ,找到 π ( x ) \pi(x) π(x) 使得 x ˙ = f ( x , π ( x ) ) \dot{x}=f(x, \pi(x)) x˙=f(x,π(x)) 的解满足如下命题:对于 ∀ ϵ > 0 , t 1 < t 2 \forall \epsilon>0, t_1<t_2 ϵ>0,t1<t2 ,总是存在 δ > 0 \delta>0 δ>0 ,使得
 1)  → ∥ x ( t 1 ) − x ref  ( t 1 ) ∥ ≤ δ ⇒ ∥ x ( t 2 ) − x ref  ( t 2 ) ∥ ≤ ϵ  2)  → lim ⁡ t → ∞ ∥ x ( t ) − x ref  ( t ) ∥ = 0 \begin{aligned} & \text { 1) } \rightarrow\left\|x\left(t_1\right)-x_{\text {ref }}\left(t_1\right)\right\| \leq \delta \\ & \quad \Rightarrow\left\|x\left(t_2\right)-x_{\text {ref }}\left(t_2\right)\right\| \leq \epsilon \\ & \text { 2) } \rightarrow \lim _{t \rightarrow \infty}\left\|x(t)-x_{\text {ref }}(t)\right\|=0 \end{aligned}  1) x(t1)xref (t1)δx(t2)xref (t2)ϵ 2) tlimx(t)xref (t)=0

In many cases, analyzing the stability of trajectories can be reduced to determining the origin’s stability in a time varying system. The basic form of Lyapunov’s theorem is only applicable to time invariant systems. However, stability theory for time varying systems is also well established (e.g. [137, Theorem 4.9]).
在许多情况下,分析轨迹的稳定性可以简化为确定时变系统的原点的稳定性。李雅普诺夫定理的基本形式仅适用于时不变系统。然而,时变系统的稳定性理论也得到了很好的建立(例如[137]的定理4.9)。

Some useful qualifiers for various types of stability include:
Uniform asymptotic stability for a time varying system which asserts that δ \delta δ in condition 1 of the above problem is independent of t 1 t_{1} t1.
Exponential stability asserts that the rate of convergence is bounded above by an exponential decay.
A delicate issue that should be noted is that controller specifications are usually expressed in terms of the asymptotic tracking error as time tends to infinity. In practice, reference trajectories are finite so there should also be consideration for the transient response of the system.
对于各种类型的稳定性,一些有用的术语包括:
时变系统的一致渐近稳定性,其断言上述问题的条件 1 中的 δ \delta δ 独立于 t 1 t_{1} t1
指数稳定性,其断言收敛速率以指数衰减为界。
需要注意的一个微妙问题是,当时间趋于无穷大时,控制器的规范通常用渐近跟踪误差来表示。在实践中,参考轨迹是有限的,因此还应当考虑系统的瞬态响应。

The remainder of this section is devoted to a survey of select control designs which are applicable to driverless cars. An overview of these controllers is provided in Table II.
Subsection V-A details a number of effective control strategies for path stabilization of the kinematic model, and subsection V-B2 discusses trajectory stabilization techniques. Predictive control strategies, discussed in subsection V-C, are effective for more complex vehicle models and can be applied to path and trajectory stabilization.
本节的剩余部分将选择一些适用于无人驾驶汽车的控制设计,并对其进行综述。表II提供了这些控制器的概述。第V-A小节详细介绍了用于运动学模型的路径稳定的一些有效控制策略。第V-B2小节讨论了轨迹稳定技术。第V-C小节将讨论的预测控制策略对于更复杂的车辆模型是有效的,可以应用于路径和轨迹稳定。
在这里插入图片描述

表II:本节讨论的控制器概述。 ☆: 局部指数稳定性(LES); *: 假设(5.1)是通过在路径或轨迹的 n 点离散化上的线性搜索来评估的; +: 假设使用内点法求解(5.28),其中时间范围/区间为 n ,解的精确度为 \epsilon ;ǂ: 基于使用最陡下降的、向(5.25)的局部最小值收敛的渐近收敛速率,不保证返回解或找到全局最小值; #: 由 R m \mathbb{R}^m Rm 中的各个输入定义的状态空间 R n \mathbb{R}^n Rn 上的向量场是连续可微分函数,从而定义关于参考的成本梯度或线性化。

🔴 A. Path Stabilization for the Kinematic Model(基于运动学模型的路径稳定)

🟥 1)Pure Pursuit(纯追踪)

Among the earliest proposed path tracking strategies is pure pursuit. The first discussion appeared in [138], and was elaborated upon in [52], [139]. This strategy and its variations (e.g. [140], [141]) have proven to be an indispensable tool for vehicle control owing to its simple implementation and satisfactory performance. Numerous publications including two vehicles in the DARPA Grand Challenge [8] and three vehicles in the DARPA Urban challenge [9] reported using the pure pursuit controller.
纯追踪算法是最早提出的路径跟踪(path tracking)策略之一。文章[138]中第一次讨论了它,并在[52][139]中进行了详细阐述。该策略及其变体(例如[140][141])已被证明是车辆控制不可或缺的工具,因为其实施简单且性能令人满意。许多相关成果,包括DARPA大挑战中的两辆车[8]和DARPA城市挑战中的三辆车[9]都报道使用了纯追踪器。

The control law is based on fitting a semi-circle through the vehicle’s current configuration to a point on the reference path ahead of the vehicle by a distance L called the lookahead distance. Figure V.2 illustrates the geometry. The circle is defined as passing through the position of the car and the point on the path ahead of the car by one lookahead distance with the circle tangent to the car’s heading. The curvature of the circle is given by
纯追踪的控制律的基本思想是,利用半圆弧来拟合从车辆当前构型到参考路径上特定一点,这个特定点在车辆前方、距离为 L ,称为前瞻距离。图V.2描述了这个几何结构。通过两个点和一个切线来定义这个圆:代表汽车所处位置的点、在该点处与车辆朝向方向相同的切线、车辆前方相距一个前瞻距离的参考路径上的点。圆的曲率由下式给出:
κ = 2 sin ⁡ α L ( V . 2 ) \kappa=\frac{2 \sin \alpha}{L} \quad(V.2) κ=L2sinα(V.2)

For a vehicle speed v r v_r vr, the commanded heading rate is
对于车辆速度 v r v_r vr ,指令的航向速率为
ω = 2 v r sin ⁡ α L ( V . 3 ) \omega=\frac{2 v_r \sin \alpha}{L} \quad(V.3) ω=L2vrsinα(V.3)
在这里插入图片描述

图V.2:纯追踪控制器的几何结构。一个圆(蓝色)位于后轮位置和参考路径(棕色)之间,使得弦长(绿色)为前瞻距离 L L L ,并且该圆与当前车辆的朝向方向相切。

In the original publication of this controller [138], the angle α \alpha α is computed directly from camera output data. However, α \alpha α can be expressed in terms of the inertial coordinate system to define a state feedback control. Consider the configuration ( x r , y r , θ ) T \left(x_r, y_r, \theta\right)^T (xr,yr,θ)T and the points on the path, ( x r e f ( s ) , y r e f ( s ) ) \left(x_{r e f}(s), y_{r e f}(s)\right) (xref(s),yref(s)), such that ∥ ( x ref  ( s ) , y ref  ( s ) ) − ( x r , y r ) ∥ = L \left\|\left(x_{\text {ref }}(s), y_{\text {ref }}(s)\right)-\left(x_r, y_r\right)\right\|=L (xref (s),yref (s))(xr,yr)=L. Since there is generally more than one such point on the reference, take the one with the greatest value of the parameter s to uniquely define a control. Then α \alpha α is given by
在这个控制器的最早报道[138]中,从相机的输出数据中直接计算角度 α \alpha α 。然而, α \alpha α 可以用惯性坐标系表示,以定义一个状态反馈控制。考虑构型 ( x r , y r , θ ) T \left(x_r, y_r, \theta\right)^T (xr,yr,θ)T 以及路径点 ( x r e f ( s ) , y r e f ( s ) ) \left(x_{r e f}(s), y_{r e f}(s)\right) (xref(s),yref(s)) ,使得 ∥ ( x ref  ( s ) , y ref  ( s ) ) − ( x r , y r ) ∥ = L \left\|\left(x_{\text {ref }}(s), y_{\text {ref }}(s)\right)-\left(x_r, y_r\right)\right\|=L (xref (s),yref (s))(xr,yr)=L 。由于路径上通常不止有一个这样的点,我们选择参数 s s s 的值最大的点,以唯一地定义控制。进而, α \alpha α 由下式给出:
α = arctan ⁡ ( y ref  − y r x ref  − x r ) − θ ( V . 4 ) \alpha=\arctan \left(\frac{y_{\text {ref }}-y_r}{x_{\text {ref }}-x_r}\right)-\theta \quad(V.4) α=arctan(xref xryref yr)θ(V.4)

Assuming that the path has no curvature and the vehicle speed is constant (potentially negative), the pure pursuit controller solves Problem V.1. For a fixed nonzero curvature, pure pursuit has a small steady state tracking error.
In the case where the vehicle’s distance to the path is greater than L L L, the controller output is not defined. Another consideration is that changes in reference path curvature can lead to19 the car deviating from the reference trajectory. This may be acceptable for driving along a road, but can be problematic for tracking parking maneuvers. Lastly, the heading rate command ω \omega ω becomes increasingly sensitive to the feedback angle α \alpha α as the vehicle speed increases. A common fix for this issue is to scale L L L with the vehicle speed.
假设路径没有曲率且车辆速度恒定(可能为负),则纯追踪控制器可以给出问题V.1的解。对于固定的非零曲率,纯追踪具有较小的稳态跟踪误差。
在车辆到路径的距离大于 L L L 的情况下,控制器输出并未被定义。另一个考虑是,参考路径的曲率的变化会导致汽车偏离参考轨迹,这对于沿道路行驶的任务可能可以接受,但是对于跟踪泊车策略可能存在问题。最后,随着车辆速度的增加,航向速率指令 ω \omega ω 对反馈角 α \alpha α 更加敏感。解决此问题的一个常见方法是根据车速来缩放 L L L

🟧 2)Rear wheel position based feedback(基于后轮位置的反馈)

The next approach uses the rear wheel position as an output to stabilize a nominal rear wheel path [56]. The controller assigns
后轮反馈控制使用后轮位置作为输出,使之稳定于一条标准后轮路径[56]。控制器规定
s ( t ) = arg ⁡ min ⁡ γ ∥ ( x r ( t ) , y r ( t ) ) − ( x ref  ( γ ) , y ref  ( γ ) ) ∥ ( V . 5 ) s(t)=\arg \min _\gamma\left\|\left(x_r(t), y_r(t)\right)-\left(x_{\text {ref }}(\gamma), y_{\text {ref }}(\gamma)\right)\right\| \quad(V.5) s(t)=argγmin(xr(t),yr(t))(xref (γ),yref (γ))(V.5)

Detailed assumptions on the reference path and a finite domain containing the reference path where (V.5) is a continuous function are described in [56]. The unit tangent to the path at s ( t ) s(t) s(t) is given by
文章[56]中描述了关于参考路径和包含参考路径的有限域的详细假设,在这个有限域内,(V.5)是连续函数。 s ( t ) s(t) s(t) 处与路径相切的单位正切由下式给出
t ^ = ( ∂ x r e f ∂ s ∣ s ( t ) , ∂ y r e f ∂ s ∣ s ( t ) ) ∥ ( ∂ x r e f ( s ( t ) ) ∂ s , ∂ y r e f ( s ( t ) ) ∂ s ) ∥ ( V . 6 ) \hat{t}=\frac{\left(\left.\frac{\partial x_{r e f}}{\partial s}\right|_{s(t)},\left.\frac{\partial y_{r e f}}{\partial s}\right|_{s(t)}\right)}{\left\|\left(\frac{\partial x_{r e f}(s(t))}{\partial s}, \frac{\partial y_{r e f}(s(t))}{\partial s}\right)\right\|} \quad(V.6) t^= (sxref(s(t)),syref(s(t))) (sxref s(t),syref s(t))(V.6)

and the tracking error vector is
且跟踪误差向量为
d ( t ) : = ( x r ( t ) , y r ( t ) ) − ( x ref  ( s ( t ) ) , y ref  ( s ( t ) ) ) ( V . 7 ) d(t):=\left(x_r(t), y_r(t)\right)-\left(x_{\text {ref }}(s(t)), y_{\text {ref }}(s(t))\right) \quad(V.7) d(t):=(xr(t),yr(t))(xref (s(t)),yref (s(t)))(V.7)

These values are used to compute a transverse error coordinate from the path e e e which is a cross product between the two vectors
这些值用于根据路径 e e e 计算横向误差坐标,其中路径 e e e 是两个向量之间的向量积
e = d x t ^ y − d y t ^ x ( V . 8 ) e=d_x \hat{t}_y-d_y \hat{t}_x \quad(V.8) e=dxt^ydyt^x(V.8)

with the subscript denoting the component indices of the vector. The control uses the angle θ e \theta_e θe between the vehicle’s heading vector and the tangent vector to the path.
其中下标表示向量的分量索引。这种控制策略使用车辆的航向向量和路径的切线向量之间的角度 θ e \theta_e θe
θ e ( t ) = θ − arctan ⁡ 2 ( ∂ y ref  ( s ( t ) ) ∂ s , ∂ x ref  ( s ( t ) ) ∂ s ) ( V . 9 ) \theta_e(t)=\theta-\arctan _2\left(\frac{\partial y_{\text {ref }}(s(t))}{\partial s}, \frac{\partial x_{\text {ref }}(s(t))}{\partial s}\right) \quad(V.9) θe(t)=θarctan2(syref (s(t)),sxref (s(t)))(V.9)

The geometry is illustrated in Figure V.3.
这个几何关系如图V.3所示。
在这里插入图片描述

图V.3:基于后轮的反馈控制的反馈变量 θ e \theta_e θe 是路径上距离后轮最近的点处的切线与汽车航向之间的差值。标量 e e e 的大小(绝对值)用红色表示。如图所示, e > 0 e>0 e>0 ,而对于汽车位于路径左侧的情况, e < 0 e<0 e<0

A change of coordinates to ( s , e , θ e ) \left(s, e, \theta_e\right) (s,e,θe) yields
坐标 ( s , e , θ e ) \left(s, e, \theta_e\right) (s,e,θe) 的变化率满足:
s ˙ = v r cos ⁡ θ e 1 − κ ( s ) e e ˙ = v r sin ⁡ θ e θ e = ω − v r κ ( s ) cos ⁡ θ e 1 − κ ( s ) e ( V . 10 ) \begin{aligned} & \dot{s}=\frac{v_r \cos \theta_e}{1-\kappa(s) e} \\ &\dot{e}=v_r \sin \theta_e \\ & \theta_e=\omega-\frac{v_r \kappa(s) \cos \theta_e}{1-\kappa(s) e} \end{aligned} \quad(V.10) s˙=1κ(s)evrcosθee˙=vrsinθeθe=ω1κ(s)evrκ(s)cosθe(V.10)

where κ ( s ) \kappa(s) κ(s) denotes the curvature of the path at s s s. The following heading rate command provides local asymptotic convergence to twice continuously differentiable paths:
其中 κ ( s ) \kappa(s) κ(s) 表示路径在 s s s 处的曲率。下式中的转向率指令为局部渐近收敛提供了连续二次可微分的路径:
ω = v r κ ( s ) cos ⁡ θ e 1 − κ ( s ) e − g 1 ( e , θ e , t ) θ e − k 2 v r sin ⁡ θ e θ e e ( V . 11 ) \omega=\frac{v_r \kappa(s) \cos \theta_e}{1-\kappa(s) e}-g_1\left(e, \theta_e, t\right) \theta_e-k_2 v_r \frac{\sin \theta_e}{\theta_e} e \quad(V.11) ω=1κ(s)evrκ(s)cosθeg1(e,θe,t)θek2vrθesinθee(V.11)

with g1(e; θe; t) > 0, k2 > 0, and vr 6= 0 which is verified with the Lyapunov function V (e; θe) = e2 + θe2=k2 in [56] using the coordinate system (V.10). The requirement that the path be twice differentiable comes from the appearance of the curvature in the feedback law. An advantage of this control law is that stability is unaffected by the sign of vr making it suitable for reverse driving.
其中 g 1 ( e , θ e , t ) > 0 , k 2 > 0 , v r ≠ 0 g_1\left(e, \theta_e, t\right)>0, k_2>0, v_r \neq 0 g1(e,θe,t)>0,k2>0,vr=0 ,可以通过[56]中利用了坐标系(5.10)的李雅普诺夫函数 V ( e , θ e ) = e 2 + θ e 2 / k 2 V\left(e, \theta_e\right)=e^2+\theta_e^2 / k_2 V(e,θe)=e2+θe2/k2 来证明。之所以要求路径是二次可微分的,是因为反馈定律中出现了曲率。这种控制律的一个优点是,稳定性不受 v r v_r vr 的正负号的影响,从而使其适用于反向驾驶。

Setting g 1 ( v r , θ e , t ) = k θ ∣ v r ∣ g_1\left(v_r, \theta_e, t\right)=k_\theta\left|v_r\right| g1(vr,θe,t)=kθvr for k e > 0 k_e>0 ke>0 leads to local exponential convergence with a rate independent of the vehicle speed so long as v r ≠ 0 v_r \neq 0 vr=0. The control law in this case is
k e > 0 k_e>0 ke>0 时,设置 g 1 ( v r , θ e , t ) = k θ ∣ v r ∣ g_1\left(v_r, \theta_e, t\right)=k_\theta\left|v_r\right| g1(vr,θe,t)=kθvr 可以实现局部指数收敛,且收敛速率与车速无关(只要 v r ≠ 0 v_r \neq 0 vr=0)。这种情况下的控制律是
ω = v r κ ( s ) cos ⁡ θ e 1 − κ ( s ) e − ( k θ ∣ v r ∣ ) θ e − ( k e v r sin ⁡ θ e θ e ) e ( V . 12 ) \omega=\frac{v_r \kappa(s) \cos \theta_e}{1-\kappa(s) e}-\left(k_\theta\left|v_r\right|\right) \theta_e-\left(k_e v_r \frac{\sin \theta_e}{\theta_e}\right) e \quad(V.12) ω=1κ(s)evrκ(s)cosθe(kθvr)θe(kevrθesinθe)e(V.12)

🟨 3)Front wheel position based feedback(基于前轮位置的反馈)

This approach was proposed and used in Stanford University’s entry to the 2005 DARPA Grand Challenge [55], [8]. The approach is to take the front wheel position as the regulated variable. The control uses the variables s ( t ) s(t) s(t); e ( t ) e(t) e(t); and θ e ( t ) \theta_e(t) θe(t) as in the previous subsections, with the modification that e ( t ) e(t) e(t) is computed with the front wheel position as opposed to the rear wheel position. Taking the time derivative of the transverse error reveals
前轮反馈控制是斯坦福大学在2005年DARPA大挑战中提出并使用的方法[55][8],其将前轮位置作为控制变量。它同样使用上一节中的变量 s ( t ) s(t) s(t), e ( t ) e(t) e(t), θ e ( t ) \theta_e(t) θe(t) ,不同的是其根据前轮位置而不是后轮位置来计算 e ( t ) e(t) e(t) 。取横向误差的时间导数
e ˙ = v f sin ⁡ ( θ e + δ ) ( V . 13 ) \dot{e}=v_f \sin \left(\theta_e+\delta\right) \quad(V.13) e˙=vfsin(θe+δ)(V.13)

The error rate in (V.13) can be directly controlled by the steering angle for error rates with magnitude less than v f v_f vf . Solving for the steering angle such that e ˙ = − k e \dot{e}=-k e e˙=ke drives e ( t ) e(t) e(t) to zero exponentially fast.
对于上式中的误差变化率,如果大小小于 v f v_f vf ,则可直接由转向角控。转向角的解应使得 e ˙ = − k e \dot{e}=-k e e˙=ke 能以指数速度将 e ( t ) e(t) e(t) 控制到零。
v f sin ⁡ ( δ + θ e ) = − k e ⇒ δ = arcsin ⁡ ( − k e v f ) − θ e ( V . 14 ) \begin{aligned} v_f \sin \left(\delta+\theta_e\right)=-k e \Rightarrow & \delta=\arcsin \left(-\frac{k e}{v_f}\right)-\theta_e \end{aligned} \quad(V.14) vfsin(δ+θe)=keδ=arcsin(vfke)θe(V.14)

The term θ e \theta_e θe in this case is not interpreted as heading error since it will be nonzero even with perfect tracking. It is more appropriately interpreted as a combination of a feed-forward term of the nominal steering angle to trace out the reference path and a heading error term. The drawback to this control law is that it is not defined when ∣ k e v f ∣ > 1 \left|\frac{k e}{v_f}\right|>1 vfke >1. The exponential convergence over a finite domain can be relaxed to local exponential convergence with the feedback law
在这种情况下,术语 θ e \theta_e θe 不被解释为航向误差,因为即使在完美跟踪的情况下,它也将是非零的。更恰当的解释应该是, \theta_e 是为用于追踪参考路径的标准转向角的前馈项和航向误差项的组合。这种控制律的缺点是,当 ∣ k e v f ∣ > 1 \left|\frac{k e}{v_f}\right|>1 vfke >1 时,它未被定义。通过如下的反馈律,有限域上的指数收敛可以被放松为局部指数收敛。
δ = arctan ⁡ ( − k e v f ) − θ e ( V . 15 ) \delta=\arctan \left(-\frac{k e}{v_f}\right)-\theta_e \quad(V.15) δ=arctan(vfke)θe(V.15)

which, to first order in e e e, is identical to the previous equation. This is illustrated in Figure V.4
考虑 e e e 的一阶导,该式与前面的公式相同,如图V.4所示。

Like the control law in (V.14) this controller locally exponentially stabilizes the car to paths with varying curvature with the condition that the path is continuously differentiable. The condition on the path arises from the definition of θ e \theta_e θe in the feedback policy. A drawback to this controller is that it is not stable in reverse making it unsuitable for parking.
与(V.14)中的控制律一样,此控制器在路径连续可微分的条件下,局部指数地将车辆稳定于具有可变曲率的路径。之所以要求路径连续可微分,是因为反馈策略中对 θ e \theta_e θe 的定义。此控制器的缺点是它在倒车时不稳定,因此不适合处理泊车任务。
在这里插入图片描述

图V.4:基于前轮输出的控制。这种控制策略将前轮指向路径,以使前轮垂直于路径的速度分量正比于前轮到路径的距离。这种控制在局部实现,并导致局部指数收敛。

Comparison of path tracking controllers for kinematic models: The advantages of controllers based on the kinematic model with the no-slip constraint on the wheels is that they have low computational requirements, are readily implemented, and have good performance at moderate speeds. Figure V.5 provides a qualitative comparison of the path stabilizing controllers of this sections based on, and simulated with, (III.3) for a lane change maneuver. In the simulation of the front wheel output based controller, the rear wheel reference path is replaced by the front wheel reference path satisfying
基于具有车轮无滑移约束的运动学模型的控制器的优点在于,它们的计算要求低,易于实现,并且在中等速度下具有良好的性能。图V.5定性比较了本节讨论的路径稳定控制器,其中各个控制器基于(III.3)进行了变道策略的模拟。在基于前轮输出的控制器的仿真中,后轮参考路径被满足以下条件的前轮参考路径代替
x r e f ( s ) ⟼ x r e f ( s ) + l cos ⁡ θ y r e f ( s ) ⟼ y r e f ( s ) + l sin ⁡ θ ( V . 16 ) \begin{aligned} & x_{r e f}(s) \longmapsto x_{r e f}(s)+l \cos \theta \\ & y_{r e f}(s) \longmapsto y_{r e f}(s)+l \sin \theta \end{aligned} \quad(V.16) xref(s)xref(s)+lcosθyref(s)yref(s)+lsinθ(V.16)

The parameters of the simulation are summarized in Table III.
模拟中涉及的参数如表III所示。

In reference to Figure V.5, the pure pursuit control tracks the reference path during periods with no curvature. In the region where the path has high curvature, the pure pursuit control causes the system to deviate from the reference path. In contrast, the latter two controllers converge to the path and track it through the high curvature regions.
参考图V.5,纯追踪控制在没有曲率的周期内能够跟踪参考路径。在对应高曲率路径的区域中,纯追踪控制将导致系统偏离参考路径。与之相反,后两种控制器收敛于参考路径,并仍能在高曲率的区域内跟踪参考路径。

In both controllers using (V.5) in the feedback policy, local exponential stability can only be proven if there is a neighborhood of the path where (V.5) is continuous. Intuitively, this means the path cannot cross over itself and must be differentiable.
对于均使用(V.5)作为控制策略的两种控制器,仅当存在路径的邻域使得(V.5)是连续的,局部指数稳定性才能被证明。直觉上,这意味着路径不能自相交,且必须是可微分的。
在这里插入图片描述

图V.5:本节中的三种路径稳定控制律的跟踪性能比较。(a) 当曲率非零时,纯追踪控制策略偏离参考路径。(b) 基于后轮输出的控制器将后轮驱动至后轮参考路径。系统的二阶响应导致了过冲。© 基于前轮输出的控制器以一阶响应将前轮驱动至参考路径并跟踪路径。

在这里插入图片描述

表III:用于生成图V.5的模拟和控制器参数

🟠 B. Trajectory Tracking Control for the Kinematic Model(基于运动学模型的轨迹跟踪控制)

🟥 1)Control Lyapunov based design(基于控制李雅普诺夫函数的设计)

A control design based on a control Lyapunov function is described in [142]. The approach is to define the tracking error in a coordinate frame fixed to the car. The configuration error can be expressed by a change of basis from the inertial coordinate frame using the reference trajectory, and velocity, ( x ref  , y ref  , θ ref  , v ref  , ω ref  ) \left(x_{\text {ref }}, y_{\text {ref }}, \theta_{\text {ref }}, v_{\text {ref }}, \omega_{\text {ref }}\right) (xref ,yref ,θref ,vref ,ωref ),
文章[142]描述了基于控制李雅普诺夫函数的控制设计,其在汽车坐标系中定义跟踪误差。利用参考轨迹和参考速度 ( x ref  , y ref  , θ ref  , v ref  , ω ref  ) \left(x_{\text {ref }}, y_{\text {ref }}, \theta_{\text {ref }}, v_{\text {ref }}, \omega_{\text {ref }}\right) (xref ,yref ,θref ,vref ,ωref ) ,构型误差可以表示为惯性坐标系的基的变化:

( x e y e θ e ) = ( cos ⁡ θ sin ⁡ θ 0 − sin ⁡ θ cos ⁡ θ 0 0 0 1 ) ( x ref  − x r y ref  − y r θ ref  − θ ) \left(\begin{array}{l} x_e \\ y_e \\ \theta_e \end{array}\right)=\left(\begin{array}{ccc} \cos \theta & \sin \theta & 0 \\ -\sin \theta & \cos \theta & 0 \\ 0 & 0 & 1 \end{array}\right)\left(\begin{array}{c} x_{\text {ref }}-x_r \\ y_{\text {ref }}-y_r \\ \theta_{\text {ref }}-\theta \end{array}\right) xeyeθe = cosθsinθ0sinθcosθ0001 xref xryref yrθref θ

The evolution of the configuration error is then
构型误差的变化继而满足:
x ˙ e = ω y e − v r + v r e f cos ⁡ θ e y ˙ e = − ω x e + v r e f sin ⁡ θ e θ ˙ e = ω r e f − ω \begin{aligned} & \dot{x}_e=\omega y_e-v_r+v_{r e f} \cos \theta_e \\ & \dot{y}_e=-\omega x_e+v_{r e f} \sin \theta_e \\ &\dot{\theta}_e=\omega_{r e f}-\omega \end{aligned} x˙e=ωyevr+vrefcosθey˙e=ωxe+vrefsinθeθ˙e=ωrefω

With the control assignment,
通过如下的控制分配
v r = v r e f cos ⁡ θ e + k 1 x e ω = ω r e f + v r e f ( k 2 y e + k 3 sin ⁡ θ e ) \begin{aligned} &v_r=v_{r e f} \cos \theta_e+k_1 x_e \\ &\omega=\omega_{r e f}+v_{r e f}\left(k_2 y_e+k_3 \sin \theta_e\right) \end{aligned} vr=vrefcosθe+k1xeω=ωref+vref(k2ye+k3sinθe)

the closed loop error dynamics become
可以得到如下的闭环误差动力学
x ˙ e = ( ω ref  + v ref  ( k 2 y e + k 3 sin ⁡ θ e ) ) y e − k 1 x e y ˙ e = − ( ω ref  + v ref  ( k 2 y e + k 3 sin ⁡ θ e ) ) x e + v ref  sin ⁡ θ e θ e = ω ref  − ω \begin{aligned} &\dot{x}_e=\left(\omega_{\text {ref }}+v_{\text {ref }}\left(k_2 y_e+k_3 \sin \theta_e\right)\right) y_e-k_1 x_e \\ &\dot{y}_e=-\left(\omega_{\text {ref }}+v_{\text {ref }}\left(k_2 y_e+k_3 \sin \theta_e\right)\right) x_e+v_{\text {ref }} \sin \theta_e \\ &\theta_e=\omega_{\text {ref }}-\omega \end{aligned} x˙e=(ωref +vref (k2ye+k3sinθe))yek1xey˙e=(ωref +vref (k2ye+k3sinθe))xe+vref sinθeθe=ωref ω

Stability is verified for k 1 , 2 , 3 > 0 k_{1,2,3}>0 k1,2,3>0, ω ˙ r e f = 0 \dot{\omega}_{r e f}=0 ω˙ref=0, and v ˙ ref  = 0 \dot{v}_{\text {ref }}=0 v˙ref =0 by the Lyapunov function
对于 k 1 , 2 , 3 > 0 k_{1,2,3}>0 k1,2,3>0, ω ˙ r e f = 0 \dot{\omega}_{r e f}=0 ω˙ref=0, v ˙ ref  = 0 \dot{v}_{\text {ref }}=0 v˙ref =0 ,其稳定性可以由如下的李雅普诺夫函数得证

V = 1 2 ( x e 2 + y e 2 ) + 1 − cos ⁡ θ e k 2 V=\frac{1}{2}\left(x_e^2+y_e^2\right)+\frac{1-\cos \theta_e}{k_2} V=21(xe2+ye2)+k21cosθe

with negative semi-definite time derivative,
且李雅普诺夫函数具有半负定的时间导数
V ˙ = − k 1 x e 2 − v r e f k 3 sin ⁡ 2 θ e k 2 \dot{V}=-k_1 x_e^2-\frac{v_{r e f} k_3 \sin ^2 \theta_e}{k_2} V˙=k1xe2k2vrefk3sin2θe

A local analysis shows that the control law provides local exponential stability. However, for the system to be time invariant, !ref and vref are required to be constant. A related controller is proposed in [143] which utilizes a backstepping design to achieve uniform local exponential stability for a finite domain with time varying references.
局部的分析表明,此控制律实现了局部指数稳定性。然而,对于时不变系统,要求 ω r e f \omega_{r e f} ωref v ref  v_{\text {ref }} vref  是常数。文章[143]提出了一种相关的控制器,其利用反推的设计方法,以达到在具有时变参考的有限域上的一致局部指数稳定性。

🟧 2)Output feedback linearization(输出反馈线性化)

For higher vehicle speeds, it is appropriate to constrain the steering angle to have continuous motion as in (III.8). With the added state, it becomes more difficult to design a controller from simple geometric considerations. A good option in this case is to output-linearize the system.
对于较高的车辆速度,同理(III.8),应当约束转向角以实现连续转向。由于附加了一个状态,从简单的几何角度来考虑如何设计控制器变得更加困难。在这种情况下,输出线性化的系统是一种好的选择。

This is not easily accomplished using the front or rear wheel positions. An output which simplifies the feedback linearization is proposed in [144], where a point ahead of the vehicle by any distance d 6= 0, aligned with the steering angle is selected.
使用前轮或后轮的位置并不容易实现这一点。文章[144]中提出了简化反馈线性化的输出,其中选择了与转向角对齐的、距离车辆前方任意 d ≠ 0 d \neq 0 d=0 的点。

Let x p = x f + d cos ⁡ ( θ + δ ) x_p=x_f+d \cos (\theta+\delta) xp=xf+dcos(θ+δ) and y p = y f + d sin ⁡ ( θ + δ ) y_p=y_f+d \sin (\theta+\delta) yp=yf+dsin(θ+δ) be the output of the system. Taking the derivative of these outputs and substituting the dynamics of III.8 yields
x p = x f + d cos ⁡ ( θ + δ ) x_p=x_f+d \cos (\theta+\delta) xp=xf+dcos(θ+δ) y p = y f + d sin ⁡ ( θ + δ ) y_p=y_f+d \sin (\theta+\delta) yp=yf+dsin(θ+δ) 为系统的输出。取输出的导数,代入(III.8)的动力学得
( x ˙ p y ˙ p ) = ( cos ⁡ ( θ + δ ) − d l sin ⁡ ( θ + δ ) sin ⁡ δ − d sin ⁡ ( θ + δ ) sin ⁡ ( θ + δ ) + d l cos ⁡ ( θ + δ ) sin ⁡ δ d cos ⁡ ( θ + δ ) ) ( v f v δ ) = : A ( θ , δ ) ( v f v δ ) ( V . 17 ) \begin{aligned} \left(\begin{array}{l} \dot{x}_p \\ \dot{y}_p \end{array}\right)=\left(\begin{array}{cc} \cos (\theta+\delta)-\frac{d}{l} \sin (\theta+\delta) \sin \delta & -d \sin (\theta+\delta) \\ \sin (\theta+\delta)+\frac{d}{l} \cos (\theta+\delta) \sin \delta & d \cos (\theta+\delta) \end{array}\right)\left(\begin{array}{l} v_f \\ v_\delta \end{array}\right) =: A(\theta, \delta)\left(\begin{array}{l} v_f \\ v_\delta \end{array}\right) \end{aligned} \quad(V.17) (x˙py˙p)=(cos(θ+δ)ldsin(θ+δ)sinδsin(θ+δ)+ldcos(θ+δ)sinδdsin(θ+δ)dcos(θ+δ))(vfvδ)=:A(θ,δ)(vfvδ)(V.17)

Then, defining the right hand side of (V.17) as auxiliary control variables u x u_x ux and u y u_y uy yields
再定义(V.17)等式右侧为辅助控制变量 u x u_x ux u y u_y uy ,有
( x ˙ p y ˙ p ) = ( u x u y ) ( V . 18 ) \left(\begin{array}{l} \dot{x}_p \\ \dot{y}_p \end{array}\right)=\left(\begin{array}{l} u_x \\ u_y \end{array}\right) \quad(V.18) (x˙py˙p)=(uxuy)(V.18)

which makes control straightforward. From ux and uy, the original controls vf and vδ are recovered by using the inverse of the matrix in (V.17), provided below:
这使得控制变得简单。根据 u x u_x ux u y u_y uy ,使用(V.17)中的矩阵的逆,来重新得到原始控制 v f v_f vf v δ v_\delta vδ ,如下所示:
[ A ( θ , δ ) ] − 1 = ( cos ⁡ ( θ + δ ) sin ⁡ ( θ + δ ) − 1 d sin ⁡ ( θ + δ ) − 1 l cos ⁡ ( θ + δ ) sin ⁡ δ 1 d cos ⁡ ( θ + δ ) − 1 l sin ⁡ ( θ + δ ) sin ⁡ δ ) ( V . 19 ) \begin{aligned} {[A(\theta, \delta)]^{-1}} & =\left(\begin{array}{cc} \cos (\theta+\delta) & \sin (\theta+\delta) \\ -\frac{1}{d} \sin (\theta+\delta)-\frac{1}{l} \cos (\theta+\delta) \sin \delta & \frac{1}{d} \cos (\theta+\delta)-\frac{1}{l} \sin (\theta+\delta) \sin \delta \end{array}\right) \end{aligned} \quad(V.19) [A(θ,δ)]1=(cos(θ+δ)d1sin(θ+δ)l1cos(θ+δ)sinδsin(θ+δ)d1cos(θ+δ)l1sin(θ+δ)sinδ)(V.19)

From the input-output linear system, local trajectory stabilization can be accomplished with the controls
根据输入-输出线性系统,可以通过如下的控制,来实现局部轨迹稳定
u x = x ˙ p ,  ref  + k x ( x p , r e f − x p ) u y = y p ,  ref  + k y ( y p , r e f − y p ) ( V . 20 ) \begin{aligned} & u_x=\dot{x}_{p, \text { ref }}+k_x\left(x_{p, r e f}-x_p\right) \\ & u_y=y_{p, \text { ref }}+k_y\left(y_{p, r e f}-y_p\right) \end{aligned} \quad(V.20) ux=x˙p, ref +kx(xp,refxp)uy=yp, ref +ky(yp,refyp)(V.20)

To avoid confusion, note that in this case, the output position ( x p , y p ) \left(x_p, y_p\right) (xp,yp) and controlled speed v f v_f vf are not collocated as in the previously discussed controllers.
为避免混淆,注意在这种情况下,输出位置 ( x p , y p ) \left(x_p, y_p\right) (xp,yp) 和受控速度 v f v_f vf 并不像前面讨论的控制器那样配置。

🟡 C. Predictive Control Approaches(预测控制方法)

The simple control laws discussed above are suitable for moderate driving conditions. However, slippery roads or emergency maneuvers may require a more accurate model, such as the one introduced in Section III-B. The added detail of more sophisticated models complicates the control design making it difficult to construct controllers from intuition and geometry of the configuration space.
上面讨论的简单控制律适用于中等驾驶条件。然而,湿滑道路或紧急机动可能需要更精确的模型,例如第III-B节中介绍的模型。更复杂的模型所增加的细节使控制设计复杂化,使得难以根据直觉和构型空间的几何结构来构造控制器。

Model predictive control [145] is a general control design methodology which can be very effective for this problem. Conceptually, the approach is to solve the motion planning problem over a short time horizon, take a short interval of the resulting open loop control, and apply it to the system. While executing, the motion planning problem is re-solved to find an appropriate control for the next time interval. Advances in computing hardware as well as mathematical programming algorithms have made predictive control feasible for real-time
use in driverless vehicles. MPC is a major field of research on its own and this section is only intended to provide a brief description of the technique and to survey results on its application to driverless vehicle control.
模型预测控制[145]是一种通用的控制设计方法,对这种问题非常有效。从概念上讲,此方法在短时间范围/区间内求解运动规划问题,取短时间间隔内的开环控制,并将其应用于系统。在执行时,重新求解运动规划问题,以找到下一时间间隔的适当控制。计算硬件和数学编程算法的进步使得预测控制在无人驾驶车辆中的实时应用成为可能。MPC本身是一个主要的研究领域,本节仅旨在简要描述该技术,并综述其在无人驾驶车辆控制中的应用结果。

Since model predictive control is a very general control technique, the model takes the form of a general continuous time control system with control, u ( t ) ∈ R m u(t) \in \mathbb{R}^m u(t)Rm, and state, x ( t ) ∈ R n x(t) \in \mathbb{R}^n x(t)Rn,
由于模型预测控制是一种非常通用的控制技术,因此其模型可表示为具有控制 u ( t ) ∈ R m u(t) \in \mathbb{R}^m u(t)Rm 和状态 x ( t ) ∈ R n x(t) \in \mathbb{R}^n x(t)Rn 的一般连续时间控制系统:
x ˙ = f ( x , u , t ) ( V . 21 ) \dot{x}=f(x, u, t) \quad(V.21) x˙=f(x,u,t)(V.21)

A feasible reference trajectory x ref  ( t ) x_{\text {ref }}(t) xref (t), and for some motion planners u r e f ( t ) u_{r e f}(t) uref(t), are provided satisfying (V.21). The system is then discretized by an appropriate choice of numerical approximation so that (V.21) is given at discrete time instances by
问题给定一条可行的参考轨迹 x ref  ( t ) x_{\text {ref }}(t) xref (t) ,以及对于一些运动规划器,还给定 u r e f ( t ) u_{r e f}(t) uref(t)。这些给定条件满足(V.21)。随后,通过一种合适的数值近似来离散化系统,使得(V.21)在离散时间情况下表示为
x k + 1 = F k ( x k , u k ) , k ∈ N ( V . 22 ) x_{k+1}=F_k\left(x_k, u_k\right), \quad k \in \mathbb{N} \quad(V.22) xk+1=Fk(xk,uk),kN(V.22)

One of the simplest discretization schemes is Euler’s method with a zero order hold on control:
欧拉法是最简单的离散化策略之一,其对控制施加零阶保持
F k ( x ( k ⋅ Δ t ) , u ( k ⋅ Δ t ) ) = x ( k ⋅ Δ t ) + Δ t ⋅ f ( x ( k ⋅ Δ t ) , u ( k ⋅ Δ t ) , t k ) , k ∈ N ( V . 23 ) \begin{aligned} F_k(x(k \cdot \Delta t), u(k \cdot \Delta t)) =x(k \cdot \Delta t)+\Delta t & \cdot f\left(x(k \cdot \Delta t), u(k \cdot \Delta t), t_k\right), \quad k \in \mathbb{N} \end{aligned} \quad(V.23) Fk(x(kΔt),u(kΔt))=x(kΔt)+Δtf(x(kΔt),u(kΔt),tk),kN(V.23)

The state and control are discretized by their approximation at times t k = k ⋅ Δ t t_k=k \cdot \Delta t tk=kΔt. Solutions to the discretized system are approximate and will not match the continuous time equation exactly. Similarly, the reference trajectory and control sampled at the discrete times t k t_k tk will not satisfy the discrete time equation. For example, the mismatch between solutions to (V.23) and (V.21) will be O ( Δ t ) O(\Delta t) O(Δt) and the reference trajectory sampled at time t k t_k tk will result in
状态和控制在时间 t k = k ⋅ Δ t t_k=k \cdot \Delta t tk=kΔt 时通过其近似值离散化。离散系统的解是近似的,因此不会精确地匹配连续时间方程。类似地,在离散时间 t k t_k tk 采样的参考轨迹和控制将不满足离散时间方程。例如,(V.23)和(V.21)的解之间的误差将是 O ( Δ t ) O(\Delta t) O(Δt) ,且在时间 t k t_k tk 采样的参考轨迹将导致
F k ( x r e f ( t k ) , u r e f ( t k ) ) − x r e f ( t k + 1 ) = O ( Δ t 2 ) ( V . 24 ) F_k\left(x_{r e f}\left(t_k\right), u_{r e f}\left(t_k\right)\right)-x_{r e f}\left(t_{k+1}\right)=O\left(\Delta t^2\right) \quad(V.24) Fk(xref(tk),uref(tk))xref(tk+1)=O(Δt2)(V.24)

To avoid over-complicating the following discussion, we assume the discretization is exact for the remainder of the section. The control law typically takes the form
为了避免过度复杂化接下来的讨论,我们在本节的剩余部分假设离散化是精确的。通常,控制律有如下形式
u k ( x m e a s . ) = arg ⁡ min ⁡ x n ∈ X n , u n ∈ U n { h ( x N − x r e f , N , u N − u r e f , N ) + ∑ n = k g n ( x n − x r e f , n , u n − u r e f , n ) } ( V . 25 ) \begin{array}{r} u_k\left(x_{m e a s .}\right)=\arg \min _{\substack{x_n \in X_n, u_n \in U_n}}\left\{h\left(x_N-x_{r e f, N}, u_N-u_{r e f, N}\right)\right. \\ \left.+\sum_{n=k} g_n\left(x_n-x_{r e f, n}, u_n-u_{r e f, n}\right)\right\} \end{array} \quad(V.25) uk(xmeas.)=argminxnXn,unUn{h(xNxref,N,uNuref,N)+n=kgn(xnxref,n,unuref,n)}(V.25)

The function g n g_n gn penalizes deviations from the reference trajectory and control at each time step, while the function h h h is a terminal penalty at the end of the time horizon. The set x n x_n xn is the set of allowable states which can restrict undesirable positions or velocities, e.g., excessive tire slip or obstacles. The set u n u_n un encodes limits on the magnitude of the input signals. Important considerations are whether the solutions to the right hand side of (V.25) exist, and when they do, the stability and robustness of the closed loop system. These issues are investigated in the predictive control literature [146], [147].
函数 g n g_n gn 将每个时间步长处的、与参考轨迹和参考控制的偏差作为惩罚项,而函数 h h h 是时间区间结束时的终止惩罚项。集合 x n x_n xn 是可允许状态的集合,以限制非期望的位置或速度,例如过度的轮胎打滑或障碍物。集合 u n \mathcal{u}_n un 对输入信号的幅度限制进行编码。重要的考虑因素是,(V.25)的等式右侧的解是否存在、何时存在,以及闭环系统的稳定性和鲁棒性。预测控制文献[146][147]研究了这些问题。

To implement an MPC on a driverless car, (V.25) must be solved several times per second which is a major obstacle to its use. In the special case that h h h and g n g_n gn are quadratic, u n u_n un and x n x_n xn are polyhedral, and F F F is linear, the problem becomes a quadratic program. Unlike a general nonlinear programming formulation, interior point algorithms are available for solving quadratic programs in polynomial time. To leverage this, the complex vehicle model is often linearized to obtain an approximate linear model. Linearization approaches typically differ in the reference about which the linearization is computed—current operating point [148]–[150], reference path [151] or more generally, about a reference trajectory, which results in the following approximate linear model:
为了在无人驾驶汽车上实现MPC,必须每秒内若干次地求解出(V.25),这是使用MPC的主要障碍。一种特殊情况下, h h h g n g_n gn 是二次的, u n u_n un x n x_n xn 是多面体, F F F 是线性的,此时问题变成了二次规划。与一般的非线性规划不同,内点算法可以在多项式时间内求解二次规划。为了利用这一点,复杂的车辆模型通常被线性化以获得近似的线性模型。线性化方法通常在计算线性化的参考上有所不同,包括当前操作点[148-150]、参考路径[151]、或者,更一般地,参考轨迹。采用参考轨迹作为线性化的参考,将得到如下的近似线性模型:
x r e f , k + 1 + ξ k + 1 = F k ( x r e f , k , u r e f , k ) + ∇ x F k ( x r e f , k , u r e f , k ) ξ k + ∇ u F k ( x r e f , k , u r e f , k ) η k + O ( ∥ ξ k ∥ 2 ) + O ( ∣ ∣ η k ∥ 2 ) = : F k ( x r e f , k , u r e f , k ) + A k ξ k + B k η k + O ( ∥ ξ k ∥ 2 ) + O ( ∣ ∣ η k ∥ 2 ) ( V . 26 ) \begin{aligned} & x_{r e f, k+1}+\xi_{k+1}\\ &= F_k\left(x_{r e f, k}, u_{r e f, k}\right) +\nabla_x F_k\left(x_{r e f, k}, u_{r e f, k}\right) \xi_k \\ &+\nabla_u F_k\left(x_{r e f, k}, u_{r e f, k}\right) \eta_k+O\left(\left\|\xi_k\right\|^2\right) + O\left(|| \eta_k \|^2\right) \\ &=: F_k\left(x_{r e f, k}, u_{r e f, k}\right)+A_k \xi_k+B_k \eta_k+O\left(\left\|\xi_k\right\|^2\right) +O\left(|| \eta_k \|^2\right) \end{aligned} \quad(V.26) xref,k+1+ξk+1=Fk(xref,k,uref,k)+xFk(xref,k,uref,k)ξk+uFk(xref,k,uref,k)ηk+O(ξk2)+O(∣∣ηk2)=:Fk(xref,k,uref,k)+Akξk+Bkηk+O(ξk2)+O(∣∣ηk2)(V.26)

where ξ : = x − x ref  \xi:=x-x_{\text {ref }} ξ:=xxref  and η : = u − u r e f \eta:=u-u_{r e f} η:=uuref are the deviations of the state and control from the reference trajectory. This first order expansion of the perturbation dynamics yields a linear time varying (LTV) system,
其中 ξ : = x − x ref  \xi:=x-x_{\text {ref }} ξ:=xxref  η : = u − u r e f \eta:=u-u_{r e f} η:=uuref 分别是状态和控制与参考轨迹间的偏差。扰动动力学的这种一阶扩展得到了一个线性时变系统,
ξ k + 1 = A k ξ k + B k η k ( V . 27 ) \xi_{k+1}=A_k \xi_k+B_k \eta_k \quad(V.27) ξk+1=Akξk+Bkηk(V.27)

Then using a quadratic objective, and expressing the polyhedral constraints algebraically, we obtain
接着利用二次目标函数,并代数形式地表示多面体约束,我们可以得到
u k ( x meas.  ) = arg ⁡ min ⁡ ξ k , η k { ξ N T H ξ N + ∑ n = k k + N − 1 ξ k T Q k ξ k + η k T R k η k } ( V . 28 ) \begin{aligned} u_k\left(x_{\text {meas. }}\right)= & \arg \min _{\xi_k, \eta_k}\left\{\xi_N^T H \xi_N\right. \left.+\sum_{n=k}^{k+N-1} \xi_k^T Q_k \xi_k+\eta_k^T R_k \eta_k\right\} \end{aligned} \quad(V.28) uk(xmeas. )=argξk,ηkmin{ξNTHξN+n=kk+N1ξkTQkξk+ηkTRkηk}(V.28)

subject to
约束条件:
ξ k = x meas.  − x r e f C n ξ n ≤ 0 , D n η n ≤ 0 ξ k + 1 = A k ξ k + B n η n , n ∈ { k , … , k + N − 1 } \begin{aligned} &\xi_k=x_{\text {meas. }}-x_{r e f} \\ &C_n \xi_n \leq 0, \quad D_n \eta_n \leq 0 \\ &\xi_{k+1}=A_k \xi_k+B_n \eta_n, \quad n \in\{k, \ldots, k+N-1\} \end{aligned} ξk=xmeas. xrefCnξn0,Dnηn0ξk+1=Akξk+Bnηn,n{k,,k+N1}

where R k R_k Rk and Q k Q_k Qk are positive semi-definite. If the states and inputs are unconstrained, i.e., u n = R m , x n = R n u_n=\mathbb{R}^m , x_n=\mathbb{R}^n un=Rmxn=Rn, a semi-closed form solution can be obtained by dynamic programming requiring only the calculation of an N step matrix recursion [152]. Similar closed form recursive solutions have also been explored when vehicle models are represented by controlled auto-regressive integrated moving average (CARIMA) with no state and input constraints [153], [154].
其中 R k R_k Rk Q k Q_k Qk 是半正定的。如果状态和输入是无约束的,即 u n = R m , x n = R n u_n=\mathbb{R}^m , x_n=\mathbb{R}^n un=Rmxn=Rn 则可以通过动态规划来获得半封闭形式的解,这只需要计算 N 步的矩阵递归[152]。当车辆模型表示为无状态和输入约束的受控自回归积分滑动平均模型[153][154]时,类似的闭式递归解也得到了探索。

A further variation in the model predictive control approach is to replace state constraints (e.g., obstacles) and input constraints by penalty functions in the performance functional. Such a predictive control approach based on a dynamic model with nonlinear tire behavior is presented in [155]. In addition to penalizing control effort and deviation from a reference path to a goal which does not consider obstacles, the performance functional penalizes input constraint violations and collisions with obstacles over the finite control horizon. In this sense
it is similar to potential field based motion planning, but is demonstrated to have improved performance.
模型预测控制方法的一种进阶变体是用性能泛函中的惩罚函数来代替状态约束(例如障碍物)和输入约束。文章[155]提出了这种基于具有非线性轮胎行为的动力学模型的预测控制方法。除了惩罚控制输入以及惩罚从参考路径(不考虑障碍物且通往目标)的偏离,性能函数还惩罚对输入约束的违反以及在有限控制区间内与障碍物的碰撞。在这个意义上,它类似于基于势场的运动规划,但是被证明具有更好的性能。

The following are some variations of the model predictive control framework that are found in the literature of car controllers:
以下是在汽车控制器文献中发现的模型预测控制框架的一些变体:
1) Unconstrained MPC with Kinematic Models(利用运动学模型的无约束的模型预测控制):
The earliest predictive controller in [153] falls under this category, in which the model predictive control framework is applied without input or state constraints using a CARIMA model. The resulting semi-closed form solution has minimal computational requirements and has also been adopted in [154]. Moreover, the time-varying linear quadratic programming approach with no input or state constraints was considered in [154] using a linearized kinematic model.
文章[153]提出的最早的预测控制器属于此类,其中使用CARIMA模型,在没有输入或状态约束的情况下应用模型预测控制框架。所得到的半封闭形式的解具有最小的计算要求,并已在[154]中采用。此外,[154]中使用线性化的运动学模型,考虑了无输入或状态约束的时变线性二次规划方法。

2) Path Tracking Controllers(路径跟踪控制器):
In [151], a predictive control is investigated using a center of mass based linear dynamic model (assuming constant velocity) for path tracking and an approximate steering model. The resulting integrated model is validated with a detailed automatic steering model and a 27 degree-of-freedom CarSim vehicle model.
在[151]中,使用基于质心的线性动力学模型(假设恒定速度)和近似转向模型研究了预测控制。通过详细的自动转向模型和一个具有27自由度的CarSim车辆模型,生成的集成模型得到了验证。

3)Trajectory Tracking Controllers(轨迹跟踪控制器):
A predictive controller using a tire model similar to Section III was investigated in [148]. The full nonlinear predictive control strategy was carried out in simulation and shown to stabilize a simulated emergency maneuver in icy conditions with a control frequency of 20 Hz. However, with a control horizon of just two time steps the computation time was three times the sample time of the controller making experimental validation impossible. A linearization based approach was also investigated in [148]–[150] based on a single linearization about the state of the vehicle at the current time step. The reduced complexity of solving the quadratic program resulted in acceptable computation time, and successful experimental results are reported for driving in icy conditions at speeds up to 21m/s. The promising simulation and experimental results of this approach are improved upon in [150] by providing conditions for the uniform local-asymptotic stability of the time varying system.
文章[148]研究了使用类似于第III节的轮胎模型的预测控制器。在仿真中执行了完全非线性预测控制策略,并在结冰条件下以20Hz的控制频率实现了模拟紧急机动的稳定。然而,由于控制区间只有两个时间步长,然而计算时间是控制器采样时间的三倍,因此无法进行实验验证。在[148-150]中还研究了基于线性化的方法,其基于当前时间步长下车辆状态的单一线性化。此时,求解二次规划的复杂度降低,使得计算时间是可接受的,同时还报告了在结冰条件下以高达21m/s的速度行驶的成功实验结果。文章[150]通过为时变系统的一致局部渐近稳定性提供条件,改进了该方法的模拟和实验结果。

🟢 D. Linear Parameter Varying Controllers(线性变参数控制)

Many controller design techniques are available for linear systems making a linear model desirable. However, the broad range of operating points encountered under normal driving conditions make it difficult to rely on a model linearized about a single operating point. To illustrate this, consider the lateral error dynamics in (V.10). If the tracking error is assumed to remain small a linearization of the dynamics around the operating point θ e = 0 \theta_e=0 θe=0 and e = 0 e=0 e=0 yields
许多控制器设计技术可用于线性系统,使得人们通常期望使用线性模型。然而,正常驾驶条件下遇到的操作点范围很广,因此很难依赖于在单个操作点上线性化的模型。为了说明这一点,考虑(V.10)中的横向误差动力学。如果假设跟踪误差保持较小,则在操作点 θ e = 0 \theta_e=0 θe=0 e = 0 e=0 e=0 周围的动力学的线性化为:
( e ˙ θ ˙ e ) = ( 0 v r 0 0 ) ( e θ e ) + ( 0 1 ) ω + ( 0 − v r κ ( s ) ) ( V . 29 ) \left(\begin{array}{c} \dot{e} \\ \dot{\theta}_e \end{array}\right)=\left(\begin{array}{cc} 0 & v_r \\ 0 & 0 \end{array}\right)\left(\begin{array}{l} e \\ \theta_e \end{array}\right)+\left(\begin{array}{l} 0 \\ 1 \end{array}\right) \omega+\left(\begin{array}{c} 0 \\ -v_r \kappa(s) \end{array}\right) \quad(V.29) (e˙θ˙e)=(00vr0)(eθe)+(01)ω+(0vrκ(s))(V.29)

Introducing a new control variable incorporating a feedforward u = ω + v r κ ( s ) u=\omega+v_r \kappa(s) u=ω+vrκ(s) simplifies the discussion. The dynamics are now
引入一个新的控制变量来合并前馈 u = ω + v r κ ( s ) u=\omega+v_r \kappa(s) u=ω+vrκ(s) 以简化上式,得到动力学:
( e ˙ θ ˙ e ) = ( 0 v r 0 0 ) ( e θ e ) + ( 0 1 ) u ( V . 30 ) \left(\begin{array}{c} \dot{e} \\ \dot{\theta}_e \end{array}\right)=\left(\begin{array}{cc} 0 & v_r \\ 0 & 0 \end{array}\right)\left(\begin{array}{l} e \\ \theta_e \end{array}\right)+\left(\begin{array}{l} 0 \\ 1 \end{array}\right) u \quad(V.30) (e˙θ˙e)=(00vr0)(eθe)+(01)u(V.30)

Observe that the model is indeed linear, but the forward speed v r v_r vr appears in the linear model. A simple proportional plus derivative control with gains k p k_p kp and k d k_d kd will stabilize the lateral dynamics but the poles of the closed loop system are given by ( − k d ± k d 2 − 4 k p v r ) / 2 \left(-k_d \pm \sqrt{k_d^2-4 k_p v_r}\right) / 2 (kd±kd24kpvr )/2 . At higher speeds the poles move into the complex plane leading to an oscillatory response. In contrast, a small k p k_p kp gain leads to a poor response at low speed. A very intuitive and widely used remedy to this challenge is gain scheduling. In this example, parameterizing k p k_p kp as a function of v r v_r vr fixes the poles to a single value for each speed. This technique falls into the category of control design for linear parameter varying (LPV) models [156]. Gain scheduling is a classical approach to this type of controller design. Tools from robust control and convex optimization are readily applied to address more complex models.
我们观察到模型确实是线性的,但是前进速度 v r v_r vr 出现在线性模型中。具有增益 k p k_p kp k d k_d kd 的简单比例加微分控制可以稳定横向动力学,但是闭环系统的极点为 ( − k d ± k d 2 − 4 k p v r ) / 2 \left(-k_d \pm \sqrt{k_d^2-4 k_p v_r}\right) / 2 (kd±kd24kpvr )/2 。在较高速度下,极点将移动到复平面,这将导致振荡响应。相比之下,小的 k p k_p kp 增益将导致低速时的响应较差。针对这个问题的一种非常直观且广泛使用的解决方案是增益调度。在本例中,将 k p k_p kp 参数化为 v r v_r vr 的函数,可以将每个速度下的极点固定为一个值。该技术属于线性参数变化模型的控制设计范畴[156]。增益调度是这类控制器设计的经典方法。鲁棒控制和凸优化工具很容易应用于解决更复杂的模型。

LPV control designs for lateral control are presented in [157]–[159]. LPV models are used in [160], [161] together with predictive control approaches for path and trajectory stabilization. At a lower level of automation, LPV control techniques have been proposed for integrated system control. In these designs, several subsystems are combined under a single controller to achieve improved handling performance. LPV control strategies for actuating active and semi-active suspension systems are developed in [162], [163], while integrated suspension and braking control systems are developed in [164], [165].
在[157-159]中介绍了横向控制的LPV控制设计。在[160][161]中,同时使用了LPV模型以及预测控制方法,用于路径和轨迹稳定。在较低的自动化水平上,LPV控制技术已被提出用于集成系统控制。在这些设计中,多个子系统被组合在一个控制器下,以实现改进的操纵性能。在[162][163]中开发了用于驱动主动和半主动悬架系统的LPV控制策略,而在[164][165]中开发了集成悬架和制动控制系统。

🚚 VI. Conclusions(结论)

The past three decades have seen increasingly rapid progress in driverless vehicle technology. In addition to the advances in computing and perception hardware, this rapid progress has been enabled by major theoretical progress in the computational aspects of mobile robot motion planning and feedback control theory. Research efforts have undoubtedly been spurred by the improved utilization and safety of road networks that driverless vehicles would provide.
在过去三十年中,无人驾驶汽车技术的进步越来越快。除了计算和感知硬件的进步之外,移动机器人运动规划和反馈控制理论在计算方面的重大理论进步也推动了这一快速进步。毫无疑问,无人驾驶汽车所提供的道路网络的利用率和安全性的提高推动了研究工作。

Driverless vehicles are complex systems which have been decomposed into a hierarchy of decision making problems, where the solution of one problem is the input to the next. The breakdown into individual decision making problems has enabled the use of well developed methods and technologies from a variety of research areas. The task is then to integrate these methods so that their interactions are semantically valid, and the combined system is computationally efficient. A more efficient motion planning algorithm may only be compatible with a computationally intensive feedback controller such as model predictive control. Conversely, a simple control law may require less computation to execute, but is also less robust and requires using a more detailed model for motion planning.
无人驾驶汽车是复杂系统,它已经被分解到决策问题的层次,其中一个问题的解就是下一个问题的输入。将决策问题分解为各个独立的问题,使得我们能够使用来自各个研究领域的成熟方法和技术。随后的任务便是集成这些方法,以使它们的交互语义有效,并使组合的系统在计算上高效。更有效的运动规划算法可能仅与计算密集型的反馈控制器(例如模型预测控制)兼容。相反,一个简单的控制律可能只需要更少的计算,但是也不那么鲁棒,并且需要使用更详细的运动规划模型。

This paper has provided a survey of the various aspects of driverless vehicle decision making problems with a focus on motion planning and feedback control. The survey of performance and computational requirements of various motion planning and control techniques serves as a reference for assessing compatibility and computational tradeoffs between various choices for system level design.
本文综述了无人驾驶车辆决策问题的各个方面,且将重点放在了运动规划和反馈控制。对各种运动规划和控制技术的性能和计算要求的综述可作为参考,来帮助评估系统级设计的不同选择的兼容性和计算权衡。

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.coloradmin.cn/o/193425.html

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈,一经查实,立即删除!

相关文章

H3C SecParh堡垒机任意用户登录与远程执行代码漏洞

H3C SecParh堡垒机任意用户登录与远程执行代码漏洞1.H3C SecParh堡垒机任意用户登录漏洞1.1.漏洞描述1.2.漏洞影响1.3.漏洞复现1.3.1.登录页面1.3.2.构建URL1.4.总结2.H3C SecParh堡垒机远程命令执行漏洞2.1.漏洞描述2.2.漏洞影响2.3.漏洞复现2.3.1.登录页面2.3.2.构建URL2.4.总…

python-pptx 操作PPTx幻灯片文件删除并替换图片

python-pptx 操作PPTx幻灯片文件删除并替换图片 作者&#xff1a;虚坏叔叔 博客&#xff1a;https://xuhss.com 早餐店不会开到晚上&#xff0c;想吃的人早就来了&#xff01;&#x1f604; 一、原理 通过查找ppt中的图片指纹替换 二、操作流程 原始ppt如下&#xff1a; 根据…

[单片机] MCU串口发送C方案优化

应用场景&#xff1a; 主频不高非操作系统的单片机&#xff0c;需要在while循环中发送 数据到上位机&#xff0c;当数据较长时&#xff0c;会让发送的过程会让其他操作有卡顿感。为了解决这个问题&#xff0c;需采用一种方法&#xff1a;在每次大循环中只发一个字节数据&#x…

HTML5+CSS3(一)-全面详解(学习总结---从入门到深化)

目录 ​编辑 第一个前端程序 学习效果反馈 前端工具的选择与安装 前端常见开发者工具 浏览器 VSCode中文语言包安装&#xff1a; 学习效果反馈 VSCode开发者工具快捷键 VSCode常用快捷键列表 学习效果反馈 HTML5简介与基础骨架 HTML5的DOCTYPE声明 HTML5基本骨架 html…

Linux(CentOS Stream 9)安装MySQL8.0

mysql8下载链接 链接&#xff1a;https://pan.baidu.com/s/1yBCDbDYUmQWjcM1SdS7Xng 提取码&#xff1a;t37m 上传到服务器上并解压 cd /usr/localtar -xvf mysql-8.0.21-linux-glibc2.12-x86_64.tar.xz解压包重命名为mysql mv mysql-8.0.21-linux-glibc2.12-x86_64 /usr/l…

Linux部署RKNN-toolkit过程以及异常点记录(详细记录)

文章目录Linux部署RKNN-toolkit过程以及异常点记录1.在Linux中安装Miniconda1.1 使用服务器下载Miniconda1.2 安装conda1.3 激活刚安装完成的软件1.4参考博文2.创建并激活Miniconda新环境&#xff08;rknn&#xff09;2.1 创建conda环境&#xff08;命名为rknn&#xff09;2.2 …

做亚马逊、沃尔玛测评自养号大额、退款一定要解决的几个问题?

大家好我是测评龙哥&#xff0c;今天我跟大家说下做亚马逊、沃尔玛测评自养号、退款、lu货、项目需要用到的防关联、防封号环境的一些底层技术原理。这里讲的内容我相信很少有人能掌握&#xff0c;都是一些比较难的IT术技。 如果你现在准备开始做测评是在了解阶段还是已经在做…

SRM-询报价管理系统搭建指南

1、简介1.1、案例简介本文将介绍&#xff0c;如何搭建SRM-询报价管理。1.2、应用场景企业根据询价需求通知参与报价的供应商&#xff0c;所有供应商会收到通知后进行报价&#xff0c;自动生成了比价数据&#xff0c;企业可参考比价数据对供应商进行选择。2、设置方法2.1、表单搭…

GF_CLR初始用 - 正式版

参照&#xff1a;DeerGF_Wolong框架使用教程 与tackor老哥的踩坑日记所编写&#xff0c;第二次尝试&#xff0c;总结第一次经验重新来。 点击链接加入群聊【Gf_Wolong热更集合】 一. 部署 HybridCLR(Wolong) 环境 首先安装Windows Build Support (IL2CPP)需要完整的克隆项目…

自动驾驶感知——激光雷达物体检测算法

文章目录1. 基于激光雷达的物体检测1.1 物体检测的输入与输出1.2 点云数据库1.3 激光雷达物体检测算法1.3.1 点视图1.3.1.1 PointNet1.3.1.2 PointNet1.3.1.3 Point-RCNN1.3.1.4 3D-SSD1.3.1.5 总结和对比1.3.2 俯视图1.3.2.1 VoxelNet1.3.2.2 SECOND1.3.2.3 PIXOR1.3.2.4 AFDe…

2023年Java学到什么程度可以找工作了?

不管是过去现在还是未来&#xff0c;任何以就业为目的的学习&#xff0c;参考的就业要求最直接的方式就是直接去搜索目标岗位企业的招聘要求。是不是很简单呢&#xff01;下面是根据Java不同技术层次列举招聘要求&#xff1a;初级Java开发工程师&#xff1a;中级Java开发工程师…

出现这些症状,说明你的免疫力在走下坡路!

这些年免疫力逐渐成为大家关注的重点。随着身边越来越多的人感染&#xff0c;免疫力的强弱影响着每个人身体的恢复情况&#xff0c;好的免疫力就是最有效的药物。免疫力讲究平衡二字&#xff0c;太强、太弱都不好。太强会让机体过于敏感&#xff0c;对非致病因素也发起攻击&…

网络故障监控某小程序延时分析案例

背景 某港口集疏港系统近期出现故障&#xff0c;在凌晨3-5点时段无法上传疫情通勤卡&#xff0c;对港口货物运输带来影响。 该港口已部署NetInside全流量回溯系统&#xff0c;针对本次故障&#xff0c;进行故障定位和原因分析。 分析简介 操作时间&#xff1a;2022年9月8日星…

【C++】C++入门 命名空间 及输入与输出

前言 C是在C的基础之上&#xff0c;容纳进去了面向对象编程思想&#xff0c;并增加了许多有用的库&#xff0c;以及编程范式等。熟悉C语言之后&#xff0c;对C学习有一定的帮助。 C补充C语言语法的不足&#xff0c;以及对C语言设计不合理的地方进行优化&#xff0c;比如&#x…

联想昭阳K4e电脑系统错误导致屏幕闪烁怎么重装系统?

联想昭阳K4e电脑系统错误导致屏幕闪烁怎么重装系统&#xff1f;有用户安装的电脑系统有兼容性错误&#xff0c;导致电脑开机之后&#xff0c;屏幕会不断的进行闪烁&#xff0c;无法正常的进行电脑操作。那么这个情况我们如何去进行电脑系统的重装呢&#xff1f;今天教大家U盘重…

项目管理系统

项目要求 1&#xff09;服务器负责管理所有员工表单&#xff08;以数据库形式&#xff09;&#xff0c;其他客户端可通过网络连接服务器来查询员工表单。 2&#xff09;需要账号密码登陆&#xff0c;其中需要区分管理员账号还是普通用户账号。 3&#xff09;管理员账号可以查…

【数据结构】极致详解:树与二叉树(下)——链式存储实现

目录 &#x1f929;前言&#x1f929;&#xff1a; &#x1f92f;一、链式存储概述&#x1f92f;&#xff1a; &#x1f920;二、链式结构的遍历&#x1f920;&#xff1a; 1.前序、中序与后序遍历&#xff1a; 2.层序遍历&#xff1a; &#x1f970;三、链式存储结构各接…

2023年转行IT互联网:盘点高薪职业岗位!

要问今年转行求职最想进入的行业&#xff0c;那么互联网肯定算其中一个。智联招聘发布的《2022大学生就业力调研报告》显示&#xff0c;IT/通信/电子/互联网行业是应届生最期望就业的行业。中国青年报中青校媒面向全国大学生发起调查&#xff0c;有64.33%希望毕业后能进入互联网…

linux常识及常用命令

一、介绍 一般项目都是部署在linux服务器上的&#xff0c;linux内核起初是由芬兰人林纳斯托瓦兹在上学时出于爱好编写的。它是一套免费试用和自由传播的类Unix操作系统&#xff0c;是一个基于POSIX&#xff08;可移植&#xff09;和UNIX的多用户、多任务、多线程和多CPU的操作…

Task10-Excel看板

文章目录一 分析思路二 实现过程1 确定周数2 销售基础整理3 周销售数据变化趋势4 周销售渠道整理5 看板绘制一 分析思路 二 实现过程 1 确定周数 确定日期所在的周数用&#xff1a;【WEEKNUM函数】 WEEKNUM&#xff08;serial_num&#xff0c;return_type&#xff09;参数Ser…