https://github.com/RomaTeng/EKF-SLAM-on-Manifold
Raw File
Tip revision: 12d7d8d88c84161baed173e38d49dedb4adb2b96 authored by Teng Zhang on 26 February 2017, 15:09:17 UTC
Record my control paper
Tip revision: 12d7d8d
so3_exp.m
function [ result ] = so3_exp( x )
% compute the exponential mapping of R^3 to SO(3)
% use sparse matrix
	N = size(x,1);
	%if N == 3
        theta=norm(x);
        if theta==0
            result=eye(3);
        else     
            omega =x/theta;
            result=eye(3,3) + sin(theta) * skew(omega) + (1 - cos(theta))*skew(omega)^2;  
        end
		      
    %else
        % todo, compute exp() of R^6 to SE(3)?
    %    m = (N-3)/3;
    %    result=speye(3+m);
    %    result(1:3,1:3)=Exp( x(1:3));
    %end
end

back to top