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.
41 The state vector of the UKF is:
44 \textbf{x}[0] &=& x \\
45 \textbf{x}[1] &=& y \\
46 \textbf{x}[2] &=& \theta
49 where \f$ \theta \f$ is the heading of the robot.
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:
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
61 Some noise is added to the measurement vector to simulate measurements which are
64 The mean of several angles must be computed in the Unscented Transform. The definition we chose to use
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$
69 As the Unscented Transform uses a weighted mean, the actual implementation of the weighted mean
70 of several angles is the following:
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$
74 where \f$ w_m^i \f$ is the weight associated to the \f$ i^{th} \f$ measurements for the weighted mean.
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$ .
81from visp.core
import ColVector, Matrix, UnscentedKalman, UKSigmaDrawerMerwe, Math
83from typing
import List
88 from visp.gui
import Plot
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:
99 angle_MinPi_Pi = angle_MinPi_Pi - 2. * np.pi
100 return angle_MinPi_Pi
104 Compute the weighted mean of measurement vectors.
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.
110 :return ColVector: The weighted mean.
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)
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]
125 orientations = np.arctan2(sum_sin, sum_cos)
126 mean[1::2] = orientations
127 return ColVector(mean)
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 ...
134 :param meas: Measurement to which we must subtract something.
135 :param toSubtract: The something we must subtract.
137 :return ColVector: \b meas - \b toSubtract .
139 res = meas.numpy() - to_subtract.numpy()
141 return ColVector(res)
145 Compute the addition between two vectors expressed in the state space,
146 such as v[0] = x ; v[1] = y; v[2] = heading .
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.
151 :return ColVector: The sum a + b.
159 Compute the weighted mean of state vectors.
161 :param states: The state vectors.
162 :param wm: The associated weights.
163 :return ColVector: The weighted mean.
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)
178 Compute the subtraction between two vectors expressed in the state space,
179 such as v[0] = x ; v[1] = y; v[2] = heading .
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.
184 :return ColVector: The subtraction a - b.
189def fx(x: ColVector, dt: float) -> ColVector:
191 As the state model {x, y, \f$ \theta \f$} does not contain any velocity
192 information, it does not evolve without commands.
194 :param x: The internal state of the UKF.
195 :param dt: The sampling time: how far in the future are we projecting x.
197 :return ColVector: The updated internal state, projected in time, also known as the prior.
203 Compute the commands realising a turn at constant linear velocity.
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.
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])
221 Generate the list of commands for the simulation.
223 :return List[ColVector]: The list of commands to use in the simulation
228 dv = (1.1 - 0.001) / float(nbSteps - 1)
229 for i
in range(nbSteps):
230 cmd = ColVector([0.001 + float(i) * dv, 0.])
234 lastLinearVelocity = cmds[len(cmds) -1][0]
236 cmds.extend(leftTurnCmds)
238 cmds.append(cmds[len(cmds) -1])
241 lastLinearVelocity = cmds[len(cmds) -1][0]
243 cmds.extend(rightTurnCmds)
245 cmds.append(cmds[len(cmds) -1])
248 lastLinearVelocity = cmds[len(cmds) -1][0]
250 cmds.extend(leftTurnCmds)
252 cmds.append(cmds[len(cmds) -1])
254 lastLinearVelocity = cmds[len(cmds) -1][0]
256 cmds.extend(leftTurnCmds)
258 cmds.append(cmds[len(cmds) -1])
264 Class that approximates a 4-wheel robot unp.sing a bicycle model.
268 Construct a new vpBicycleModel object.
270 :param w:The length of the wheelbase.
276 Models the effect of the command on the state model.
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.
288 if (abs(steeringAngle) > 0.001):
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)
297 -radius * sinh + radius * sinhb,
298 radius * cosh - radius * coshb,
305 distance * np.cos(heading),
306 distance * np.sin(heading),
311 def move(self, u: ColVector, x: ColVector, dt: float) -> ColVector:
313 Models the effect of the command on the state model.
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.
323 return ColVector([newX[0], newX[1], normalizedAngle])
327 Class that permits to convert the position + heading of the 4-wheel
328 robot into measurements from a landmark.
330 def __init__(self, x: float, y: float, range_std: float, rel_angle_std: float):
332 Construct a new LandmarkMeasurements object.
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.
347 Convert the prior of the UKF into the measurement space.
349 :param chi: The prior.
350 :return ColVector: The prior expressed in the measurement space.
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])])
359 Perfect measurement of the range and relative orientation of the robot
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.
365 dx = self.
_x - pos[0]
366 dy = self.
_y - pos[1]
367 range = sqrt(dx * dx + dy * dy)
369 measurements = ColVector([range, orientation])
374 Noisy measurement of the range and relative orientation that
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.
381 measurementsNoisy = measurementsGT
382 range = measurementsNoisy[0] + np.random.normal(0., self.
_range_std)
384 return ColVector([range, relAngle])
389 Class that represent a grid of landmarks that measure the distance and
390 relative orientation of the 4-wheel robot.
392 def __init__(self, landmarks: List[LandmarkMeasurements]):
394 Construct a new LandmarksGrid object.
396 :param landmarks: The list of landmarks forming the grid.
402 Convert the prior of the UKF into the measurement space.
404 :param chi: The prior.
405 :return ColVector: The prior expressed in the measurement space.
408 measurements = np.zeros(2*nbLandmarks)
409 for i
in range (nbLandmarks):
411 measurements[2*i] = landmarkMeas[0]
412 measurements[(2*i) + 1] = landmarkMeas[1]
413 return ColVector(measurements)
417 Perfect measurement from each landmark of the range and relative orientation of the robot
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.
425 measurements = np.zeros(2*nbLandmarks)
426 for i
in range(nbLandmarks):
428 measurements[2*i] = landmarkMeas[0]
429 measurements[(2*i) + 1] = landmarkMeas[1]
430 return ColVector(measurements)
434 Noisy measurement from each landmark of the range and relative orientation that
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.
442 measurements = np.zeros(2*nbLandmarks)
443 for i
in range(nbLandmarks):
445 measurements[2*i] = landmarkMeas[0]
446 measurements[(2*i) + 1] = landmarkMeas[1]
447 return ColVector(measurements)
449if __name__ ==
'__main__':
453 sigma_bearing = Math.rad(0.5)
455 process_variance = 0.0001
456 positions = [ (5, 10) , (10, 5), (15, 15), (20, 5), (0, 30), (50, 30), (40, 10)]
458 nbLandmarks = len(landmarks)
467 drawer = UKSigmaDrawerMerwe(n=3, alpha=0.1, beta=2, kappa=0, resFunc=state_residual_vectors, addFunc=state_add_vectors)
470 P0 = Matrix([[0.1, 0., 0.],
473 R1landmark = Matrix([[sigma_range * sigma_range, 0], [0, sigma_bearing*sigma_bearing]])
474 R = Matrix(2*nbLandmarks, 2 * nbLandmarks)
475 for i
in range(nbLandmarks):
476 R.insert(R1landmark, 2*i, 2*i)
480 Q = Q * process_variance
481 X0 = ColVector([2., 6., 0.3])
484 ukf = UnscentedKalman(Q, R, drawer, fx, grid.state_to_measurement)
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)
498 plot = Plot(num_plots)
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")
507 for i
in range(nb_cmds):
508 robot_pos = robot.move(cmds[i], robot_pos, dt / step)
510 if (i % int(step) == 0):
512 z = grid.measure_with_noise(robot_pos)
515 ukf.filter(z, dt, cmds[i])
520 plot.plot(0, 1, Xest[0], Xest[1])
525 plot.plot(0, 0, robot_pos[0], robot_pos[1])
528 input(
'Press enter to quit')
__init__(self, float x, float y, float range_std, float rel_angle_std)
ColVector measure_with_noise(self, ColVector pos)
ColVector state_to_measurement(self, ColVector chi)
ColVector measure_gt(self, ColVector pos)
ColVector state_to_measurement(self, ColVector chi)
ColVector measure_with_noise(self, ColVector pos)
__init__(self, List[LandmarkMeasurements] landmarks)
ColVector measure_gt(self, ColVector pos)
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)
List[ColVector] generate_commands()
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)
float normalize_angle(float angle)
ColVector state_residual_vectors(a, b)