TR2ANGVEC Convert to angle/vector form [THETA V] = TR2ANGVEC(M) Returns a vector/angle representation of the pose corresponding to M, either a rotation matrix or the rotation part of a homogeneous transform. This is a rotation of THETA about the vector V. See also: ANGVEC2R, ANGVEC2TR
0001 %TR2ANGVEC Convert to angle/vector form 0002 % 0003 % [THETA V] = TR2ANGVEC(M) 0004 % 0005 % Returns a vector/angle representation of the pose corresponding to M, either a rotation 0006 % matrix or the rotation part of a homogeneous transform. 0007 % This is a rotation of THETA about the vector V. 0008 % 0009 % See also: ANGVEC2R, ANGVEC2TR 0010 0011 % Copyright (C) 1993-2008, by Peter I. Corke 0012 % 0013 % This file is part of The Robotics Toolbox for Matlab (RTB). 0014 % 0015 % RTB is free software: you can redistribute it and/or modify 0016 % it under the terms of the GNU Lesser General Public License as published by 0017 % the Free Software Foundation, either version 3 of the License, or 0018 % (at your option) any later version. 0019 % 0020 % RTB is distributed in the hope that it will be useful, 0021 % but WITHOUT ANY WARRANTY; without even the implied warranty of 0022 % MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 0023 % GNU Lesser General Public License for more details. 0024 % 0025 % You should have received a copy of the GNU Leser General Public License 0026 % along with RTB. If not, see <http://www.gnu.org/licenses/>. 0027 0028 function [theta, v] = tr2angvec(t) 0029 0030 qs = sqrt(trace(t)+1)/2.0; 0031 qs 0032 kx = t(3,2) - t(2,3); % Oz - Ay 0033 ky = t(1,3) - t(3,1); % Ax - Nz 0034 kz = t(2,1) - t(1,2); % Ny - Ox 0035 0036 if (t(1,1) >= t(2,2)) & (t(1,1) >= t(3,3)) 0037 kx1 = t(1,1) - t(2,2) - t(3,3) + 1; % Nx - Oy - Az + 1 0038 ky1 = t(2,1) + t(1,2); % Ny + Ox 0039 kz1 = t(3,1) + t(1,3); % Nz + Ax 0040 add = (kx >= 0); 0041 elseif (t(2,2) >= t(3,3)) 0042 kx1 = t(2,1) + t(1,2); % Ny + Ox 0043 ky1 = t(2,2) - t(1,1) - t(3,3) + 1; % Oy - Nx - Az + 1 0044 kz1 = t(3,2) + t(2,3); % Oz + Ay 0045 add = (ky >= 0); 0046 else 0047 kx1 = t(3,1) + t(1,3); % Nz + Ax 0048 ky1 = t(3,2) + t(2,3); % Oz + Ay 0049 kz1 = t(3,3) - t(1,1) - t(2,2) + 1; % Az - Nx - Oy + 1 0050 add = (kz >= 0); 0051 end 0052 0053 if add 0054 kx = kx + kx1; 0055 ky = ky + ky1; 0056 kz = kz + kz1; 0057 else 0058 kx = kx - kx1; 0059 ky = ky - ky1; 0060 kz = kz - kz1; 0061 end 0062 v = unit([kx ky kz]); 0063 theta = 2*acos(qs); 0064 0065 if nargout == 0 0066 fprintf('Rotation: %f rad x [%f %f %f]\n', theta, v(1), v(2), v(3)); 0067 end