本文涵蓋了動力學模型以及不同車輛活動模型、Pure Pursuit Control 的原理,以及 bicycle model 的應用。動力學模型用來描述車子的狀態變化,而 Pure Pursuit Control 則是根據速度和角速度來畫圓弧,將車子移動到前方某個點的位置。bicycle model 則是一個根據方向盤轉角來描述車子原點運動的模型。
若我們想讓車子移動到路徑上到達終點,可以用前後和左右兩種 control 方式。
Car PID Control 若只使用 PID control 來完成,需要調整太多的參數,所以我們必須要引入一些車輛的特性,來減輕 control system 的負擔:
我們用 x, y 代表車子的二維座標,θ \theta θ 代表車子的轉向,合起來為車子的狀態
state: ξ 1 = [ x y θ ] \begin{aligned} \text{state: } \xi_1 = \begin{bmatrix}x\\y\\\theta\end{bmatrix} \end{aligned} state: ξ 1 = ⎣ ⎡ x y θ ⎦ ⎤ 因為座標有分車子當前的座標,還有世界座標,我們有一個 rotation matrix 可以轉換兩個座標系統
R ( θ ) = [ cos θ sin θ 0 − sin θ cos θ 0 0 0 1 ] \begin{aligned} R(\theta) = \begin{bmatrix} \cos\theta & \sin\theta & 0 \\ -\sin\theta & \cos\theta & 0 \\ 0& 0& 1 \end{bmatrix} \end{aligned} R ( θ ) = ⎣ ⎡ cos θ − sin θ 0 sin θ cos θ 0 0 0 1 ⎦ ⎤ 基本的模型 (basic kinematic model) 指的就是狀態 (state) 的變化 (derivative)
Basic Kinematic Model State 變化可以從車子的當前狀態,乘上 rotation matrix 的反矩陣得到
x R ˙ \dot{x_R} x R ˙ 是 x R x_R x R 的變化,也就是前進速度 (v v v )而側向是沒有速度的,所以 y R ˙ = 0 \dot{y_R} = 0 y R ˙ = 0 θ ˙ \dot{\theta} θ ˙ 是 θ \theta θ 的變化,也就是角速度 (ω \omega ω )Kinematic Model: [ x ˙ y ˙ θ ˙ ] = R ( θ ) − 1 [ x R ˙ y R ˙ θ ˙ ] = [ cos θ − sin θ 0 sin θ cos θ 0 0 0 1 ] [ v 0 ω ] = [ v cos ( θ ) v sin ( θ ) ω ] \begin{aligned} \text{Kinematic Model:} \\ \begin{bmatrix}\dot{x} \\ \dot{y} \\ \dot{\theta}\end{bmatrix} &= R(\theta)^{-1}\begin{bmatrix}\dot{x_R}\\\dot{y_R}\\\dot{\theta}\end{bmatrix} \\ &= \begin{bmatrix} \cos\theta & -\sin\theta & 0 \\ \sin\theta & \cos\theta & 0 \\ 0& 0& 1\end{bmatrix} \begin{bmatrix}v\\0\\\omega\end{bmatrix} \\ &= \begin{bmatrix}v\cos(\theta) \\ v\sin(\theta) \\\omega\end{bmatrix} \end{aligned} Kinematic Model: ⎣ ⎡ x ˙ y ˙ θ ˙ ⎦ ⎤ = R ( θ ) − 1 ⎣ ⎡ x R ˙ y R ˙ θ ˙ ⎦ ⎤ = ⎣ ⎡ cos θ sin θ 0 − sin θ cos θ 0 0 0 1 ⎦ ⎤ ⎣ ⎡ v 0 ω ⎦ ⎤ = ⎣ ⎡ v cos ( θ ) v sin ( θ ) ω ⎦ ⎤ Differential Drive Vehicle 現在來考慮兩輪的自走車活動模型
P: 原點 l: 原點分別到兩輪的距離 r: 輪子的半徑 座標依然是 x R , y R x_R, y_R x R , y R Differential Drive Vehicle 兩輪的轉速分別是 ϕ 1 \phi_1 ϕ 1 和 ϕ 2 \phi_2 ϕ 2
右輪 (左輪) 速度 = 半徑 * 角速度right: r × ϕ 1 ˙ \text{right: } r \times \dot{\phi_1} right: r × ϕ 1 ˙ left: r × ϕ 2 ˙ \text{left: } r \times \dot{\phi_2} left: r × ϕ 2 ˙ 原點的速度就是右輪 (左輪) 速度的一半x R 1 ˙ = r ϕ 1 ˙ 2 \dot{x_{R1}} = \frac{r\dot{\phi_1}}{2} x R 1 ˙ = 2 r ϕ 1 ˙ x R 2 ˙ = r ϕ 2 ˙ 2 \dot{x_{R2}} = \frac{r\dot{\phi_2}}{2} x R 2 ˙ = 2 r ϕ 2 ˙ 原點的角速度 = 速度 / 到輪子的距離ω 1 = r ϕ 1 ˙ 2 l \omega_1 = \frac{r\dot{\phi_1}}{2l} ω 1 = 2 l r ϕ 1 ˙ ω 2 = − r ϕ 2 ˙ 2 l \omega_2 = \frac{-r\dot{\phi_2}}{2l} ω 2 = 2 l − r ϕ 2 ˙ 要注意左輪旋轉半徑是 − l -l − l 而原點的運動就是左右兩輪相加
Kinematic Model: [ x ˙ y ˙ θ ˙ ] = R ( θ ) − 1 [ x R ˙ y R ˙ θ ˙ ] = [ cos θ − sin θ 0 sin θ cos θ 0 0 0 1 ] [ r ϕ 1 ˙ 2 + r ϕ 2 ˙ 2 0 r ϕ 1 ˙ 2 l − r ϕ 2 ˙ 2 l ] \begin{aligned} \text{Kinematic Model:} \\ \begin{bmatrix}\dot{x} \\ \dot{y} \\ \dot{\theta}\end{bmatrix} &= R(\theta)^{-1}\begin{bmatrix}\dot{x_R}\\\dot{y_R}\\\dot{\theta}\end{bmatrix} \\ &= \begin{bmatrix} \cos\theta & -\sin\theta & 0 \\ \sin\theta & \cos\theta & 0 \\ 0& 0& 1\end{bmatrix} \begin{bmatrix} \frac{r\dot{\phi_1}}{2}+\frac{r\dot{\phi_2}}{2}\\ 0\\ \frac{r\dot{\phi_1}}{2l}-\frac{r\dot{\phi_2}}{2l} \end{bmatrix} \\ \end{aligned} Kinematic Model: ⎣ ⎡ x ˙ y ˙ θ ˙ ⎦ ⎤ = R ( θ ) − 1 ⎣ ⎡ x R ˙ y R ˙ θ ˙ ⎦ ⎤ = ⎣ ⎡ cos θ sin θ 0 − sin θ cos θ 0 0 0 1 ⎦ ⎤ ⎣ ⎡ 2 r ϕ 1 ˙ + 2 r ϕ 2 ˙ 0 2 l r ϕ 1 ˙ − 2 l r ϕ 2 ˙ ⎦ ⎤ 左右輪的馬達轉速通常不會設成參數,而是用 v , ω v, \omega v , ω 來推導
RPM Inference 直線前進,相同轉速,相同方向 (v r \frac{v}{r} r v ) 原地旋轉,相同轉速,相反方向 (正負 ω \omega ω ) Pure pursuit control 將根據速度與角速度來畫圓弧移動到前方某個點的位置
Pure Pursuit Control L d L_d L d 是車子與目標點的距離R R R 是畫圓產生的半徑α \alpha α 是車子直線方向和 L d L_d L d 的夾角α = arctan ( y − y g x − x g ) − θ \alpha = \arctan\left(\frac{y-y_g}{x-x_g}\right) - \theta α = arctan ( x − x g y − y g ) − θ 因為圓心角 = 兩倍的弦切角 所以圓心角就是 2 a l p h a 2 alpha 2 a lp ha 因為是等腰三角形所以其他兩個角是 π 2 − α \frac{\pi}{2} - \alpha 2 π − α 根據正弦定理可以得到
L d sin ( 2 α ) = R sin ( π 2 − α ) R = L d sin ( π 2 − α ) sin ( 2 α ) = L d cos ( α ) 2 sin ( α ) cos ( α ) = L d 2 sin ( α ) ω = v R = 2 v sin ( α ) L d \begin{aligned} \frac{L_d}{\sin(2\alpha)} &= \frac{R}{\sin(\frac{\pi}{2}-\alpha)} \\\\ R &= \frac{L_d\sin(\frac{\pi}{2}-\alpha)}{\sin(2\alpha)} &= \frac{L_d\cos(\alpha)}{2\sin(\alpha)\cos(\alpha)} &= \frac{L_d}{2\sin(\alpha)} \\\\ \omega &= \frac{v}{R} = \frac{2v\sin(\alpha)}{L_d} \end{aligned} sin ( 2 α ) L d R ω = sin ( 2 π − α ) R = sin ( 2 α ) L d sin ( 2 π − α ) = R v = L d 2 v sin ( α ) = 2 sin ( α ) cos ( α ) L d cos ( α ) = 2 sin ( α ) L d 也就是說,若速度 v 透過 PID 為已知的值,那就可以推出對應的角速度 (ω \omega ω )
Ld 通常用速度來決定,速度越快就越遠,例如 L d = k v + L f c L_d = kv + L_{fc} L d = k v + L f c ,其中的 k , L f c k, L_{fc} k , L f c 是可調參數
上面講的模型可以自由移動旋轉,但真正的車子是有一定的幾何限制 (nonholonomic constraints )。而生活中最常見的移動機構設計是 bicycle model (汽車可以把前後的兩個輪子各別簡化為一個)
Kinematic Bicycle Model 後輪為車輛原點 (x, y) 車輛轉向 (車軸方向) θ \theta θ 方向盤轉角 δ \delta δ 車軸長度 L L L Kinematic Bicycle Model 將前輪放大可以得到一些細節:
車子以 v 的速度向前 有兩個世界座標的軸分量 (weight) 為 x f ˙ \dot{x_f} x f ˙ 和 y f ˙ \dot{y_f} y f ˙ 計算兩個 weight 對車子垂直方向的 weight
x f ˙ sin ( θ + δ ) \dot{x_f}\sin(\theta+\delta) x f ˙ sin ( θ + δ ) y f ˙ cos ( θ + δ ) \dot{y_f}\cos(\theta+\delta) y f ˙ cos ( θ + δ ) 考慮在低速下,兩個 weight 相加會抵消,就可以得到前後輪的 equation (Nonholonomic constraint equations )
( 1 ) x f ˙ sin ( θ + δ ) − y f ˙ cos ( θ + δ ) = 0 (front wheel) ( 2 ) x ˙ sin ( θ ) − y ˙ cos ( θ ) = 0 (rear wheel) \begin{aligned} (1) && \dot{x_f}\sin(\theta+\delta) - \dot{y_f}\cos(\theta+\delta) = 0 && \text{(front wheel)}\\ (2) && \dot{x}\sin(\theta) - \dot{y}\cos(\theta) = 0 && \text{(rear wheel)} \end{aligned} ( 1 ) ( 2 ) x f ˙ sin ( θ + δ ) − y f ˙ cos ( θ + δ ) = 0 x ˙ sin ( θ ) − y ˙ cos ( θ ) = 0 (front wheel) (rear wheel) 我們的目標是算出車輛原點的運動 ,可以從後輪座標推得前輪座標 (Front wheel position )
x f = x + L cos ( θ ) y f = y + L sin ( θ ) \begin{aligned} x_f = x + L\cos(\theta) \\ y_f = y + L\sin(\theta) \end{aligned} x f = x + L cos ( θ ) y f = y + L sin ( θ ) 將前輪座標帶回 (1) 就可以得到基於車輛原點的限制方程式
( 3 ) x ˙ sin ( θ + δ ) − y ˙ cos ( θ + δ ) − θ ˙ L cos ( δ ) = 0 \begin{aligned} (3) && \dot{x}\sin(\theta+\delta) - \dot{y}\cos(\theta+\delta) - \dot{\theta}L\cos(\delta) = 0 \end{aligned} ( 3 ) x ˙ sin ( θ + δ ) − y ˙ cos ( θ + δ ) − θ ˙ L cos ( δ ) = 0 由 (2) 和 (3) 可以得到一組解,代表原點的變化
( 4 ) x ˙ = v cos ( θ ) ( 5 ) y ˙ = v sin ( θ ) \begin{aligned} (4) && \dot{x} = v\cos(\theta)\\ (5) && \dot{y} = v\sin(\theta) \end{aligned} ( 4 ) ( 5 ) x ˙ = v cos ( θ ) y ˙ = v sin ( θ ) 將 (4) 和 (5) 再帶回 (3) 就可以得到角速度 (θ ˙ \dot{\theta} θ ˙ )
θ ˙ = v tan ( δ ) L \dot{\theta} = \frac{v\tan(\delta)}{L} θ ˙ = L v tan ( δ ) 於是我們就可以得到完整的 kinematic bicycle model (基於方向盤轉角 δ \delta δ )
[ x ˙ y ˙ θ ˙ ] = [ cos ( θ ) sin ( θ ) tan ( δ ) L ] v \begin{aligned} \begin{bmatrix} \dot{x}\\\dot{y}\\\dot{\theta} \end{bmatrix} = \begin{bmatrix} \cos(\theta) \\ \sin(\theta) \\ \frac{\tan(\delta)}{L} \end{bmatrix} v \end{aligned} ⎣ ⎡ x ˙ y ˙ θ ˙ ⎦ ⎤ = ⎣ ⎡ cos ( θ ) sin ( θ ) L t a n ( δ ) ⎦ ⎤ v 以及一些相關的 properties
∙ R θ ˙ = v ∙ v tan ( δ ) L = v R ∙ tan ( δ ) = L R \begin{aligned} &\bullet R\dot{\theta} = v \\ &\bullet \frac{v\tan(\delta)}{L} = \frac{v}{R} \\ &\bullet \tan(\delta) = \frac{L}{R} \end{aligned} ∙ R θ ˙ = v ∙ L v tan ( δ ) = R v ∙ tan ( δ ) = R L Bicycle Model Pure Pursuit Control 我們可以將 bicycle model 應用於 pure pursuit control
α \alpha α 和 R R R 和原本的 pure pursuit control 一樣我們可以用上面的 bicycle model properties 來求得方向盤轉角 (δ \delta δ ) tan ( δ ) = L R δ = arctan ( L R ) = arctan ( 2 L sin ( α ) L d ) \begin{aligned} &\tan(\delta) = \frac{L}{R} \\ &\delta = \arctan\left(\frac{L}{R}\right) = \arctan\left(\frac{2L\sin(\alpha)}{L_d}\right) \end{aligned} tan ( δ ) = R L δ = arctan ( R L ) = arctan ( L d 2 L sin ( α ) )