Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
ukf-nonlinear-complex-example.py
35
36""" @example ukf-nonlinear-complex-example.py
37 Example of a complex non-linear use-case of the Unscented Kalman Filter (UKF).
38 The system we are interested in is a 4-wheel robot, moving at a low velocity.
39 As such, it can be modeled unp.sing a bicycle model.
40
41 The state vector of the UKF is:
42 \f[
43 \begin{array}{lcl}
44 \textbf{x}[0] &=& x \\
45 \textbf{x}[1] &=& y \\
46 \textbf{x}[2] &=& \theta
47 \end{array}
48 \f]
49 where \f$ \theta \f$ is the heading of the robot.
50
51 The measurement \f$ \textbf{z} \f$ corresponds to the distance and relative orientation of the
52 robot with different landmarks. Be \f$ p_x^i \f$ and \f$ p_y^i \f$ the position of the \f$ i^{th} \f$ landmark
53 along the x and y axis, the measurement vector can be written as:
54 \f[
55 \begin{array}{lcl}
56 \textbf{z}[2i] &=& \sqrt{(p_x^i - x)^2 + (p_y^i - y)^2} \\
57 \textbf{z}[2i+1] &=& \tan^{-1}{\frac{p_y^i - y}{p_x^i - x}} - \theta
58 \end{array}
59 \f]
60
61 Some noise is added to the measurement vector to simulate measurements which are
62 not perfect.
63
64 The mean of several angles must be computed in the Unscented Transform. The definition we chose to use
65 is the following:
66
67 \f$ mean(\boldsymbol{\theta}) = atan2 (\frac{\sum_{i=1}^n sin{\theta_i}}{n}, \frac{\sum_{i=1}^n cos{\theta_i}}{n}) \f$
68
69 As the Unscented Transform uses a weighted mean, the actual implementation of the weighted mean
70 of several angles is the following:
71
72 \f$ mean_{weighted}(\boldsymbol{\theta}) = atan2 (\sum_{i=1}^n w_m^i sin{\theta_i}, \sum_{i=1}^n w_m^i cos{\theta_i}) \f$
73
74 where \f$ w_m^i \f$ is the weight associated to the \f$ i^{th} \f$ measurements for the weighted mean.
75
76 Additionally, the addition and subtraction of angles must be carefully done, as the result
77 must stay in the interval \f$[- \pi ; \pi ]\f$ or \f$[0 ; 2 \pi ]\f$ . We decided to use
78 the interval \f$[- \pi ; \pi ]\f$ .
79"""
80
81from visp.core import ColVector, Matrix, UnscentedKalman, UKSigmaDrawerMerwe, Math
82import numpy as np
83from typing import List
84from math import sqrt
85
86# For the Graphical User Interface
87try:
88 from visp.gui import Plot
89 has_gui = True
90except:
91 has_gui = False
92import numpy as np
93
94def normalize_angle(angle: float) -> float:
95 angle_0_to_2pi = Math.modulo(angle, 2. * np.pi)
96 angle_MinPi_Pi = angle_0_to_2pi
97 if angle_MinPi_Pi > np.pi:
98 # Substract 2 PI to be in interval [-Pi; Pi]
99 angle_MinPi_Pi = angle_MinPi_Pi - 2. * np.pi
100 return angle_MinPi_Pi
101
102def measurement_mean(measurements: List[ColVector], wm: List[float]) -> ColVector:
103 """
104 Compute the weighted mean of measurement vectors.
105
106 :param measurements: The measurement vectors, such as v[0] = dist_0 ; v[1] = bearing_0;
107 v[2] = dist_1 ; v[3] = bearing_1 ...
108 :param wm: The associated weights.
109
110 :return ColVector: The weighted mean.
111 """
112 nb_points = len(measurements)
113 size_measurement = measurements[0].size()
114 nb_landmarks = size_measurement // 2
115 mean = np.zeros(size_measurement)
116 sum_cos = np.zeros(nb_landmarks)
117 sum_sin = np.zeros(nb_landmarks)
118
119 for i in range(nb_points):
120 for j in range(nb_landmarks):
121 mean[2*j] += wm[i] * measurements[i][2*j]
122 sum_cos[j] += np.cos(measurements[i][(2*j)+1]) * wm[i]
123 sum_sin[j] += np.sin(measurements[i][(2*j)+1]) * wm[i]
124
125 orientations = np.arctan2(sum_sin, sum_cos)
126 mean[1::2] = orientations
127 return ColVector(mean)
128
129def measurement_residual(meas: ColVector, to_subtract: ColVector) -> ColVector:
130 """
131 Compute the subtraction between two vectors expressed in the measurement space,
132 such as v[0] = dist_0 ; v[1] = bearing_0; v[2] = dist_1 ; v[3] = bearing_1 ...
133
134 :param meas: Measurement to which we must subtract something.
135 :param toSubtract: The something we must subtract.
136
137 :return ColVector: \b meas - \b toSubtract .
138 """
139 res = meas.numpy() - to_subtract.numpy()
140 res[1::2] = [normalize_angle(angle) for angle in res[1::2]]
141 return ColVector(res)
142
143def state_add_vectors(a: ColVector, b: ColVector) -> ColVector:
144 """
145 Compute the addition between two vectors expressed in the state space,
146 such as v[0] = x ; v[1] = y; v[2] = heading .
147
148 :param a: The first state vector to which another state vector must be added.
149 :param b: The other state vector that must be added to a.
150
151 :return ColVector: The sum a + b.
152 """
153 add = a + b
154 return ColVector([add[0], add[1], normalize_angle(add[2])] )
155
156
157def state_mean_vectors(states: List[ColVector], wm: List[float]) -> ColVector:
158 """
159 Compute the weighted mean of state vectors.
160
161 :param states: The state vectors.
162 :param wm: The associated weights.
163 :return ColVector: The weighted mean.
164 """
165 mean = np.zeros(3)
166 wm_np = np.array(wm)
167 weighted_x = wm_np * np.array([state[0] for state in states])
168 weighted_y = wm_np * np.array([state[1] for state in states])
169 mean[0] = np.array(weighted_x).sum()
170 mean[1] = np.array(weighted_y).sum()
171 sumCos = (wm_np * np.array([np.cos(state[2]) for state in states])).sum()
172 sumSin = (wm_np * np.array([np.sin(state[2]) for state in states])).sum()
173 mean[2] = np.arctan2(sumSin, sumCos)
174 return ColVector(mean)
175
176def state_residual_vectors(a, b) -> ColVector:
177 """
178 Compute the subtraction between two vectors expressed in the state space,
179 such as v[0] = x ; v[1] = y; v[2] = heading .
180
181 :param a: The first state vector to which another state vector must be subtracted.
182 :param b: The other state vector that must be subtracted to a.
183
184 :return ColVector: The subtraction a - b.
185 """
186 res = a - b
187 return ColVector([res[0], res[1], normalize_angle(res[2])])
188
189def fx(x: ColVector, dt: float) -> ColVector:
190 """
191 As the state model {x, y, \f$ \theta \f$} does not contain any velocity
192 information, it does not evolve without commands.
193
194 :param x: The internal state of the UKF.
195 :param dt: The sampling time: how far in the future are we projecting x.
196
197 :return ColVector: The updated internal state, projected in time, also known as the prior.
198 """
199 return x
200
201def generate_turn_commands(v: float, angleStart: float, angleStop: float, nbSteps: int) -> List[ColVector]:
202 """
203 Compute the commands realising a turn at constant linear velocity.
204
205 :param v: Constant linear velocity.
206 :param angleStart: Starting angle (in degrees).
207 :param angleStop: Stop angle (in degrees).
208 :param nbSteps: Number of steps to perform the turn.
209 :return List[ColVector]: The corresponding list of commands.
210 """
211 cmds = []
212 dTheta = Math.rad(angleStop - angleStart) / float(nbSteps - 1)
213 for i in range(nbSteps):
214 theta = Math.rad(angleStart) + dTheta * float(i)
215 cmd = ColVector([v, theta])
216 cmds.append(cmd)
217 return cmds
218
219def generate_commands() -> List[ColVector]:
220 """
221 Generate the list of commands for the simulation.
222
223 :return List[ColVector]: The list of commands to use in the simulation
224 """
225 cmds = []
226 # Starting by a straight line acceleration
227 nbSteps = 30
228 dv = (1.1 - 0.001) / float(nbSteps - 1)
229 for i in range(nbSteps):
230 cmd = ColVector([0.001 + float(i) * dv, 0.])
231 cmds.append(cmd)
232
233 # Left turn
234 lastLinearVelocity = cmds[len(cmds) -1][0]
235 leftTurnCmds = generate_turn_commands(lastLinearVelocity, 0, 2, 15)
236 cmds.extend(leftTurnCmds)
237 for i in range(100):
238 cmds.append(cmds[len(cmds) -1])
239
240 # Right turn
241 lastLinearVelocity = cmds[len(cmds) -1][0]
242 rightTurnCmds = generate_turn_commands(lastLinearVelocity, 2, -2, 15);
243 cmds.extend(rightTurnCmds)
244 for i in range(200):
245 cmds.append(cmds[len(cmds) -1])
246
247 # Left turn again
248 lastLinearVelocity = cmds[len(cmds) -1][0]
249 leftTurnCmds = generate_turn_commands(lastLinearVelocity, -2, 0, 15)
250 cmds.extend(leftTurnCmds)
251 for i in range(150):
252 cmds.append(cmds[len(cmds) -1])
253
254 lastLinearVelocity = cmds[len(cmds) -1][0]
255 leftTurnCmds = generate_turn_commands(lastLinearVelocity, 0, 1, 25)
256 cmds.extend(leftTurnCmds)
257 for i in range(150):
258 cmds.append(cmds[len(cmds) -1])
259
260 return cmds
261
263 """
264 Class that approximates a 4-wheel robot unp.sing a bicycle model.
265 """
266 def __init__(self, w: float):
267 """
268 Construct a new vpBicycleModel object.
269
270 :param w:The length of the wheelbase.
271 """
272 self._w = w # The length of the wheelbase.
273
274 def compute_motion(self, u: ColVector, x: ColVector, dt: float) -> ColVector:
275 """
276 Models the effect of the command on the state model.
277
278 :param u: The commands. u[0] = velocity ; u[1] = steeringAngle .
279 :param x: The state model. x[0] = x ; x[1] = y ; x[2] = heading
280 :param dt: The period.
281 :return ColVector: The state model after applying the command.
282 """
283 heading = x[2]
284 vel = u[0]
285 steeringAngle = u[1]
286 distance = vel * dt
287
288 if (abs(steeringAngle) > 0.001):
289 # The robot is turning
290 beta = (distance / self._w) * np.tan(steeringAngle)
291 radius = self._w / np.tan(steeringAngle)
292 sinh = np.sin(heading)
293 sinhb = np.sin(heading + beta)
294 cosh = np.cos(heading)
295 coshb = np.cos(heading + beta)
296 motion = ColVector([
297 -radius * sinh + radius * sinhb,
298 radius * cosh - radius * coshb,
299 beta
300 ])
301 return motion
302 else:
303 # The robot is moving in straight line
304 motion = ColVector([
305 distance * np.cos(heading),
306 distance * np.sin(heading),
307 0.
308 ])
309 return motion
310
311 def move(self, u: ColVector, x: ColVector, dt: float) -> ColVector:
312 """
313 Models the effect of the command on the state model.
314
315 :param u: The commands. u[0] = velocity ; u[1] = steeringAngle .
316 :param x: The state model. x[0] = x ; x[1] = y ; x[2] = heading
317 :param dt: The period.
318 :return ColVector: The state model after applying the command.
319 """
320 motion = self.compute_motion(u, x, dt)
321 newX = x + motion
322 normalizedAngle = normalize_angle(newX[2])
323 return ColVector([newX[0], newX[1], normalizedAngle])
324
326 """
327 Class that permits to convert the position + heading of the 4-wheel
328 robot into measurements from a landmark.
329 """
330 def __init__(self, x: float, y: float, range_std: float, rel_angle_std: float):
331 """
332 Construct a new LandmarkMeasurements object.
333
334 :param x: The position along the x-axis of the landmark.
335 :param y: The position along the y-axis of the landmark.
336 :param range_std: The standard deviation of the range measurements.
337 :param rel_angle_std: The standard deviation of the relative angle measurements.
338 """
339 self._x = x # The position along the x-axis of the landmark
340 self._y = y # The position along the y-axis of the landmark
341 self._range_std = range_std # The standard deviation of the range measurement
342 self._rel_angle_std = rel_angle_std # The standard deviation of the relative angle measurement
343 np.random.seed(4224)
344
345 def state_to_measurement(self, chi: ColVector) -> ColVector:
346 """
347 Convert the prior of the UKF into the measurement space.
348
349 :param chi: The prior.
350 :return ColVector: The prior expressed in the measurement space.
351 """
352 dx = self._x - chi[0]
353 dy = self._y - chi[1]
354 meas = ColVector([sqrt(dx * dx + dy * dy), normalize_angle(np.arctan2(dy, dx) - chi[2])])
355 return meas
356
357 def measure_gt(self, pos: ColVector) -> ColVector:
358 """
359 Perfect measurement of the range and relative orientation of the robot
360 located at pos.
361
362 :param pos: The actual position of the robot (pos[0]: x, pos[1]: y, pos[2] = heading.
363 :return ColVector: [0] the range [1] the relative orientation of the robot.
364 """
365 dx = self._x - pos[0]
366 dy = self._y - pos[1]
367 range = sqrt(dx * dx + dy * dy)
368 orientation = normalize_angle(np.arctan2(dy, dx) - pos[2])
369 measurements = ColVector([range, orientation])
370 return measurements
371
372 def measure_with_noise(self, pos: ColVector) -> ColVector:
373 """
374 Noisy measurement of the range and relative orientation that
375 correspond to pos.
376
377 :param pos: The actual position of the robot (pos[0]: x ; pos[1] = y ; pos[2] = heading).
378 :return ColVector: [0] the range [1] the relative orientation.
379 """
380 measurementsGT = self.measure_gt(pos)
381 measurementsNoisy = measurementsGT
382 range = measurementsNoisy[0] + np.random.normal(0., self._range_std)
383 relAngle = normalize_angle(measurementsNoisy[1] + np.random.normal(0., self._rel_angle_std))
384 return ColVector([range, relAngle])
385
386
388 """
389 Class that represent a grid of landmarks that measure the distance and
390 relative orientation of the 4-wheel robot.
391 """
392 def __init__(self, landmarks: List[LandmarkMeasurements]):
393 """
394 Construct a new LandmarksGrid object.
395
396 :param landmarks: The list of landmarks forming the grid.
397 """
398 self._landmarks = landmarks # The list of landmarks forming the grid.
399
400 def state_to_measurement(self, chi: ColVector) -> ColVector:
401 """
402 Convert the prior of the UKF into the measurement space.
403
404 :param chi: The prior.
405 :return ColVector: The prior expressed in the measurement space.
406 """
407 nbLandmarks = len(self._landmarks)
408 measurements = np.zeros(2*nbLandmarks)
409 for i in range (nbLandmarks):
410 landmarkMeas = self._landmarks[i].state_to_measurement(chi)
411 measurements[2*i] = landmarkMeas[0]
412 measurements[(2*i) + 1] = landmarkMeas[1]
413 return ColVector(measurements)
414
415 def measure_gt(self, pos: ColVector) -> ColVector:
416 """
417 Perfect measurement from each landmark of the range and relative orientation of the robot
418 located at pos.
419
420 :param pos: The actual position of the robot (pos[0]: x, pos[1]: y, pos[2] = heading.
421 :return ColVector: n x ([0] the range [1] the relative orientation of the robot), where
422 n is the number of landmarks.
423 """
424 nbLandmarks = len(self._landmarks)
425 measurements = np.zeros(2*nbLandmarks)
426 for i in range(nbLandmarks):
427 landmarkMeas = self._landmarks[i].measure_gt(pos)
428 measurements[2*i] = landmarkMeas[0]
429 measurements[(2*i) + 1] = landmarkMeas[1]
430 return ColVector(measurements)
431
432 def measure_with_noise(self, pos: ColVector) -> ColVector:
433 """
434 Noisy measurement from each landmark of the range and relative orientation that
435 correspond to pos.
436
437 :param pos: The actual position of the robot (pos[0]: x ; pos[1] = y ; pos[2] = heading).
438 :return ColVector: n x ([0] the range [1] the relative orientation of the robot), where
439 n is the number of landmarks.
440 """
441 nbLandmarks = len(self._landmarks)
442 measurements = np.zeros(2*nbLandmarks)
443 for i in range(nbLandmarks):
444 landmarkMeas = self._landmarks[i].measure_with_noise(pos)
445 measurements[2*i] = landmarkMeas[0]
446 measurements[(2*i) + 1] = landmarkMeas[1]
447 return ColVector(measurements)
448
449if __name__ == '__main__':
450 dt = 0.1 # Period of 0.1s
451 step = 1. # Number of update of the robot position between two UKF filtering
452 sigma_range = 0.3 # Standard deviation of the range measurement: 0.3m
453 sigma_bearing = Math.rad(0.5) # Standard deviation of the bearing angle: 0.5deg
454 wheelbase = 0.5 # Wheelbase of 0.5m
455 process_variance = 0.0001
456 positions = [ (5, 10) , (10, 5), (15, 15), (20, 5), (0, 30), (50, 30), (40, 10)] # Positions of the landmarks constituting the grid
457 landmarks = [LandmarkMeasurements(x, y, sigma_range, sigma_bearing) for x,y in positions] # Vector of landmarks constituting the grid
458 nbLandmarks = len(landmarks) # Number of landmarks constituting the grid
460 nb_cmds = len(cmds)
461
462 # Creation of the simulated grid of landmarks and robot
463 grid = LandmarksGrid(landmarks)
464 robot = vpBicycleModel(wheelbase)
465
466 # The object that draws the sigma points used by the UKF
467 drawer = UKSigmaDrawerMerwe(n=3, alpha=0.1, beta=2, kappa=0, resFunc=state_residual_vectors, addFunc=state_add_vectors)
468
469 # The matrices require for the construction of the Unscented filter
470 P0 = Matrix([[0.1, 0., 0.],
471 [0., 0.1, 0.],
472 [0., 0., 0.05]]) # The initial estimate of the state covariance matrix
473 R1landmark = Matrix([[sigma_range * sigma_range, 0], [0, sigma_bearing*sigma_bearing]]) # The measurement covariance matrix for 1 landmark
474 R = Matrix(2*nbLandmarks, 2 * nbLandmarks) # The measurement covariance matrix for the grid of landmarks
475 for i in range(nbLandmarks):
476 R.insert(R1landmark, 2*i, 2*i)
477
478 Q = Matrix() # The process covariance matrix
479 Q.eye(3)
480 Q = Q * process_variance
481 X0 = ColVector([2., 6., 0.3]) # robot_x, robot_y, robot_orientation(rad)
482
483 # Creation of the Unscented Kalman filter
484 ukf = UnscentedKalman(Q, R, drawer, fx, grid.state_to_measurement) # The Unscented Kalman Filter instance
485
486 # Initializing the state vector and state covariance matrix estimates
487 ukf.init(X0, P0)
488 ukf.setCommandStateFunction(robot.compute_motion)
489 ukf.setMeasurementMeanFunction(measurement_mean)
490 ukf.setMeasurementResidualFunction(measurement_residual)
491 ukf.setStateAddFunction(state_add_vectors)
492 ukf.setStateMeanFunction(state_mean_vectors)
493 ukf.setStateResidualFunction(state_residual_vectors)
494
495 # Initializing the Graphical User Interface if the needed libraries are available
496 if has_gui:
497 num_plots = 1
498 plot = Plot(num_plots)
499 plot.initGraph(0, 2)
500 plot.setTitle(0, "Position of the robot")
501 plot.setUnitX(0, "Position along x(m)")
502 plot.setUnitY(0, "Position along y (m)")
503 plot.setLegend(0, 0, "GT")
504 plot.setLegend(0, 1, "Filtered")
505
506 robot_pos = X0
507 for i in range(nb_cmds):
508 robot_pos = robot.move(cmds[i], robot_pos, dt / step)
509
510 if (i % int(step) == 0):
511 # Perform the measurement
512 z = grid.measure_with_noise(robot_pos)
513
514 # Use the UKF to filter the measurement
515 ukf.filter(z, dt, cmds[i])
516
517 if has_gui:
518 # Plot the filtered state
519 Xest = ukf.getXest()
520 plot.plot(0, 1, Xest[0], Xest[1])
521
522 # Update the GUI if available
523 if has_gui:
524 # Plot the ground truth
525 plot.plot(0, 0, robot_pos[0], robot_pos[1])
526
527 print('Finished')
528 input('Press enter to quit')
__init__(self, float x, float y, float range_std, float rel_angle_std)
__init__(self, List[LandmarkMeasurements] landmarks)
ColVector compute_motion(self, ColVector u, ColVector x, float dt)
ColVector move(self, ColVector u, ColVector x, float dt)
ColVector state_add_vectors(ColVector a, ColVector b)
ColVector measurement_mean(List[ColVector] measurements, List[float] wm)
ColVector state_mean_vectors(List[ColVector] states, List[float] wm)
ColVector fx(ColVector x, float dt)
List[ColVector] generate_turn_commands(float v, float angleStart, float angleStop, int nbSteps)
ColVector measurement_residual(ColVector meas, ColVector to_subtract)