diff --git a/mr/ub8/localize.png b/mr/ub8/localize.png new file mode 100644 index 0000000..31a3be5 --- /dev/null +++ b/mr/ub8/localize.png Binary files differ diff --git a/mr/ub8/localize_jp/get_angle_bracket.m b/mr/ub8/localize_jp/get_angle_bracket.m new file mode 100644 index 0000000..982c4cf --- /dev/null +++ b/mr/ub8/localize_jp/get_angle_bracket.m @@ -0,0 +1,19 @@ +function [ p ] = get_angle_bracket( mean, cov ) +%GET_ANGLE_BRACKET Compute points visualizing 95% orientation uncertainty + +scale = 2; % in multiples of sigma +length = 0.5; % length of both arms of the "bracket" + +p = zeros(2,3); + +theta = mean(3); +sigmaTheta = sqrt(cov(3,3)); % marginalized standard deviation of theta +th1 = theta - scale*sigmaTheta; +th3 = theta + scale*sigmaTheta; + +p(:,2) = mean(1:2); +p(:,1) = mean(1:2) + length*[cos(th1); sin(th1)]; +p(:,3) = mean(1:2) + length*[cos(th3); sin(th3)]; + +end + diff --git a/mr/ub8/localize_jp/get_ellipse.m b/mr/ub8/localize_jp/get_ellipse.m new file mode 100644 index 0000000..4f1cfb0 --- /dev/null +++ b/mr/ub8/localize_jp/get_ellipse.m @@ -0,0 +1,25 @@ +function [ p ] = get_ellipse( mean, cov ) +%GET_ELLIPSE Compute points on the 95% uncertainty ellipse. + +% Compute eigenvalues and eigenvectors of marginalized position covariance +[V D] = eig(cov(1:2,1:2)); +[D order] = sort(diag(D),'descend'); %sort eigenvalues in descending order +V = V(:,order); +evec_max = V(:, 1); % eigenvector with alrgest eigenvalue + +% Construct uncertainty ellipse in parallel to eigenvectors +scale = 2.; % in multiples of sigma +a = scale*sqrt(D(1)); +b = scale*sqrt(D(2)); +theta_grid = linspace(0,2*pi); +ellipse_x_r = a*cos( theta_grid ); +ellipse_y_r = b*sin( theta_grid ); + +% Transform to world frame +phi = atan2(evec_max(2), evec_max(1)); % Angle between x and largest EV +R = [cos(phi) -sin(phi); sin(phi) cos(phi)]; +p = R*[ellipse_x_r;ellipse_y_r]; +p = p + repmat(mean(1:2),1,size(p,2)); + +end + diff --git a/mr/ub8/localize_jp/localize.m b/mr/ub8/localize_jp/localize.m new file mode 100644 index 0000000..1293290 --- /dev/null +++ b/mr/ub8/localize_jp/localize.m @@ -0,0 +1,79 @@ +close all; + +% ## General parameters +% Fix random seed so everyone gets the same results. +rng(230) +% Sampling time: +dt = 0.2; +% System noise: +R = diag([0.02^2, 0.02^2, 0.02^2]); +% Measurement noise (1D measurements): +Q = 0.5^2; +% Construct vector with control input: +uhc = repmat([0.1; 0.105], 1, 63); +ust = repmat([0.1; 0.1], 1, 30); +u = [uhc, ust, uhc, ust]; + +% ## Compute the true trajectory: +% Evaluate kinematic model according to control input +% and add some sampled system noise. +currx = [0; 0; 0]; +x_true = currx; +z_meas = []; +for i = 1:size(u,2) + % Evaluate kinematic Model: + currx = motion_diff(currx, u(:,i)); + % Add system noise: + currx = currx + mvnrnd([0; 0; 0], R)'; + % Simulate a measurement: + z_meas = [z_meas, measurement(currx) + mvnrnd(zeros(size(Q,1),1),Q)']; + % Store result for plotting + x_true = [x_true, currx]; +end + +% ## Evaluate EKF without measurements: +% Estimates are based on control input alone. +curr_mean = [0; 0; 0]; +curr_cov = diag([0, 0, 0]); + +nomeas_mean = curr_mean; +nomeas_cov = reshape(curr_cov, 9, 1); +for i = 1:size(u,2) + % Update mean and Jacobian G: + [curr_mean G] = motion_diff(curr_mean, u(:,i)); + + % Update covariance matrix + curr_cov = G*curr_cov*(G') + R; + + % Store result for plotting + nomeas_mean = [nomeas_mean, curr_mean]; + nomeas_cov = [nomeas_cov, reshape(curr_cov, 9, 1)]; +end % for each u +plot_trajectory_cov(x_true, nomeas_mean, nomeas_cov, dt); + +% ## Full EKF: Estimates based on control input and measurements. +curr_mean = [0; 0; 0]; +curr_cov = diag([0. 0, 0]); + +ekf_mean = curr_mean; +ekf_cov = reshape(curr_cov, 9, 1); +for i = 1:size(u,2) + % Update step: + [curr_mean G] = motion_diff(curr_mean, u(:,i)); + curr_cov = G*curr_cov*(G') + R; + + % Correction step: + % Expected measurement: + [z_exp, H] = measurement(curr_mean); + + % Kalman gain: + K = curr_cov * (H') * inv(H*curr_cov*(H') + Q); + curr_mean = curr_mean + K*(z_meas(:,i) - z_exp); + curr_cov = (eye(3) - K*H)*curr_cov; + + % Store result for plotting + ekf_mean = [ekf_mean, curr_mean]; + ekf_cov = [ekf_cov, reshape(curr_cov, 9, 1)]; +end % for each u + +plot_trajectory_cov(x_true, ekf_mean, ekf_cov, dt); \ No newline at end of file diff --git a/mr/ub8/localize_jp/measurement.m b/mr/ub8/localize_jp/measurement.m new file mode 100644 index 0000000..35c902f --- /dev/null +++ b/mr/ub8/localize_jp/measurement.m @@ -0,0 +1,16 @@ +function [ z H ] = measurement( x ) +%MEASUREMENT Measurement Model: Measure the robot's distance from origin. + +% YOUR CODE STARTS HERE + +z = sqrt(x(1)*x(1)+x(2)*x(2)); % fill this with the measurement result +syms x1 x2 x3 +H=jacobian(sqrt(x1*x1+x2*x2),[x1;x2;x3]); +x1=x(1); +x2=x(2); +H = eval(H); % fill this with the measurement Jacobian + +% YOUR CODE ENDS HERE + +end + diff --git a/mr/ub8/localize_jp/motion_diff.m b/mr/ub8/localize_jp/motion_diff.m new file mode 100644 index 0000000..848f892 --- /dev/null +++ b/mr/ub8/localize_jp/motion_diff.m @@ -0,0 +1,27 @@ +function [ xnew G] = motion_diff( x, u ) +%MOTION_DIFF Compute differential drive motion model + +l = 0.1; % distance between both wheels + +theta = x(3); +sl = u(1); +sr = u(2); + +% YOUR CODE STARTS HERE % +syms x1 x2 x3 + +if (sl == sr) + xnew=x+sl*[cos(theta);sin(theta);0]; + G=jacobian([x1;x2;x3]+sl*[cos(x3);sin(x3);0],[x1;x2;x3]); +else + r=(sl+sr)/(sr-sl)*l/2; + dtheta=(sr-sl)/l; + xnew=x+[r*(sin(theta+dtheta)-sin(theta));r*(-cos(theta+dtheta)+cos(theta));dtheta]; + G=jacobian([x1;x2;x3]+[r*(sin(x3+dtheta)-sin(x3));r*(-cos(x3+dtheta)+cos(x3));dtheta],[x1;x2;x3]); +end +x3=theta; +G=eval(G); +% YOUR CODE ENDS HERE % + +end + diff --git a/mr/ub8/localize_jp/plot_trajectory_cov.m b/mr/ub8/localize_jp/plot_trajectory_cov.m new file mode 100644 index 0000000..5e11454 --- /dev/null +++ b/mr/ub8/localize_jp/plot_trajectory_cov.m @@ -0,0 +1,46 @@ +function [ ] = plot_trajectory_cov(xtrue, mean, cov, dt ) +%PLOT_TRAJECTORY_COV Plot the 2d trajectory of a robot with uncertainty +% estimates + +% Create a new figure for this plot +figure + +% Plot ground truth trajectory: +plot(xtrue(1,:), xtrue(2,:), 'r'); + +hold on % keep drawing into the same figure + +% Draw the estimate of the same trajectory. +plot(mean(1,:), mean(2,:)) + +% Only at some times: Visualize the estimate uncertainty. +ellipsetime = 4/dt; % Once in 4 seconds +em = mean(:,1:ellipsetime:end); +ecov = cov(:,1:ellipsetime:end); + +% Draw uncertainty ellipses +for i = 1:size(ecov,2) + s = reshape(ecov(:,i),3,3); + + % Compute and plot uncertainty ellipse for position covariance. + p_pos = get_ellipse(em(:,i), s); + plot(p_pos(1,:), p_pos(2,:),'k'); + + % Compute and plot angle interval showing orientation uncertainty. + p_th = get_angle_bracket(em(:,i), s); + plot(p_th(1,:), p_th(2,:),'k'); +end + +% Description & legend +axis equal +xlabel('x in m') +ylabel('y in m') +title('robot trajectory with uncertainty estimates') +legend('true trajectory', ... + 'estimate (mean)', ... + 'estimate (covariance)', ... + 'location', 'SouthEast'); + + +end +