forked from petercorke/robotics-toolbox-matlab
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Quaternion.m
749 lines (657 loc) · 24.4 KB
/
Quaternion.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
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
%QUATERNION Quaternion class
%
% A quaternion is a compact method of representing a 3D rotation that has
% computational advantages including speed and numerical robustness.
% A quaternion has 2 parts, a scalar s, and a vector v and is typically
% written: q = s <vx, vy, vz>.
%
% A unit-quaternion is one for which s^2+vx^2+vy^2+vz^2 = 1. It can be
% considered as a rotation by an angle theta about a unit-vector V in space where
%
% q = cos (theta/2) < v sin(theta/2)>
%
% Q = Quaternion(X) is a unit-quaternion equivalent to X which can be any
% of:
% - orthonormal rotation matrix.
% - homogeneous transformation matrix (rotation part only).
% - rotation angle and vector
%
% Methods::
% inv inverse of quaterion
% norm norm of quaternion
% unit unitized quaternion
% plot same options as trplot()
% interp interpolation (slerp) between q and q2, 0<=s<=1
% scale interpolation (slerp) between identity and q, 0<=s<=1
% dot derivative of quaternion with angular velocity w
% R equivalent 3x3 rotation matrix
% T equivalent 4x4 homogeneous transform matrix
% double quaternion elements as 4-vector
% inner inner product of two quaternions
%
% Overloaded operators::
% q1==q2 test for quaternion equality
% q1~=q2 test for quaternion inequality
% q+q2 elementwise sum of quaternions
% q-q2 elementwise difference of quaternions
% q*q2 quaternion product
% q*v rotate vector by quaternion, v is 3x1
% s*q elementwise multiplication of quaternion by scalar
% q/q2 q*q2.inv
% q^n q to power n (integer only)
%
% Properties (read only)::
% s real part
% v vector part
%
% Notes::
% - Quaternion objects can be used in vectors and arrays.
%
% References::
% - Animating rotation with quaternion curves,
% K. Shoemake,
% in Proceedings of ACM SIGGRAPH, (San Fran cisco), pp. 245-254, 1985.
% - On homogeneous transforms, quaternions, and computational efficiency,
% J. Funda, R. Taylor, and R. Paul,
% IEEE Transactions on Robotics and Automation, vol. 6, pp. 382-388, June 1990.
% - Robotics, Vision & Control,
% P. Corke, Springer 2011.
%
% See also trinterp, trplot.
% TODO
% properties s, v for the vector case
% 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
% TODO
% constructor handles R, T trajectory and returns vector
% .r, .t on a quaternion vector??
classdef Quaternion
properties (SetAccess = private)
s % scalar part
v % vector part
end
methods
function q = Quaternion(a1, a2)
%Quaternion.Quaternion Constructor for quaternion objects
%
% Construct a quaternion from various other orientation representations.
%
% Q = Quaternion() is the identitity unit-quaternion 1<0,0,0> representing a null rotation.
%
% Q = Quaternion(Q1) is a copy of the quaternion Q1
%
% Q = Quaternion([S V1 V2 V3]) is a quaternion formed by specifying directly its 4 elements
%
% Q = Quaternion(S) is a quaternion formed from the scalar S and zero vector part: S<0,0,0>
%
% Q = Quaternion(V) is a pure quaternion with the specified vector part: 0<V>
%
% Q = Quaternion(TH, V) is a unit-quaternion corresponding to rotation of TH about the
% vector V.
%
% Q = Quaternion(R) is a unit-quaternion corresponding to the SO(3)
% orthonormal rotation matrix R (3x3). If R (3x3xN) is a sequence then Q
% (Nx1) is a vector of Quaternions corresponding to the elements of R.
%
% Q = Quaternion(T) is a unit-quaternion equivalent to the rotational part
% of the SE(3) homogeneous transform T (4x4). If T (4x4xN) is a sequence
% then Q (Nx1) is a vector of Quaternions corresponding to the elements of
% T.
if nargin == 0
q.v = [0,0,0];
q.s = 1;
elseif isa(a1, 'Quaternion')
% Q = Quaternion(q) from another quaternion
q = a1;
elseif nargin == 1
if isvec(a1, 4)
% Q = Quaternion([s v1 v2 v3]) from 4 elements
a1 = a1(:);
q.s = a1(1);
q.v = a1(2:4)';
elseif isrot(a1) || ishomog(a1)
% Q = Quaternion(R) from a 3x3 or 4x4 matrix
for i=1:size(a1,3)
q(i) = Quaternion( tr2q(a1(:,:,i)) );
end
elseif length(a1) == 3
% Q = Quaternion(v) from a vector
q.s = 0;
q.v = a1(:)';
elseif length(a1) == 1
% Q = Quaternion(s) from a scalar
q.s = a1(1);
q.v = [0 0 0];
else
error('RTB:Quaternion:badarg', 'unknown dimension of input');
end
elseif nargin == 2
if isscalar(a1) && isvector(a2)
% Q = Quaternion(theta, v) from vector plus angle
q.s = cos(a1/2);
q.v = sin(a1/2)*unit(a2(:)');
else
error ('RTB:Quaternion:badarg', 'bad argument to quaternion constructor');
end
end
end
function s = char(q)
%Quaternion.char Convert to string
%
% S = Q.char() is a compact string representation of the quaternion's value
% as a 4-tuple. If Q is a vector then S has one line per element.
if length(q) > 1
s = '';
for qq = q;
s = char(s, char(qq));
end
return
end
s = [num2str(q.s), ' < ' ...
num2str(q.v(1)) ', ' num2str(q.v(2)) ', ' num2str(q.v(3)) ' >'];
end
function display(q)
%Quaternion.display Display quaternion
%
% Q.display() displays a compact string representation of the quaternion's value
% as a 4-tuple. If Q is a vector then S has one line per element.
%
% Notes::
% - This method is invoked implicitly at the command line when the result
% of an expression is a Quaternion object and the command has no trailing
% semicolon.
%
% See also Quaternion.char.
loose = strcmp( get(0, 'FormatSpacing'), 'loose');
if loose
disp(' ');
end
disp([inputname(1), ' = '])
if loose
disp(' ');
end
disp(char(q))
if loose
disp(' ');
end
end
function v = double(q)
%Quaternion.double Convert a quaternion to a 4-element vector
%
% V = Q.double() is a 4-vector comprising the quaternion
% elements [s vx vy vz].
v = [q.s q.v];
end
function qi = inv(q)
%Quaternion.inv Invert a unit-quaternion
%
% QI = Q.inv() is a quaternion object representing the inverse of Q.
qi = Quaternion([q.s -q.v]);
end
function qu = unit(q)
%Quaternion.unit Unitize a quaternion
%
% QU = Q.unit() is a unit-quaternion representing the same orientation as Q.
%
% See also Quaternion.norm.
qu = q / norm(q);
end
function n = norm(q)
%Quaternion.norm Quaternion magnitude
%
% QN = Q.norm(Q) is the scalar norm or magnitude of the quaternion Q.
%
% Notes::
% - This is the Euclidean norm of the quaternion written as a 4-vector.
% - A unit-quaternion has a norm of one.
%
% See also Quaternion.inner, Quaternion.unit.
n = norm(double(q));
end
function n = inner(q1, q2)
%Quaternion.inner Quaternion inner product
%
% V = Q1.inner(Q2) is the inner (dot) product of two vectors (1x4),
% comprising the elements of Q1 and Q2 respectively.
%
% Notes::
% - Q1.inner(Q1) is the same as Q1.norm().
%
% See also Quaternion.norm.
n = double(q1)*double(q2)';
end
function q = interp(Q1, Q2, r, varargin)
%Quaternion.interp Interpolate quaternions
%
% QI = Q1.interp(Q2, S, OPTIONS) is a unit-quaternion that interpolates a rotation
% between Q1 for S=0 and Q2 for S=1.
%
% If S is a vector QI is a vector of quaternions, each element
% corresponding to sequential elements of S.
%
% Options::
% 'shortest' Take the shortest path along the great circle
%
% Notes::
% - This is a spherical linear interpolation (slerp) that can be interpretted
% as interpolation along a great circle arc on a sphere.
% - The value of S is clipped to the interval 0 to 1.
%
% References::
% - Animating rotation with quaternion curves,
% K. Shoemake,
% in Proceedings of ACM SIGGRAPH, (San Fran cisco), pp. 245-254, 1985.
%
% See also Quaternion.scale, ctraj.
q1 = double(Q1);
q2 = double(Q2);
opt.shortest = false;
opt = tb_optparse(opt, varargin);
cosTheta = q1*q2';
if opt.shortest
% take shortest path along the great circle, patch by Gauthier Gras
if cosTheta < 0
q1 = - q1;
cosTheta = - cosTheta;
end;
end
theta = acos(cosTheta);
count = 1;
% clip values of r
r(r<0) = 0;
r(r>1) = 1;
q(length(r)) = Quaternion(); % preallocate space for Quaternion vector
for i=1:length(r)
if theta == 0
q(i) = Q1;
else
q(i) = Quaternion( (sin((1-r(i))*theta) * q1 + sin(r(i)*theta) * q2) / sin(theta) );
end
end
end
function q = scale(Q, r)
%Quaternion.scale Interpolate rotations expressed by quaternion objects
%
% QI = Q.scale(S) is a unit-quaternion that interpolates between a null
% rotation (identity quaternion) for S=0 to Q for S=1. This is a spherical
% linear interpolation (slerp) that can be interpretted as interpolation
% along a great circle arc on a sphere.
%
% If S is a vector QI is a vector of quaternions, each element
% corresponding to sequential elements of S.
%
% Notes::
% - This is a spherical linear interpolation (slerp) that can be interpretted
% as interpolation along a great circle arc on a sphere.
%
% See also Quaternion.interp, ctraj.
q2 = double(Q);
if any(r<0) || (r>1)
error('r out of range');
end
q1 = [1 0 0 0]; % identity quaternion
theta = acos(q1*q2');
if length(r) == 1
if theta == 0
q = Q;
else
q = Quaternion( (sin((1-r)*theta) * q1 + sin(r*theta) * q2) / sin(theta) ).unit;
end
else
count = 1;
for R=r(:)'
if theta == 0
qq = Q;
else
qq = Quaternion( (sin((1-r)*theta) * q1 + sin(r*theta) * q2) / sin(theta) ).unit;
end
q(count) = qq;
count = count + 1;
end
end
end
function e = eq(q1, q2)
%EQ Test quaternion equality
%
% Q1==Q2 is true if the quaternions Q1 and Q2 are equal.
%
% Notes::
% - Overloaded operator '=='.
% - Note that for unit Quaternions Q and -Q are the equivalent
% rotation, so non-equality does not mean rotations are not
% equivalent.
% - If Q1 is a vector of quaternions, each element is compared to
% Q2 and the result is a logical array of the same length as Q1.
% - If Q2 is a vector of quaternions, each element is compared to
% Q1 and the result is a logical array of the same length as Q2.
% - If Q1 and Q2 are vectors of the same length, then the result
% is a logical array of the same length.
%
% See also Quaternion.ne.
if (numel(q1) == 1) && (numel(q2) == 1)
e = all( eq(q1.double, q2.double) );
elseif (numel(q1) > 1) && (numel(q2) == 1)
e = zeros(1, numel(q1));
for i=1:numel(q1)
e(i) = q1(i) == q2;
end
elseif (numel(q1) == 1) && (numel(q2) > 1)
e = zeros(1, numel(q2));
for i=1:numel(q2)
e(i) = q2(i) == q1;
end
elseif numel(q1) == numel(q2)
e = zeros(1, numel(q1));
for i=1:numel(q1)
e(i) = q1(i) == q2(i);
end
else
error('RTB:quaternion:badargs');
end
end
function e = ne(q1, q2)
%NE Test quaternion inequality
%
% Q1~=Q2 is true if the quaternions Q1 and Q2 are not equal.
%
% Notes::
% - Overloaded operator '~='
% - Note that for unit Quaternions Q and -Q are the equivalent
% rotation, so non-equality does not mean rotations are not
% equivalent.
% - If Q1 is a vector of quaternions, each element is compared to
% Q2 and the result is a logical array of the same length as Q1.
% - If Q2 is a vector of quaternions, each element is compared to
% Q1 and the result is a logical array of the same length as Q2.
% - If Q1 and Q2 are vectors of the same length, then the result
% is a logical array of the same length.
%
% See also Quaternion.eq.
if (numel(q1) == 1) && (numel(q2) == 1)
e = all( ne(q1.double, q2.double) );
elseif (numel(q1) > 1) && (numel(q2) == 1)
e = zeros(1, numel(q1));
for i=1:numel(q1)
e(i) = q1(i) ~= q2;
end
elseif (numel(q1) == 1) && (numel(q2) > 1)
e = zeros(1, numel(q2));
for i=1:numel(q2)
e(i) = q2(i) ~= q1;
end
elseif numel(q1) == numel(q2)
e = zeros(1, numel(q1));
for i=1:numel(q1)
e(i) = q1(i) ~= q2(i);
end
else
error('RTB:quaternion:badargs');
end
end
function qp = plus(q1, q2)
%PLUS Add quaternions
%
% Q1+Q2 is the element-wise sum of quaternion elements.
%
% Notes::
% - Overloaded operator '+'
% - The result is not guaranteed to be a unit-quaternion.
%
% See also Quaternion.minus, Quaternion.mtimes.
if isa(q1, 'Quaternion') && isa(q2, 'Quaternion')
qp = Quaternion(double(q1) + double(q2));
end
end
function qp = minus(q1, q2)
%Quaternion.minus Subtract quaternions
%
% Q1-Q2 is the element-wise difference of quaternion elements.
%
% Notes::
% - Overloaded operator '-'
% - The result is not guaranteed to be a unit-quaternion.
%
% See also Quaternion.plus, Quaternion.mtimes.
if isa(q1, 'Quaternion') && isa(q2, 'Quaternion')
qp = Quaternion(double(q1) - double(q2));
end
end
function qp = mtimes(q1, q2)
%Quaternion.mtimes Multiply a quaternion object
%
% Q1*Q2 is a quaternion formed by the Hamilton product of two quaternions.
% Q*V is a vector formed by rotating the vector V by the quaternion Q.
% Q*S is the element-wise multiplication of quaternion elements by the scalar S.
%
% Notes::
% - Overloaded operator '*'
% - If the two multiplicands are unit-quaternions, the product will be a
% unit quaternion.
%
% See also Quaternion.mrdivide, Quaternion.mpower, Quaternion.plus, Quaternion.minus.
if isa(q1, 'Quaternion') && isa(q2, 'Quaternion')
%QQMUL Multiply unit-quaternion by unit-quaternion
%
% QQ = qqmul(Q1, Q2)
%
% Return a product of unit-quaternions.
%
% See also: TR2Q
% decompose into scalar and vector components
s1 = q1.s; v1 = q1.v;
s2 = q2.s; v2 = q2.v;
% form the product
qp = Quaternion([s1*s2-v1*v2' s1*v2+s2*v1+cross(v1,v2)]);
elseif isa(q1, 'Quaternion') && isa(q2, 'double')
%QVMUL Multiply vector by unit-quaternion
%
% VT = qvmul(Q, V)
%
% Rotate the vector V by the unit-quaternion Q.
%
% See also: QQMUL, QINV
if length(q2) == 3
qp = q1 * Quaternion([0 q2(:)']) * inv(q1);
qp = qp.v(:);
elseif length(q2) == 1
qp = Quaternion( double(q1)*q2);
else
error('quaternion-vector product: must be a 3-vector or scalar');
end
elseif isa(q2, 'Quaternion') && isa(q1, 'double')
if length(q1) == 3
qp = q2 * Quaternion([0 q1(:)']) * inv(q2);
qp = qp.v;
elseif length(q1) == 1
qp = Quaternion( double(q2)*q1);
else
error('quaternion-vector product: must be a 3-vector or scalar');
end
end
end
function qp = mpower(q, p)
%Quaternion.mpower Raise quaternion to integer power
%
% Q^N is the quaternion Q raised to the integer power N.
%
% Notes::
% - Overloaded operator '^'
% - Computed by repeated multiplication.
% - If the argument is a unit-quaternion, the result will be a
% unit quaternion.
%
% See also Quaternion.mrdivide, Quaternion.mpower, Quaternion.plus, Quaternion.minus.
% check that exponent is an integer
if (p - floor(p)) ~= 0
error('quaternion exponent must be integer');
end
qp = q;
% multiply by itself so many times
for i = 2:abs(p)
qp = qp * q;
end
% if exponent was negative, invert it
if p<0
qp = inv(qp);
end
end
function qq = mrdivide(q1, q2)
%Quaternion.mrdivide Quaternion quotient.
%
% Q1/Q2 is a quaternion formed by Hamilton product of Q1 and inv(Q2).
% Q/S is the element-wise division of quaternion elements by the scalar S.
%
% Notes::
% - Overloaded operator '/'
% - If the dividend and divisor are unit-quaternions, the quotient will be a
% unit quaternion.
%
% See also Quaternion.mtimes, Quaternion.mpower, Quaternion.plus, Quaternion.minus.
if isa(q2, 'Quaternion')
% qq = q1 / q2
% = q1 * qinv(q2)
qq = q1 * inv(q2);
elseif isa(q2, 'double')
qq = Quaternion( double(q1) / q2 );
end
end
function plot(Q, varargin)
%Quaternion.plot Plot a quaternion object
%
% Q.plot(options) plots the quaternion as an oriented coordinate frame.
%
% Options::
% Options are passed to trplot and include:
%
% 'color',C The color to draw the axes, MATLAB colorspec C
% 'frame',F The frame is named {F} and the subscript on the axis labels is F.
% 'view',V Set plot view parameters V=[az el] angles, or 'auto'
% for view toward origin of coordinate frame
%
% See also trplot.
%axis([-1 1 -1 1 -1 1])
trplot( Q.R, varargin{:});
drawnow
end
function r = R(q)
%Quaternion.R Convert to orthonormal rotation matrix
%
% R = Q.R() is the equivalent SO(3) orthonormal rotation matrix (3x3). If
% Q represents a sequence (Nx1) then R is 3x3xN.
%
r = zeros(3,3,numel(q));
for i=1:numel(q)
r(:,:,i) = t2r( q2tr(q(i)) );
end
end
function t = T(q)
%Quaternion.T Convert to homogeneous transformation matrix
%
% T = Q.T() is the equivalent SE(3) homogeneous transformation matrix
% (4x4). If Q represents a sequence (Nx1) then T is 4x4xN.
%
% Notes:
% - Has a zero translational component.
t = zeros(4,4,numel(q));
for i=1:numel(q)
t(:,:,i) = q2tr(q(i));
end
end
function qd = dot(q, omega)
%Quaternion.dot Quaternion derivative
%
% QD = Q.dot(omega) is the rate of change of a frame with attitude Q and
% angular velocity OMEGA (1x3) expressed as a quaternion.
E = q.s*eye(3,3) - skew(q.v);
omega = omega(:);
qd = Quaternion([-0.5*q.v*omega; 0.5*E*omega]);
end
end % methods
end % classdef
%TR2Q Convert homogeneous transform to a unit-quaternion
%
% Q = tr2q(T)
%
% Return a unit-quaternion corresponding to the rotational part of the
% homogeneous transform T.
%
% See also: Q2TR
function q = tr2q(t)
if ishomog(t)
t = t2r(t);
end
qs = sqrt(trace(t)+1)/2.0;
kx = t(3,2) - t(2,3); % Oz - Ay
ky = t(1,3) - t(3,1); % Ax - Nz
kz = t(2,1) - t(1,2); % Ny - Ox
if (t(1,1) >= t(2,2)) && (t(1,1) >= t(3,3))
kx1 = t(1,1) - t(2,2) - t(3,3) + 1; % Nx - Oy - Az + 1
ky1 = t(2,1) + t(1,2); % Ny + Ox
kz1 = t(3,1) + t(1,3); % Nz + Ax
add = (kx >= 0);
elseif (t(2,2) >= t(3,3))
kx1 = t(2,1) + t(1,2); % Ny + Ox
ky1 = t(2,2) - t(1,1) - t(3,3) + 1; % Oy - Nx - Az + 1
kz1 = t(3,2) + t(2,3); % Oz + Ay
add = (ky >= 0);
else
kx1 = t(3,1) + t(1,3); % Nz + Ax
ky1 = t(3,2) + t(2,3); % Oz + Ay
kz1 = t(3,3) - t(1,1) - t(2,2) + 1; % Az - Nx - Oy + 1
add = (kz >= 0);
end
if add
kx = kx + kx1;
ky = ky + ky1;
kz = kz + kz1;
else
kx = kx - kx1;
ky = ky - ky1;
kz = kz - kz1;
end
nm = norm([kx ky kz]);
if nm == 0
q = Quaternion([1 0 0 0]);
else
s = sqrt(1 - qs^2) / nm;
qv = s*[kx ky kz];
q = Quaternion([qs qv]);
end
end
%Q2TR Convert unit-quaternion to homogeneous transform
%
% T = q2tr(Q)
%
% Return the rotational homogeneous transform corresponding to the unit
% quaternion Q.
%
% See also: TR2Q
function t = q2tr(q)
q = double(q);
s = q(1);
x = q(2);
y = q(3);
z = q(4);
r = [ 1-2*(y^2+z^2) 2*(x*y-s*z) 2*(x*z+s*y)
2*(x*y+s*z) 1-2*(x^2+z^2) 2*(y*z-s*x)
2*(x*z-s*y) 2*(y*z+s*x) 1-2*(x^2+y^2) ];
t = eye(4,4);
t(1:3,1:3) = r;
t(4,4) = 1;
end