forked from cpv/Buoyant-Block
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathskew.m
43 lines (39 loc) · 1.27 KB
/
skew.m
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
%SKEW Create skew-symmetric matrix
%
% S = SKEW(V) is a skew-symmetric matrix formed from V (3x1).
%
% | 0 -vz vy|
% | vz 0 -vx|
% |-vy vx 0 |
%
% See also VEX.
% Copyright (C) 1993-2015, by Peter I. Corke
%
% This file is part of The Robotics Toolbox for MATLAB (RTB).
%
% RTB is free software: you can redistribute it and/or modify
% it under the terms of the GNU Lesser General Public License as published by
% the Free Software Foundation, either version 3 of the License, or
% (at your option) any later version.
%
% RTB is distributed in the hope that it will be useful,
% but WITHOUT ANY WARRANTY; without even the implied warranty of
% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
% GNU Lesser General Public License for more details.
%
% You should have received a copy of the GNU Leser General Public License
% along with RTB. If not, see <http://www.gnu.org/licenses/>.
%
% http://www.petercorke.com
function S = skew(v)
if isvec(v,3)
% SO(3) case
S = [ 0 -v(3) v(2)
v(3) 0 -v(1)
-v(2) v(1) 0];
elseif isvec(v,1)
% SO(2) case
S = [0 -v; v 0];
else
error('argument must be a 1- or 3-vector');
end