static_math/
transformations.rs

1//-------------------------------------------------------------------------
2// @file transformations.rs
3//
4// @date 09/14/20 09:11:48
5// @author Martin Noblia
6// @email mnoblia@disroot.org
7//
8// @brief
9//
10// @detail
11//
12// Licence MIT:
13// Copyright <2020> <Martin Noblia>
14//
15// Permission is hereby granted, free of charge, to any person obtaining a copy
16// of this software and associated documentation files (the "Software"), to deal
17// in the Software without restriction, including without limitation the rights
18// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
19// copies of the Software, and to permit persons to whom the Software is
20// furnished to do so, subject to the following conditions:
21//
22// The above copyright notice and this permission notice shall be included in
23// all copies or substantial portions of the Software.  THE SOFTWARE IS PROVIDED
24// "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT
25// LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR
26// PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
27// HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
28// ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
29// WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
30//-------------------------------------------------------------------------
31use crate::matrix2x2::M22;
32use crate::matrix3x3::M33;
33use crate::matrix4x4::M44;
34use crate::matrix6x6::M66;
35use crate::m44_new;
36use crate::vector3::V3;
37use crate::vector4::V4;
38use crate::vector6::V6;
39use crate::quaternion::Quaternion;
40use crate::traits::LinearAlgebra;
41use crate::utils::{nearly_zero, nearly_equal};
42use num::{Float, Signed, Zero};
43use num::traits::FloatConst;
44use crate::slices_methods::norm2;
45
46/// Euler sequences conventions of rotations
47pub enum EulerSeq {
48    XYX,
49    XYZ,
50    XZX,
51    XZY,
52    YXY,
53    YXZ,
54    YZX,
55    YZY,
56    ZXY,
57    ZXZ
58}
59//-------------------------------------------------------------------------
60//                        transformations
61//-------------------------------------------------------------------------
62/// Compute rotation matrix from a angle in radians
63///
64/// Input:
65///
66/// `angle` - angle of rotation in radians
67pub fn rot2<T: Float>(angle: T) -> M22<T> {
68    let (s, c) = angle.sin_cos();
69    m22_new!(c, -s;
70             s,  c)
71}
72
73/// Compute the rotation around the `x` axis(in cartesian coordinates)
74///
75/// Input:
76///
77/// `angle` - angle of rotation in radians
78///
79pub fn rotx<T: Float>(angle: T) -> M33<T> {
80    let one = T::one();
81    let zero = T::zero();
82    let (s, c) = angle.sin_cos();
83    m33_new!( one, zero, zero;
84             zero,    c,   -s;
85             zero,    s,    c)
86}
87
88/// Compute the rotation around the `y` axis(in cartesian coordinates)
89///
90/// Input:
91///
92/// `angle` - Angle of rotation in radians
93///
94pub fn roty<T: Float>(angle: T) -> M33<T> {
95    let one = T::one();
96    let zero = T::zero();
97    let (s, c) = angle.sin_cos();
98    m33_new!(   c, zero,    s;
99             zero,  one, zero;
100               -s, zero,    c)
101}
102
103/// Compute the rotation around the `z` axis(in cartesian coordinates)
104///
105/// Input:
106///
107/// `angle` - Angle of rotation in radians
108///
109pub fn rotz<T: Float>(angle: T) -> M33<T> {
110    let one = T::one();
111    let zero = T::zero();
112    let (s, c) = angle.sin_cos();
113    m33_new!(   c,   -s, zero;
114                s,    c, zero;
115             zero, zero,  one)
116}
117
118/// Compute the rotation matrix from euler angles with the following conventions:
119/// XYX, XYZ, XZX, XZY, YXY, YXZ, YZX, YZY, ZXY, ZXZ
120///
121/// Function arguments:
122///
123/// yay: first euler angle in radians (Float number)
124///
125/// pitch: second euler angle in radians (Float number)
126///
127/// roll: third euler angle in radians (Float number)
128///
129/// `s`: `Option<EulerSeq>:` Optional Euler sequence if is None compute ZYX
130///
131/// Output:
132///
133/// `r`: Rotation matrix(`M33<Float>`)
134///
135pub fn euler_to_rotation<T: Float>(yay: T, pitch: T, roll: T, s: Option<EulerSeq>) -> M33<T> {
136    match s {
137        Some(EulerSeq::XYX) => rotx(yay) * roty(pitch) * rotx(roll),
138        Some(EulerSeq::XYZ) => rotx(yay) * roty(pitch) * rotz(roll),
139        Some(EulerSeq::XZX) => rotx(yay) * rotz(pitch) * rotx(roll),
140        Some(EulerSeq::XZY) => rotx(yay) * rotz(pitch) * roty(roll),
141        Some(EulerSeq::YXY) => roty(yay) * rotx(pitch) * roty(roll),
142        Some(EulerSeq::YXZ) => roty(yay) * rotx(pitch) * rotz(roll),
143        Some(EulerSeq::YZX) => rotx(yay) * roty(pitch) * rotz(roll),
144        Some(EulerSeq::YZY) => roty(yay) * rotz(pitch) * roty(roll),
145        Some(EulerSeq::ZXY) => rotz(yay) * rotx(pitch) * roty(roll),
146        Some(EulerSeq::ZXZ) => rotz(yay) * rotx(pitch) * rotz(roll),
147        None                => rotz(yay) * roty(pitch) * rotx(roll)
148    }
149}
150
151// TODO(elsuizo:2021-04-27): handle only valid rotations
152// TODO(elsuizo:2021-04-23): handle all the rotation sequences
153/// Get the euler angles from a rotation matrix comming from the convention ZYX
154///
155/// Function arguments:
156///
157/// `r`: a reference to a Rotation matrix(`M33<Float>`)
158///
159/// Output:
160///
161/// Euler angles: (yay, pitch, roll)
162///
163pub fn rotation_to_euler<T: Float + FloatConst>(r: &M33<T>) -> (T, T, T) {
164    let one   = T::one();
165    let pitch = T::atan2(-r[(2, 0)], (r[(0, 0)] * r[(0, 0)] + r[(1, 0)] * r[(1, 0)]).sqrt());
166
167    // singularity
168    if nearly_equal(pitch, -one * T::FRAC_PI_2(), T::epsilon()) {
169        let yay  = T::atan2(-r[(1, 2)], -r[(0, 2)]);
170        let roll = T::zero();
171        (yay, pitch, roll)
172    // singularity
173    } else if nearly_equal(pitch, T::FRAC_PI_2(), T::epsilon()) {
174        let yay  = T::atan2(r[(1, 2)], r[(0, 2)]);
175        let roll = T::zero();
176        (yay, pitch, roll)
177    // normal case
178    } else {
179        let yay   = T::atan2(r[(1, 0)], r[(0, 0)]);
180        let roll  = T::atan2(r[(2, 1)], r[(2, 2)]);
181        (yay, pitch, roll)
182    }
183}
184
185/// Generate a homogeneous matrix from a rotation represented by a Matrix and a translation
186/// represented by a vector
187///
188/// Function arguments:
189///
190/// `r`: a reference to a `M33<Float>` (Rotation part)
191///
192/// `p`: a reference to a  `V3<Float>` (Translation part)
193///
194///
195pub fn homogeneous_from_rotation<T: Float>(r: &M33<T>, p: &V3<T>) -> M44<T> {
196    let zero = T::zero();
197    let one  = T::one();
198    m44_new!(r[(0, 0)], r[(0, 1)], r[(0, 2)], p[0];
199             r[(1, 0)], r[(1, 1)], r[(1, 2)], p[1];
200             r[(2, 0)], r[(2, 1)], r[(2, 2)], p[2];
201                zero  ,   zero   ,    zero  , one)
202}
203
204pub fn se3_from_parts<T: Float>(r: &M33<T>, p: &V3<T>) -> M44<T> {
205    let zero = T::zero();
206    m44_new!(r[(0, 0)], r[(0, 1)], r[(0, 2)], p[0];
207             r[(1, 0)], r[(1, 1)], r[(1, 2)], p[1];
208             r[(2, 0)], r[(2, 1)], r[(2, 2)], p[2];
209                zero  ,   zero   ,    zero  , zero)
210}
211
212pub fn se3_get_parts<T: Float>(se3: &M44<T>) -> (M33<T>, V3<T>) {
213    let skew_omega = m33_new!(se3[(0, 0)], se3[(0, 1)], se3[(0, 2)];
214                              se3[(1, 0)], se3[(1, 1)], se3[(1, 2)];
215                              se3[(2, 0)], se3[(2, 1)], se3[(2, 2)]);
216    let v = V3::new_from(se3[(0, 3)], se3[(1, 3)], se3[(2, 3)]);
217    (skew_omega, v)
218}
219
220/// Generate a homogeneous matrix from a rotation represented by a quaternion and a translation
221/// represented by a vector
222///
223/// Function arguments:
224///
225/// `q`: a reference to a `Quaternion<Float>` (Rotation part)
226///
227/// `p`: a reference to a `V3<Float>` (Translation part)
228///
229///
230pub fn homogeneous_from_quaternion<T: Float>(q: &Quaternion<T>, p: &V3<T>) -> M44<T> {
231    homogeneous_from_rotation(&q.to_rotation(), p)
232}
233
234/// Get the parts of a homogeneous transformation, the rotation(expresed by a Quaternion) and the
235/// translation (expresed by a vector)
236///
237/// Function arguments:
238///
239/// `r`: Homogeneus transformation reference (`&M44<Float>`)
240///
241pub fn get_parts<T: Float + FloatConst>(r: &M44<T>) -> (Quaternion<T>, V3<T>) {
242    let rot = m33_new!(r[(0, 0)], r[(0, 1)], r[(0, 2)];
243                       r[(1, 0)], r[(1, 1)], r[(1, 2)];
244                       r[(2, 0)], r[(2, 1)], r[(2, 2)]);
245
246    let p = V3::new_from(r[(0, 3)], r[(1, 3)], r[(2, 3)]);
247
248    let (yay, pitch, roll) = rotation_to_euler(&rot);
249    let q = Quaternion::from_euler_angles(yay, pitch, roll);
250
251    (q, p)
252}
253
254/// Get the parts of a homogeneous transformation, the rotation(expresed by a Matrix) and the
255/// translation (expresed by a vector)
256///
257/// Function arguments:
258/// r: Homogeneus transformation reference(&M44<Float>)
259///
260pub fn get_parts_raw<T: Float>(r: &M44<T>) -> (M33<T>, V3<T>) {
261    let rot = m33_new!(r[(0, 0)], r[(0, 1)], r[(0, 2)];
262                       r[(1, 0)], r[(1, 1)], r[(1, 2)];
263                       r[(2, 0)], r[(2, 1)], r[(2, 2)]);
264
265    let p = V3::new_from(r[(0, 3)], r[(1, 3)], r[(2, 3)]);
266
267    (rot, p)
268}
269
270/// Get the inverse of the homogeneous transformation
271///
272/// Function arguments:
273/// r: Homogeneus transformation reference (&M44<Float>)
274///
275pub fn homogeneous_inverse<T: Float + core::iter::Sum + Signed>(r: &M44<T>) -> M44<T> {
276    let (rot, p) = get_parts_raw(r);
277    let rot_new = rot.transpose();
278    let p_new   = -rot_new * p;
279    homogeneous_from_rotation(&rot_new, &p_new)
280}
281
282/// Transform a vector with the inverse of a given homogeneous transformation
283///
284/// Function arguments:
285/// r: Homogeneus transformation reference (&M44<Float>)
286///
287/// p: reference to vector to trasnform(&V3<T>)
288///
289pub fn homogeneous_inverse_transform<T>(r: &M44<T>, p: &V3<T>) -> V3<T>
290where
291    T: Float + core::iter::Sum + FloatConst + Signed
292{
293    let (_, translation) = get_parts(r);
294    let p_trans = *p - translation;
295    let p_new = V4::new_from(p_trans[0], p_trans[1], p_trans[2], T::zero());
296    let result = homogeneous_inverse(r) * p_new;
297    V3::new_from(result[0], result[1], result[2])
298}
299
300/// Convert a 3d Vector to a $so(3)$ representation
301///
302/// Function arguments:
303/// `v`: V3<Float>
304///
305/// Output: A M33<Float> that is the skew symetric representation of `v`
306///
307pub fn skew_from_vec<T: Float>(v: &V3<T>) -> M33<T> {
308    let zero = T::zero();
309    m33_new!( zero, -v[2],  v[1];
310              v[2],  zero, -v[0];
311             -v[1],  v[0],  zero)
312}
313
314/// Convert an so(3) representation to a 3d vector
315///
316/// Function arguments:
317/// `r`: M33<Float>
318///
319/// Output: A V3<Float>
320///
321pub fn skew_to_vec<T: Float>(r: &M33<T>) -> V3<T> {
322    V3::new_from(r[(2, 1)], r[(0, 2)], r[(1, 0)])
323}
324
325pub fn skew_scalar<T: Float>(number: T) -> M22<T> {
326    let zero = T::zero();
327    m22_new!(  zero, -number;
328             number,    zero)
329}
330
331pub fn vex_m22<T: Float>(m: &M22<T>) -> T {
332    m[(1, 0)]
333}
334
335/// Create a pose in 2D from a angle(in radians) and a cartesian position (x, y) values
336pub fn ksi<T: Float>(angle: T, x: T, y: T) -> M33<T> {
337    let zero = T::zero();
338    let one = T::one();
339    let (s, c) = angle.sin_cos();
340    m33_new!(   c,   -s,   x;
341                s,    c,   y;
342             zero, zero, one)
343}
344
345/// Create augmented skew-symmetric matrix
346pub fn skew_from_vec_aug<T: Float>(v: V3<T>) -> M33<T> {
347    let zero = T::zero();
348    m33_new!(zero, -v[2], v[0];
349             v[2],  zero, v[1];
350             zero,  zero, zero)
351}
352
353/// Create augmented skew-symmetric matrix
354///
355/// Input:
356///
357/// `v`: vector(`V6<Float>`)
358///
359/// Output:
360///
361/// skew-symetric augmented matrix(`M44<Float>`)
362pub fn skew_v6<T: Float>(v: V6<T>) -> M44<T> {
363    let zero = T::zero();
364    m44_new!( zero, -v[5],  v[4], v[0];
365              v[5],  zero, -v[3], v[1];
366             -v[4],  v[3],  zero, v[2];
367              zero,  zero,  zero, zero)
368}
369
370/// Convert a 3d vector of exponential coordinates for rotation into axis-angle
371/// form
372///
373/// Function arguments:
374/// `exp`: V3<Float> 3d vector of exponential coordinates
375///
376/// Output:
377/// (omega_hat, theta)
378///
379pub fn axis_angle<T: Float>(exp: &V3<T>) -> (V3<T>, T) {
380    (exp.normalize().expect("empty vector"), exp.norm2())
381}
382
383/// Create a pure translation homogeneous transformation
384pub fn translation_2d<T: Float>(x: T, y: T) -> M33<T> {
385    let zero = T::zero();
386    let one = T::one();
387    m33_new!( one, zero,   x;
388             zero,  one,   y;
389             zero, zero, one)
390}
391
392/// Create a pure translation homogeneous transformation in 3d
393pub fn translation_3d<T: Float>(x: T, y: T, z: T) -> M44<T> {
394    let zero = T::zero();
395    let one = T::one();
396    m44_new!( one, zero, zero,  x;
397             zero,  one, zero,  y;
398             zero, zero,  one,  z;
399             zero, zero, zero, one)
400}
401
402// NOTE(elsuizo:2021-05-04): wide code is better code
403/// Compute the matrix exponential for omega theta(exponential coordinates): so(3) ---> SO(3)
404/// with the Rodriguez formula
405pub fn rotation_from_axis_angle<T: Float>(omega: &V3<T>, theta: T) -> M33<T> {
406    let skew       = skew_from_vec(omega);
407    let (sin, cos) = theta.sin_cos();
408    M33::identity() + skew * sin + skew * skew * (T::one() - cos)
409}
410
411// NOTE(elsuizo:2021-05-09): remember we have problems to Mul to left side with a constant...
412/// Compute the matrix exponential of a matrix in so(3)
413///
414/// Function arguments:
415/// `so3`: M33<T> a screw symetric matrix
416///
417/// Output:
418/// M33<T>: representing the matrix exponential of the input
419///
420pub fn matrix_exponential<T: Float>(so3: &M33<T>) -> M33<T> {
421    let omega_theta = skew_to_vec(so3);
422    let one = T::one();
423    if nearly_zero(omega_theta.norm2()) {
424        M33::identity()
425    } else {
426        let theta = axis_angle(&omega_theta).1;
427        let omega = *so3 / theta;
428        let (s, c) = theta.sin_cos();
429        M33::identity() + omega * s + omega * omega * (one - c)
430    }
431}
432
433/// Brief.
434///
435/// Compute the matrix logarithm of a rotation matrix
436///
437/// Function arguments:
438/// `r`: &M33<Float> rotation matrix
439///
440/// Output:
441/// M33<Float>: representing the matrix logarithm of the input
442///
443pub fn matrix_log<T: Float + core::iter::Sum + FloatConst>(r: &M33<T>) -> M33<T> {
444    let one = T::one();
445    let two = one + one;
446    let angle = (r.trace() - one) / two;
447    if angle >= one {
448        M33::zeros()
449    } else if angle <= -one {
450        if !nearly_zero(one + r[(2, 2)]) {
451            let omega = V3::new_from(r[(0, 2)], r[(1, 2)], one + r[(2, 2)]) * (one / T::sqrt(two * (one + r[(2, 2)])));
452            skew_from_vec(&(omega * T::PI()))
453        } else if !nearly_zero(one + r[(1, 1)]) {
454            let omega = V3::new_from(r[(0, 1)], one + r[(1, 1)], r[(2, 1)]) * (one / T::sqrt(two * (one + r[(1, 1)])));
455            skew_from_vec(&(omega * T::PI()))
456        } else {
457            let omega = V3::new_from(one + r[(0, 0)], one + r[(1, 0)], r[(2, 0)]) * (one / T::sqrt(two * (one + r[(0, 0)])));
458            skew_from_vec(&(omega * T::PI()))
459        }
460    } else {
461        let theta = T::acos(angle);
462        // TODO(elsuizo:2021-05-10): esto esta bien???
463        (*r - r.transpose()) * (theta / two / T::sin(theta))
464    }
465}
466
467/// Inverse of a Rotation matrix, where R: SO(3)
468pub fn rotation_inverse<T: Float + core::iter::Sum>(r: &M33<T>) -> M33<T> {
469    r.transpose()
470}
471
472/// Convert a spatial velocity vector to a M44 matrix in se3 space
473///
474/// Function arguments:
475/// `twist`: V6<Float> representing the "twist"
476///
477/// Output:
478/// M44<Float>: a matrix in the se3 space
479///
480pub fn twist_to_se3<T: Float>(twist: &V6<T>) -> M44<T> {
481    let skew = skew_from_vec(&V3::new_from(twist[0], twist[1], twist[2]));
482    se3_from_parts(&skew, &V3::new_from(twist[3], twist[4], twist[5]))
483}
484
485/// Convert a se3 matrix representation to a spatial velocity vector known as "twist"
486///
487/// Function arguments:
488/// `se3`: M44<Float> a matrix in the se3 space
489///
490/// Output:
491/// V3<Float>: representing spatial velocity vector("twist")
492///
493pub fn se3_to_twist<T: Float>(se3: &M44<T>) -> V6<T> {
494    V6::new_from(se3[(2, 1)], se3[(0, 2)], se3[(1, 0)], se3[(0, 3)], se3[(1, 3)], se3[(2, 3)])
495}
496
497/// Compute the adjoint representation of a homogeneous transformation matrix
498///
499/// Function arguments:
500/// `transform`: M44<Float> a homogeneous transformation matrix
501///
502/// Output:
503/// M66<Float>: the 6x6 matrix representation of the Adjoint of T
504///
505pub fn adjoint<T: Float>(transform: &M44<T>) -> M66<T> {
506    let mut result = M66::zeros();
507    let (r, p) = get_parts_raw(transform);
508    let skew = skew_from_vec(&p);
509    let transform_p = skew * r;
510    result.copy_elements_from(&r, 1);
511    result.copy_elements_from(&r, 4);
512    result.copy_elements_from(&transform_p, 3);
513    result
514}
515
516/// Takes a parametric description of a screw axis and converts it to a normalized screw axis
517///
518/// Function arguments:
519/// `q`: V3<Float> a point lying on the screw axis
520/// `s`: V3<Float> a unit vector in the direction of the screw axis
521/// `h`: Float The pitch of the screw axis
522///
523/// Output:
524/// V6<Float> A normalized screw axis described by the inputs
525///
526pub fn screw_to_axis<T: Float>(q: &V3<T>, s: &V3<T>, h: T) -> V6<T> {
527    let v = q.cross(*s) + (*s) * h;
528    V6::new_from(s[0], s[1], s[2], v[0], v[1], v[2])
529}
530
531/// Convert a 6D vector of exponential coordinates into screw axis angle
532///
533/// Function arguments:
534/// `exp`: V6<Float> A 6D vector of exponential coordinates for rigid-body motion S * theta
535///
536/// Output:
537/// (V6<Float, Float) a tuple with the first element the normalized "screw" axis, and the second
538/// tuple element called "theta" representing the distance traveled along/about S
539///
540pub fn axis_angle6<T: Float>(exp: &V6<T>) -> (V6<T>, T) {
541    // NOTE(elsuizo:2021-05-11): here we treat the vector like a slice(to obtain the first three
542    // elements)
543    let theta = norm2(&exp[0..3]);
544    if nearly_zero(theta) {
545        let theta = norm2(&exp[3..6]);
546        return (*exp / theta, theta)
547    }
548    (*exp / theta, theta)
549}
550
551/// Computes the matrix logarithm of a homogeneous transformation matrix
552///
553/// Function arguments:
554/// `se3`: M44<Float> in SE(3)
555///
556/// Output:
557/// M44<Float> The matrix logarithm of the input
558///
559pub fn matrix_exponential6<T: Float>(se3: &M44<T>) -> M44<T> {
560    let zero = T::zero();
561    let one  = T::one();
562    let (skew_omega, v) = se3_get_parts(se3);
563    let omega_theta = skew_to_vec(&skew_omega);
564    // NOTE(elsuizo:2021-05-11): if w = 0 ---> "pitch" == infinity and |v| = 1 ---> theta represents only a linear distance
565    if nearly_zero(omega_theta.norm2()) {
566        m44_new!( one,  zero,  one, v[0];
567                 zero,   one, zero, v[1];
568                 zero,  zero,  one, v[2];
569                 zero,  zero, zero, one)
570    } else {
571        // NOTE(elsuizo:2021-05-11): |w| = 1 ---> theta represents the distance along side the
572        // "screw" axis S
573        let theta = axis_angle(&omega_theta).1;
574        let omega = skew_omega / theta;
575        let mat_exp = matrix_exponential(&skew_omega);
576        let (s, c) = theta.sin_cos();
577        let v_t = (M33::identity() * theta + omega * (one - c) + omega * omega * (theta - s)) * v / theta;
578
579        m44_new!(mat_exp[(0, 0)], mat_exp[(0, 1)], mat_exp[(0, 2)], v_t[0];
580                 mat_exp[(1, 0)], mat_exp[(1, 1)], mat_exp[(1, 2)], v_t[1];
581                 mat_exp[(2, 0)], mat_exp[(2, 1)], mat_exp[(2, 2)], v_t[2];
582                          zero  ,     zero       ,       zero     ,  one)
583    }
584}
585
586/// Compute the matrix logarithm of a homogeneous transformation matrix
587///
588/// Function arguments:
589/// `t`: M44<Float> a matrix in SE(3)
590///
591/// Ouput:
592/// M44<Float> the matrix `log` of the input
593///
594pub fn matrix_log6<T: Float + core::iter::Sum + FloatConst>(t: &M44<T>) -> M44<T> {
595    let zero = T::zero();
596    let one = T::one();
597    let two = one + one;
598    let (r, p) = get_parts_raw(t);
599    let omega = matrix_log(&r);
600    // TODO(elsuizo:2021-05-13): maybe here could be better compare with epsilons
601    if omega.is_zero() {
602        m44_new!(zero, zero, zero, p[0];
603                 zero, zero, zero, p[1];
604                 zero, zero, zero, p[2];
605                 zero, zero, zero, zero)
606    } else {
607        let theta = T::acos((r.trace() - one) / two);
608        let cot = one / T::tan(theta / two);
609        let v = (M33::identity() - omega / two + omega * omega * (one / theta - cot / two) / theta) * p;
610        m44_new!(omega[(0, 0)], omega[(0, 1)], omega[(0, 2)], v[0];
611                 omega[(1, 0)], omega[(1, 1)], omega[(1, 2)], v[1];
612                 omega[(2, 0)], omega[(2, 1)], omega[(2, 2)], v[2];
613                      zero    ,     zero     ,      zero    , zero)
614    }
615
616}
617
618/// Returns the Frobenius norm to describe the distance of the transformation from the SO(3)
619/// manifold
620///
621/// Function arguments:
622/// `m`: M33<Float> a 3x3 matrix
623///
624/// Ouput:
625/// A metric describing the distance between the matrix input and the SO(3) manifold
626///
627pub fn distance_to_manifold<T: Float + core::iter::Sum>(m: &M33<T>) -> T {
628    if m.det() > T::zero() {
629        (*m * m.transpose() - M33::identity()).norm2()
630    } else {
631        T::infinity()
632    }
633}
634//-------------------------------------------------------------------------
635//                        tests
636//-------------------------------------------------------------------------
637#[cfg(test)]
638mod test_transformations {
639
640    use super::{rotation_to_euler, euler_to_rotation, rotx, roty, rotz,
641                homogeneous_from_quaternion, homogeneous_inverse,
642                homogeneous_inverse_transform, matrix_log, matrix_exponential, skew_from_vec,
643                twist_to_se3, se3_to_twist, adjoint, screw_to_axis, axis_angle6, matrix_exponential6,
644                matrix_log6, distance_to_manifold};
645
646    use crate::utils::{nearly_equal, is_rotation, is_rotation_h, compare_vecs};
647    use crate::quaternion::Quaternion;
648    use crate::vector3::V3;
649    use crate::matrix4x4::M44;
650    use crate::m44_new;
651    use crate::matrix6x6::M66;
652    use crate::m66_new;
653    use crate::vector6::V6;
654    use crate::matrix3x3::M33;
655    const EPS: f32 = 1e-6;
656
657    #[test]
658    fn rotation_and_euler_test() {
659        let expected = (0.1, 0.2, 0.3);
660        let r = euler_to_rotation(expected.0, expected.1, expected.2, None);
661        let result = rotation_to_euler(&r);
662        assert!(nearly_equal(result.0, expected.0, EPS));
663        assert!(nearly_equal(result.1, expected.1, EPS));
664        assert!(nearly_equal(result.2, expected.2, EPS));
665    }
666
667    #[test]
668    fn rotation_x() {
669        let r = rotx(20f32.to_radians());
670        assert!(is_rotation(r));
671    }
672
673    #[test]
674    fn rotation_y() {
675        let r = roty(20f32.to_radians());
676        assert!(is_rotation(r));
677    }
678
679    #[test]
680    fn rotation_z() {
681        let r = rotz(20f32.to_radians());
682        assert!(is_rotation(r));
683    }
684
685    #[test]
686    fn homogeneous_transform_test() {
687        let v = V3::y_axis() * core::f32::consts::FRAC_PI_2;
688        let q = Quaternion::rotation_norm_encoded(&v);
689        let iso_s = homogeneous_from_quaternion(&q, &V3::new_from(0.0, 0.0, 3.0));
690        assert!(is_rotation_h(iso_s));
691    }
692
693    #[test]
694    fn homogeneous_inverse_test() {
695        let v = V3::y_axis() * core::f32::consts::FRAC_PI_2;
696        let q = Quaternion::rotation_norm_encoded(&v);
697        let iso_s = homogeneous_from_quaternion(&q, &V3::new_from(0.0, 0.0, 3.0));
698        let result = iso_s * homogeneous_inverse(&iso_s);
699        let expected = M44::identity();
700        assert!(compare_vecs(&result.as_vec(), &expected.as_vec(), EPS));
701    }
702
703    // NOTE(elsuizo:2021-04-27): this is the same example from nalgebra:
704    // https://docs.rs/nalgebra/0.26.2/nalgebra/geometry/struct.Isometry.html#method.inverse_transform_point
705    #[test]
706    fn inverse_point_transform_test() {
707        let v = V3::y_axis() * core::f32::consts::FRAC_PI_2;
708        let q = Quaternion::rotation_norm_encoded(&v);
709        let iso_s = homogeneous_from_quaternion(&q, &V3::new_from(0.0, 0.0, 3.0));
710        let result = homogeneous_inverse_transform(&iso_s, &V3::new_from(1.0, 2.0, 3.0));
711        let expected = V3::new_from(0.0, 2.0, 1.0);
712        assert!(compare_vecs(&*result, &*expected, EPS));
713    }
714
715    #[test]
716    fn matrix_log_test() {
717        let r = m33_new!(0.0, 0.0, 1.0;
718                         1.0, 0.0, 0.0;
719                         0.0, 1.0, 0.0);
720        let result = matrix_log(&r);
721        let expected = m33_new!(        0.0, -1.20919958,  1.20919958;
722                                 1.20919958,         0.0, -1.20919958;
723                                -1.20919958,  1.20919958,         0.0);
724        assert!(compare_vecs(&result.as_vec(), &expected.as_vec(), EPS));
725    }
726
727    #[test]
728    fn matrix_exponential_test() {
729        let so3 = skew_from_vec(&V3::new_from(1.0, 2.0, 3.0));
730        let result = matrix_exponential(&so3);
731        let expected  = m33_new!(-0.69492056,  0.71352099,  0.08929286;
732                                 -0.19200697, -0.30378504,  0.93319235;
733                                  0.69297817,  0.6313497 ,  0.34810748);
734        assert!(compare_vecs(&result.as_vec(), &expected.as_vec(), EPS));
735    }
736
737    #[test]
738    fn twist_to_se3_test() {
739        let result = twist_to_se3(&V6::new_from(1.0, 2.0, 3.0, 4.0, 5.0, 6.0));
740        let expected = m44_new!( 0.0, -3.0,  2.0, 4.0;
741                                 3.0,  0.0, -1.0, 5.0;
742                                -2.0,  1.0,  0.0, 6.0;
743                                 0.0,  0.0,  0.0, 0.0);
744        assert!(compare_vecs(&result.as_vec(), &expected.as_vec(), EPS));
745    }
746
747    #[test]
748    fn se3_to_twist_test() {
749        let se3 = m44_new!( 0.0, -3.0,  2.0, 4.0;
750                            3.0,  0.0, -1.0, 5.0;
751                           -2.0,  1.0,  0.0, 6.0;
752                            0.0,  0.0,  0.0, 0.0);
753        let result = se3_to_twist(&se3);
754        let expected = V6::new_from(1.0, 2.0, 3.0, 4.0, 5.0, 6.0);
755        assert_eq!(
756            &result[..],
757            &expected[..],
758            "\nExpected\n{:?}\nfound\n{:?}",
759            &result[..],
760            &expected[..]
761        );
762    }
763
764    #[test]
765    fn adjoint_test() {
766        let t = m44_new!(1.0, 0.0,  0.0, 0.0;
767                         0.0, 0.0, -1.0, 0.0;
768                         0.0, 1.0,  0.0, 3.0;
769                         0.0, 0.0,  0.0, 1.0);
770
771        let result = adjoint(&t);
772        let expected = m66_new!(1.0, 0.0,  0.0, 0.0, 0.0,  0.0;
773                                0.0, 0.0, -1.0, 0.0, 0.0,  0.0;
774                                0.0, 1.0,  0.0, 0.0, 0.0,  0.0;
775                                0.0, 0.0,  3.0, 1.0, 0.0,  0.0;
776                                3.0, 0.0,  0.0, 0.0, 0.0, -1.0;
777                                0.0, 0.0,  0.0, 0.0, 1.0,  0.0);
778
779        assert!(compare_vecs(&result.as_vec(), &expected.as_vec(), EPS));
780    }
781
782    #[test]
783    fn screw_to_axis_test() {
784        let q = V3::new_from(3.0, 0.0, 0.0);
785        let s = V3::new_from(0.0, 0.0, 1.0);
786        let h = 2.0;
787        let result = screw_to_axis(&q, &s, h);
788        let expected = V6::new_from(0.0, 0.0, 1.0, 0.0, -3.0, 2.0);
789        assert_eq!(
790            &result[..],
791            &expected[..],
792            "\nExpected\n{:?}\nfound\n{:?}",
793            &result[..],
794            &expected[..]
795        );
796    }
797
798    #[test]
799    fn axis_angle6_test() {
800        let v = V6::new_from(1.0, 0.0, 0.0, 1.0, 2.0, 3.0);
801        let result = axis_angle6(&v);
802        let expected = (V6::new_from(1.0, 0.0, 0.0, 1.0, 2.0, 3.0), 1.0);
803        assert_eq!(
804            &result.0[..],
805            &expected.0[..],
806            "\nExpected\n{:?}\nfound\n{:?}",
807            &result.0[..],
808            &expected.0[..]
809        );
810        assert!(nearly_equal(result.1, expected.1, EPS));
811    }
812
813    #[test]
814    fn matrix_exponential6_test() {
815        let se3mat = m44_new!(0.0,          0.0,           0.0,          0.0;
816                              0.0,          0.0,   -1.57079632,   2.35619449;
817                              0.0,   1.57079632,           0.0,   2.35619449;
818                              0.0,          0.0,           0.0,          0.0);
819
820        let result = matrix_exponential6(&se3mat);
821        let expected = m44_new!(1.0, 0.0,  0.0, 0.0;
822                                0.0, 0.0, -1.0, 0.0;
823                                0.0, 1.0,  0.0, 3.0;
824                                0.0, 0.0,  0.0, 1.0);
825        assert!(compare_vecs(&result.as_vec(), &expected.as_vec(), EPS));
826    }
827
828    #[test]
829    fn matrix_log6_test() {
830        let t = m44_new!(1.0, 0.0,  0.0, 0.0;
831                         0.0, 0.0, -1.0, 0.0;
832                         0.0, 1.0,  0.0, 3.0;
833                         0.0, 0.0,  0.0, 1.0);
834        let result = matrix_log6(&t);
835
836        let expected = m44_new!(0.0,        0.0,         0.0,        0.0;
837                                0.0,        0.0, -1.57079633, 2.35619449;
838                                0.0, 1.57079633,         0.0, 2.35619449;
839                                0.0,        0.0,         0.0,        0.0);
840
841        assert!(compare_vecs(&result.as_vec(), &expected.as_vec(), EPS));
842    }
843
844    #[test]
845    fn distance_to_manifold_test() {
846        let mat = m33_new!(1.0,  0.0,   0.0 ;
847                           0.0,  0.1,  -0.95;
848                           0.0,  1.0,   0.1 );
849        let result = distance_to_manifold(&mat);
850        // NOTE(elsuizo:2021-05-13): this result come from numpy
851        let expected = 0.08835298523536149;
852        assert!(nearly_equal(result, expected, EPS));
853    }
854}