Skip to content

Commit 5751829

Browse files
authored
Enhance lqr steering control docs (AtsushiSakai#1015)
* enhance lqr steering control docs * enhance lqr steering control docs * enhance lqr steering control docs * enhance lqr steering control docs * improve lqr steering control docs
1 parent cfb7363 commit 5751829

File tree

4 files changed

+111
-7
lines changed

4 files changed

+111
-7
lines changed

PathTracking/lqr_steer_control/lqr_steer_control.py

Lines changed: 8 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ def update(state, a, delta):
5555
return state
5656

5757

58-
def PIDControl(target, current):
58+
def pid_control(target, current):
5959
a = Kp * (target - current)
6060

6161
return a
@@ -70,10 +70,11 @@ def solve_DARE(A, B, Q, R):
7070
solve a discrete time_Algebraic Riccati equation (DARE)
7171
"""
7272
X = Q
73-
maxiter = 150
73+
Xn = Q
74+
max_iter = 150
7475
eps = 0.01
7576

76-
for i in range(maxiter):
77+
for i in range(max_iter):
7778
Xn = A.T @ X @ A - A.T @ X @ B @ \
7879
la.inv(R + B.T @ X @ B) @ B.T @ X @ A + Q
7980
if (abs(Xn - X)).max() < eps:
@@ -178,7 +179,7 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
178179
dl, target_ind, e, e_th = lqr_steering_control(
179180
state, cx, cy, cyaw, ck, e, e_th)
180181

181-
ai = PIDControl(speed_profile[target_ind], state.v)
182+
ai = pid_control(speed_profile[target_ind], state.v)
182183
state = update(state, ai, dl)
183184

184185
if abs(state.v) <= stop_speed:
@@ -202,8 +203,9 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal):
202203
if target_ind % 1 == 0 and show_animation:
203204
plt.cla()
204205
# for stopping simulation with the esc key.
205-
plt.gcf().canvas.mpl_connect('key_release_event',
206-
lambda event: [exit(0) if event.key == 'escape' else None])
206+
plt.gcf().canvas.mpl_connect(
207+
'key_release_event',
208+
lambda event: [exit(0) if event.key == 'escape' else None])
207209
plt.plot(cx, cy, "-r", label="course")
208210
plt.plot(x, y, "ob", label="trajectory")
209211
plt.plot(cx[target_ind], cy[target_ind], "xg", label="target")

docs/README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@ This folder contains documentation for the Python Robotics project.
88
#### Install Sphinx and Theme
99

1010
```
11-
pip install sphinx sphinx-autobuild sphinx-rtd-theme
11+
pip install sphinx sphinx-autobuild sphinx-rtd-theme sphinx_rtd_dark_mode sphinx_copybutton sphinx_rtd_dark_mode
1212
```
1313

1414
#### Building the Docs

docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst

Lines changed: 102 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,109 @@ control.
88

99
.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_steer_control/animation.gif
1010

11+
Overview
12+
~~~~~~~~
13+
14+
The LQR (Linear Quadratic Regulator) steering control model implemented in lqr_steer_control.py provides a simulation
15+
for an autonomous vehicle to track a desired trajectory by adjusting steering angle based on feedback from the current state and the desired trajectory.
16+
This model utilizes a combination of PID speed control and LQR steering control to achieve smooth and accurate trajectory tracking.
17+
18+
Vehicle motion Model
19+
~~~~~~~~~~~~~~~~~~~~~
20+
21+
The below figure shows the geometric model of the vehicle used in this simulation:
22+
23+
.. image:: lqr_steering_control_model.png
24+
:width: 600px
25+
26+
The `e` and `theta` represent the lateral error and orientation error, respectively, with respect to the desired trajectory.
27+
And :math:`\dot{e}` and :math:`\dot{\theta}` represent the rates of change of these errors.
28+
29+
The :math:`e_t` and :math:`theta_t` are the updated values of `e` and `theta` at time `t`, respectively, and can be calculated using the following kinematic equations:
30+
31+
.. math:: e_t = e_{t-1} + \dot{e}_{t-1} dt
32+
33+
.. math:: \theta_t = \theta_{t-1} + \dot{\theta}_{t-1} dt
34+
35+
Where `dt` is the time difference.
36+
37+
The change rate of the `e` can be calculated as:
38+
39+
.. math:: \dot{e}_t = V \sin(\theta_{t-1})
40+
41+
Where `V` is the vehicle speed.
42+
43+
If the :math:`theta` is small,
44+
45+
.. math:: \theta \approx 0
46+
47+
the :math:`\sin(\theta)` can be approximated as :math:`\theta`:
48+
49+
.. math:: \sin(\theta) = \theta
50+
51+
So, the change rate of the `e` can be approximated as:
52+
53+
.. math:: \dot{e}_t = V \theta_{t-1}
54+
55+
The change rate of the :math:`\theta` can be calculated as:
56+
57+
.. math:: \dot{\theta}_t = \frac{V}{L} \tan(\delta)
58+
59+
where `L` is the wheelbase of the vehicle and :math:`\delta` is the steering angle.
60+
61+
If the :math:`\delta` is small,
62+
63+
.. math:: \delta \approx 0
64+
65+
the :math:`\tan(\delta)` can be approximated as :math:`\delta`:
66+
67+
.. math:: \tan(\delta) = \delta
68+
69+
So, the change rate of the :math:`\theta` can be approximated as:
70+
71+
.. math:: \dot{\theta}_t = \frac{V}{L} \delta
72+
73+
The above equations can be used to update the state of the vehicle at each time step.
74+
75+
To formulate the state-space representation of the vehicle dynamics as a linear model,
76+
the state vector `x` and control input vector `u` are defined as follows:
77+
78+
.. math:: x_t = [e_t, \dot{e}_t, \theta_t, \dot{\theta}_t]^T
79+
80+
.. math:: u_t = \delta_t
81+
82+
The state transition equation can be represented as:
83+
84+
.. math:: x_{t+1} = A x_t + B u_t
85+
86+
where:
87+
88+
:math:`\begin{equation*} A = \begin{bmatrix} 1 & dt & 0 & 0\\ 0 & 0 & v & 0\\ 0 & 0 & 1 & dt\\ 0 & 0 & 0 & 0 \\ \end{bmatrix} \end{equation*}`
89+
90+
:math:`\begin{equation*} B = \begin{bmatrix} 0\\ 0\\ 0\\ \frac{v}{L} \\ \end{bmatrix} \end{equation*}`
91+
92+
LQR controller
93+
~~~~~~~~~~~~~~~
94+
95+
The Linear Quadratic Regulator (LQR) controller is used to calculate the optimal control input `u` that minimizes the quadratic cost function:
96+
97+
:math:`J = \sum_{t=0}^{N} (x_t^T Q x_t + u_t^T R u_t)`
98+
99+
where `Q` and `R` are the weighting matrices for the state and control input, respectively.
100+
101+
for the linear model:
102+
103+
:math:`x_{t+1} = A x_t + B u_t`
104+
105+
The optimal control input `u` can be calculated as:
106+
107+
:math:`u_t = -K x_t`
108+
109+
where `K` is the feedback gain matrix obtained by solving the Riccati equation.
110+
11111
References:
12112
~~~~~~~~~~~
13113
- `ApolloAuto/apollo: An open autonomous driving platform <https://github.com/ApolloAuto/apollo>`_
14114

115+
- `Linear Quadratic Regulator (LQR) <https://en.wikipedia.org/wiki/Linear%E2%80%93quadratic_regulator>`_
116+
17 KB
Loading

0 commit comments

Comments
 (0)