Skip to content

Commit 16f2e71

Browse files
committed
Added UKF_range_bearing.py example
1 parent fef5eac commit 16f2e71

File tree

2 files changed

+335
-1
lines changed

2 files changed

+335
-1
lines changed

README.md

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,8 @@ Filename | Description
6969
Filename | Description
7070
-------- | -----------
7171
[diffdrive_GNSS_EKF.py](diffdrive_GNSS_EKF.py) | Simple EKF implementation for a differential drive vehicle with wheel encoders, an angular rate gyro, and GNSS.
72-
[UT_example.py](UT_example.py) | Introductory problem illustrating a basic unscented transform (UT) of statistics for Gaussian inputs, after [Julier and Uhlmann (2014)](https://doi.org/10.1109/JPROC.2003.823141).
72+
[UT_example.py](UT_example.py) | Introductory problem illustrating a basic unscented transform (UT) of statistics for Gaussian inputs, after [Julier and Uhlmann (2004)](https://doi.org/10.1109/JPROC.2003.823141).
73+
[UKF_range_bearing.py](UKF_range_bearing.py) | Example implementation of a UKF for vehicle navigation by using odometry together with a range and bearing sensor, similar to the example on p. 290 of the book [Principles of Robot Motion: Theory, Algorithms, and Implementations (2005)](https://mitpress.mit.edu/books/principles-robot-motion).
7374

7475
## Cite this Work
7576

UKF_range_bearing.py

Lines changed: 333 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,333 @@
1+
"""
2+
Example UKF_range_bearing.py
3+
Author: Joshua A. Marshall <joshua.marshall@queensu.ca>
4+
GitHub: https://github.com/botprof/agv-examples
5+
"""
6+
7+
# %%
8+
# SIMULATION SETUP
9+
10+
import numpy as np
11+
import matplotlib.pyplot as plt
12+
from matplotlib.patches import Circle
13+
from scipy.stats import chi2
14+
from numpy.linalg import inv
15+
from scipy.linalg import block_diag
16+
from mobotpy.integration import rk_four
17+
from mobotpy.models import DiffDrive
18+
19+
# Set the simulation time [s] and the sample period [s]
20+
SIM_TIME = 30.0
21+
T = 0.04
22+
23+
# Create an array of time values [s]
24+
t = np.arange(0.0, SIM_TIME, T)
25+
N = np.size(t)
26+
27+
# %%
28+
# VEHICLE SETUP
29+
30+
# Set the track length of the vehicle [m]
31+
ELL = 1.0
32+
33+
# Create a vehicle object of type DiffDrive
34+
vehicle = DiffDrive(ELL)
35+
36+
# %% BUILD A MAP OF FEATURES IN THE VEHICLE'S ENVIRONMENT
37+
38+
# Number of features
39+
M = 150
40+
41+
# Map size [m]
42+
D_MAP = 100
43+
44+
# Randomly place features in the map
45+
f_map = np.zeros((2, M))
46+
for i in range(0, M):
47+
f_map[:, i] = D_MAP * (2.0 * np.random.rand(2) - 1.0)
48+
49+
# %%
50+
# SENSOR MODELS
51+
52+
# Uncertainty in wheel speeds [m/s]
53+
SIGMA_SPEED = 0.1
54+
55+
# Max and min sensor ranges
56+
R_MAX = 15
57+
R_MIN = 1
58+
59+
# Set the range [m] and bearing [rad] uncertainty
60+
SIGMA_RANGE = 0.3
61+
SIGMA_BEARING = 15 * np.pi / 180
62+
63+
# Create a range and bearing sensor model
64+
def RandB_sensor(x, f_map, R):
65+
66+
# Define how many total features are available
67+
m = np.shape(f_map)[1]
68+
69+
# Find the indices of features that are within range [r_min, r_max]
70+
a = np.array([])
71+
for i in range(0, m):
72+
r = np.sqrt((f_map[0, i] - x[0]) ** 2 + (f_map[1, i] - x[1]) ** 2)
73+
if np.all(
74+
[
75+
r < R_MAX,
76+
r > R_MIN,
77+
]
78+
):
79+
a = np.append(a, i)
80+
81+
# Compute the range and bearing to all features within range
82+
if np.shape(a)[0] > 0:
83+
# Specify the size of the output
84+
m = np.shape(a)[0]
85+
y = np.zeros(2 * m)
86+
87+
# Compute the range and bearing to all features (including sensor noise)
88+
for i in range(0, m):
89+
# Range measurement [m]
90+
y[2 * i] = np.sqrt(
91+
(f_map[0, int(a[i])] - x[0]) ** 2 + (f_map[1, int(a[i])] - x[1]) ** 2
92+
) + np.sqrt(R[0, 0]) * np.random.randn(1)
93+
# Bearing measurement [rad]
94+
y[2 * i + 1] = (
95+
np.unwrap(
96+
np.array(
97+
[
98+
np.arctan2(
99+
f_map[1, int(a[i])] - x[1], f_map[0, int(a[i])] - x[0]
100+
)
101+
- x[2]
102+
]
103+
)
104+
)
105+
- np.pi
106+
+ np.sqrt(R[1, 1]) * np.random.randn(1)
107+
)
108+
else:
109+
# No features were found within the sensing range
110+
y = np.array([])
111+
112+
# Return the range and bearing to features in y with indices in a
113+
return y, a
114+
115+
116+
# %%
117+
# CREATE A UKF-BASED ESTIMATOR
118+
119+
120+
def UKF(x, P, v_m, y_m, a, f_map, Q, R, kappa):
121+
122+
# Set the augmented state and covariance
123+
xi = np.append(x, v_m)
124+
n_x = np.shape(x)[0]
125+
n_xi = np.shape(xi)[0]
126+
P_xi = block_diag(P, Q)
127+
128+
# Define a set of sigma points for for the a priori estimate
129+
xi_sig = np.zeros((n_xi, 2 * n_xi + 1))
130+
P_xi_sig = np.linalg.cholesky((n_xi + kappa) * P_xi)
131+
for i in range(0, n_xi):
132+
xi_sig[:, i + 1] = xi + P_xi_sig[:, i]
133+
xi_sig[:, n_xi + i + 1] = xi - P_xi_sig[:, i]
134+
135+
# Propagate each sigma point through the vehicle's model
136+
xi_sig_hat = np.zeros((n_xi, 2 * n_xi + 1))
137+
for i in range(0, 2 * n_xi + 1):
138+
xi_sig_hat[0:n_x, i] = rk_four(
139+
vehicle.f, xi_sig[0:n_x, i], xi_sig[n_x:n_xi, i], T
140+
)
141+
142+
# Compute the mean and convariance from the transformed sigma points
143+
w_xi = 0.5 / (n_xi + kappa) * np.ones(2 * n_xi + 1)
144+
w_xi[0] = 2 * kappa * w_xi[0]
145+
xi = np.average(xi_sig_hat, axis=1, weights=w_xi)
146+
P_xi = np.cov(xi_sig_hat, ddof=0, aweights=w_xi)
147+
148+
# Help to keep the covariance matrix symmetrical
149+
P_xi = (P_xi + np.transpose(P_xi)) / 2
150+
151+
# Set the vehicle state estimates
152+
x_hat = xi[0:n_x]
153+
P_hat = P_xi[0:n_x, 0:n_x]
154+
155+
# Find the number of observed features
156+
m = np.shape(a)[0]
157+
158+
# Compute the a posteriori estimate if there are visible features
159+
if m > 0:
160+
161+
# Compute a new set of sigma points using the latest x_hat and P_hat
162+
x_sig = np.zeros((n_x, 2 * n_x + 1))
163+
P_sig = np.linalg.cholesky((n_x + kappa) * P_hat)
164+
for i in range(0, n_x):
165+
x_sig[:, i + 1] = x_hat + P_sig[:, i]
166+
x_sig[:, n_x + i + 1] = x_hat - P_sig[:, i]
167+
168+
# Find the expected measurement corresponding to each sigma point
169+
y_hat_sig = np.zeros((2 * m, 2 * n_x + 1))
170+
for j in range(0, 2 * n_x + 1):
171+
# Compute the expected measurements
172+
for i in range(0, m):
173+
y_hat_sig[2 * i, j] = np.sqrt(
174+
(f_map[0, int(a[i])] - x_sig[0, j]) ** 2
175+
+ (f_map[1, int(a[i])] - x_sig[1, j]) ** 2
176+
)
177+
y_hat_sig[2 * i + 1, j] = (
178+
np.unwrap(
179+
[
180+
np.arctan2(
181+
f_map[1, int(a[i])] - x_sig[1, j],
182+
f_map[0, int(a[i])] - x_sig[0, j],
183+
)
184+
- x_sig[2, j]
185+
]
186+
)
187+
- np.pi
188+
)
189+
190+
# Recombine the sigma points
191+
w_x = 0.5 / (n_x + kappa) * np.ones(2 * n_x + 1)
192+
w_x[0] = 2 * kappa * w_x[0]
193+
y_hat = np.average(y_hat_sig, axis=1, weights=w_x)
194+
195+
P_y = np.zeros((2 * m, 2 * m))
196+
P_xy = np.zeros((n_x, 2 * m))
197+
for i in range(0, 2 * n_x + 1):
198+
y_diff = y_hat_sig[:, i] - y_hat
199+
x_diff = x_sig[:, i] - x_hat
200+
P_y = P_y + w_x[i] * (y_diff.reshape((2 * m, 1))) @ np.transpose(
201+
y_diff.reshape((2 * m, 1))
202+
)
203+
P_xy = P_xy + w_x[i] * (x_diff.reshape((n_x, 1))) @ np.transpose(
204+
y_diff.reshape((2 * m, 1))
205+
)
206+
P_y = P_y + np.kron(np.identity(m), R)
207+
208+
# Help to keep the covariance matrix symmetrical
209+
P_y = (P_y + np.transpose(P_y)) / 2
210+
211+
# Update the estimate
212+
K = P_xy @ np.linalg.inv(P_y)
213+
x_hat = x_hat + K @ (y_m - y_hat)
214+
P_hat = P_hat - K @ P_y @ np.transpose(K)
215+
216+
# Help keep the covariance matrix symmetric
217+
P_hat = (P_hat + np.transpose(P_hat)) / 2
218+
219+
return x_hat, P_hat
220+
221+
222+
# %%
223+
# SIMULATE THE SYSTEM
224+
225+
# Set the covariance matrices
226+
Q = np.diag([SIGMA_SPEED ** 2, SIGMA_SPEED ** 2])
227+
R = np.diag([SIGMA_RANGE ** 2, SIGMA_BEARING ** 2])
228+
229+
# Initialize state, intput, and estimator variables
230+
x = np.zeros((3, N))
231+
v_m = np.zeros((2, N))
232+
x_hat_UKF = np.zeros((3, N))
233+
P_hat_UKF = np.zeros((3, 3, N))
234+
235+
# Initialize the state
236+
x_init = np.zeros(3)
237+
238+
# Set the initial guess of the estimator
239+
x_guess = x_init + np.array([5.0, -5.0, 0.1])
240+
P_guess = np.diag(np.square([5.0, -5.0, 0.1]))
241+
242+
# Set the initial conditions
243+
x[:, 0] = x_init
244+
v_m[:, 0] = np.zeros(2)
245+
x_hat_UKF[:, 0] = x_guess
246+
P_hat_UKF[:, :, 0] = P_guess
247+
248+
KAPPA = 3 - np.shape(x)[0]
249+
250+
for i in range(1, N):
251+
252+
# Compute some inputs (i.e., drive around)
253+
v = np.array([2.05, 1.95])
254+
255+
# Run the vehicle motion model
256+
x[:, i] = rk_four(vehicle.f, x[:, i - 1], v, T)
257+
258+
# Model the rate sensors
259+
v_m[0, i] = v[0] + np.sqrt(Q[0, 0]) * np.random.randn(1)
260+
v_m[1, i] = v[1] + np.sqrt(Q[1, 1]) * np.random.randn(1)
261+
262+
# Run the measurement model
263+
y_m, a = RandB_sensor(x[:, i], f_map, R)
264+
265+
# Run the UKF estimator
266+
x_hat_UKF[:, i], P_hat_UKF[:, :, i] = UKF(
267+
x_hat_UKF[:, i - 1],
268+
P_hat_UKF[:, :, i - 1],
269+
v_m[:, i - 1],
270+
y_m,
271+
a,
272+
f_map,
273+
Q,
274+
R,
275+
KAPPA,
276+
)
277+
278+
# %%
279+
# PLOT THE SIMULATION OUTPUTS
280+
281+
# Find the scaling factors for covariance bounds
282+
alpha = 0.01
283+
s1 = chi2.isf(alpha, 1)
284+
s2 = chi2.isf(alpha, 2)
285+
286+
# Set some plot limits for better viewing
287+
x_range = 0.5
288+
y_range = 0.5
289+
theta_range = 0.1
290+
phi_range = 0.1
291+
292+
# Plot the errors with covariance bounds
293+
sigma = np.zeros((3, N))
294+
fig1 = plt.figure(1)
295+
ax1 = plt.subplot(311)
296+
sigma[0, :] = np.sqrt(s1 * P_hat_UKF[0, 0, :])
297+
plt.fill_between(t, -sigma[0, :], sigma[0, :], color="C0", alpha=0.2)
298+
plt.plot(t, x[0, :] - x_hat_UKF[0, :], "C0")
299+
plt.ylabel(r"$e_1$ [m]")
300+
plt.setp(ax1, xticklabels=[])
301+
ax1.set_ylim([-x_range, x_range])
302+
ax2 = plt.subplot(312)
303+
sigma[1, :] = np.sqrt(s1 * P_hat_UKF[1, 1, :])
304+
plt.fill_between(t, -sigma[1, :], sigma[1, :], color="C0", alpha=0.2)
305+
plt.plot(t, x[1, :] - x_hat_UKF[1, :], "C0")
306+
plt.ylabel(r"$e_2$ [m]")
307+
plt.setp(ax2, xticklabels=[])
308+
ax2.set_ylim([-y_range, y_range])
309+
ax3 = plt.subplot(313)
310+
sigma[2, :] = np.sqrt(s1 * P_hat_UKF[2, 2, :])
311+
plt.fill_between(t, -sigma[2, :], sigma[2, :], color="C0", alpha=0.2)
312+
plt.plot(t, x[2, :] - x_hat_UKF[2, :], "C0")
313+
plt.ylabel(r"$e_3$ [rad]")
314+
plt.setp(ax3, xticklabels=[])
315+
ax3.set_ylim([-theta_range, theta_range])
316+
plt.xlabel(r"$t$ [s]")
317+
318+
# Plot the actual versus estimated positions on the map
319+
fig2, ax = plt.subplots()
320+
circle = Circle(x[0:2, 0], radius=R_MAX, alpha=0.2, color="C0", label="Sensing range")
321+
ax.add_artist(circle)
322+
plt.plot(x[0, :], x[1, :], "C0", label="Actual")
323+
plt.plot(x_hat_UKF[0, :], x_hat_UKF[1, :], "C1--", label="Estimated")
324+
plt.plot(f_map[0, :], f_map[1, :], "C2*", label="Transmitter")
325+
plt.axis("equal")
326+
ax.set_xlim([np.min(x_hat_UKF[0, :]) - 10, np.max(x_hat_UKF[0, :]) + 10])
327+
ax.set_ylim([np.min(x_hat_UKF[1, :]) - 10, np.max(x_hat_UKF[1, :]) + 10])
328+
plt.xlabel(r"$x_1$ [m]")
329+
plt.ylabel(r"$x_2$ [m]")
330+
plt.legend()
331+
332+
# Show the plot to the screen
333+
plt.show()

0 commit comments

Comments
 (0)