sguaba/math.rs
1//! Spatial operations expressed in mathematical language.
2//!
3//! This module provides type-safe wrappers around the mathematical constructs that underpin rigid
4//! body transforms (quaternions, isometries, etc.). The mathematical representation gives maximal
5//! power and flexibility to construct, combine, and use these transforms, but can be hard to grok
6//! for people without a mathematics-oriented background. For an interface better suited for those
7//! with a background in engineering, see [`mod engineering`](crate::engineering).
8//!
9//! The main type provided by this module is [`RigidBodyTransform`], which describes the
10//! isometry (ie, rotation and translation) between two coordinate systems (see also
11//! [`CoordinateSystem`]). [`RigidBodyTransform`] implements the various mathematical operations
12//! you would expect such that you can multiply them together to combine them, take one's inverse,
13//! and multiply with a [`Coordinate`] or [`Vector`] to apply the isometry to transform between
14//! coordinate systems.
15//!
16//! This module also provides the [`Rotation`] type to represents unit quaternion based transforms
17//! between coordinate systems (ie, they need no translation to convert between them).
18
19use crate::coordinate_systems::Ecef;
20use crate::coordinates::Coordinate;
21use crate::geodetic::Wgs84;
22use crate::systems::EquivalentTo;
23use crate::vectors::Vector;
24use crate::Bearing;
25use crate::{
26 systems::{EnuLike, NedLike},
27 CoordinateSystem, Isometry3, UnitQuaternion,
28};
29use nalgebra::{Matrix3, Rotation3, Translation3};
30use std::convert::From;
31use std::fmt;
32use std::fmt::{Display, Formatter};
33use std::marker::PhantomData;
34use std::ops::{Mul, Neg};
35use uom::si::angle::radian;
36use uom::si::f64::Angle;
37
38#[cfg(any(test, feature = "approx"))]
39use approx::{AbsDiffEq, RelativeEq};
40
41#[cfg(feature = "serde")]
42use serde::{Deserialize, Serialize};
43
44#[cfg(doc)]
45use crate::{engineering, systems::FrdLike};
46
47/// Defines a [rotation transform] between two [`CoordinateSystem`]s.
48///
49/// There are generally two ways to construct a rotation:
50///
51/// 1. by using [`engineering::Orientation::map_as_zero_in`] when you already have an
52/// [`engineering::Orientation`];
53/// 2. by using [Tait-Bryan angles](Rotation::from_tait_bryan_angles) to construct
54/// arbitrary rotations.
55///
56/// Mathematically speaking, this is a type-safe wrapper around a [unit quaternion].
57///
58/// <div class="warning">
59///
60/// Note that this type implements `Deserialize` despite having `unsafe` constructors -- this is
61/// because doing otherwise would be extremely unergonomic. However, when deserializing, the
62/// coordinate system of the deserialized value is _not_ checked, so this is a foot-gun to be
63/// mindful of.
64///
65/// </div>
66///
67/// <div class="warning">
68///
69/// Rotations can be chained with other transformations using `*` (ie, the [`Mul`] trait). However,
70/// note that the order of the operands to `*` matter, and do not match the mathematical
71/// convention. Specifically, matrix multiply for transforms (like rotations) traditionally have
72/// the transform on the left and the vector to transform on the right. However, doing so here
73/// would lead to a type signature of
74///
75/// ```rust,ignore
76/// let _: Coordinate<To> = Rotation<From, To> * Coordinate<From>;
77/// ```
78///
79/// Which violates the expectation that a matrix multiply eliminates the "middle" component (ie,
80/// (m × n)(n × p) = (m × p)). So, we require that the rotation is on the _right_ to go from
81/// `From` into `To`, and that the rotation is on the _left_ to go from `To` into `From` (ie, for
82/// the inverse transform).
83///
84/// </div>
85///
86/// [rotation transform]: https://en.wikipedia.org/wiki/Rotation
87/// [unit quaternion]: https://en.wikipedia.org/wiki/Versor
88#[derive(Debug)]
89#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
90// don't require From/To: Serialize/Deserialize since we skip it anyway
91#[cfg_attr(feature = "serde", serde(bound = ""))]
92// no need for the "inner": indirection
93#[cfg_attr(feature = "serde", serde(transparent))]
94pub struct Rotation<From, To> {
95 /// This is _actually_ the rotation from `To` into `From`, because that's a much more natural
96 /// constructor. This means that what we store here is equivalent to a rotation matrix whose
97 /// rows are `From` and columns are `To` (rather than the other way around). If we want convert
98 /// a vector `x` from `From` to `To`, we can't do a straight matrix multiplication of the
99 /// (equivalent) rotation matrix in `inner` with `x`, because that would yield (From x To) *
100 /// (From x 1), which doesn't math. Instead, we need to matrix multiply the _inverse_ (which is
101 /// transpose for a rotation matrix) of `inner` with `x`, which does work:
102 ///
103 /// ```text
104 /// (From x To)-1 * (From x 1)
105 /// (To x From) * (From x 1)
106 /// (To x 1)
107 /// ```
108 ///
109 /// In other words, we have to apply `inverse_transform`, not `transform`, for all conversions
110 /// `From` -> `To`. If we want to go the other way (`To` -> `From`), we need to apply
111 /// `transform`. You'll see this across the `impl Mul`s further down.
112 pub(crate) inner: UnitQuaternion,
113 #[cfg_attr(feature = "serde", serde(skip))]
114 pub(crate) from: PhantomData<From>,
115 #[cfg_attr(feature = "serde", serde(skip))]
116 pub(crate) to: PhantomData<To>,
117}
118
119// manual impls of Clone and Copy to avoid requiring In: Copy + Clone
120impl<From, To> Clone for Rotation<From, To> {
121 fn clone(&self) -> Self {
122 *self
123 }
124}
125impl<From, To> Copy for Rotation<From, To> {}
126
127impl<From, To> PartialEq<Self> for Rotation<From, To> {
128 fn eq(&self, other: &Self) -> bool {
129 self.inner.eq(&other.inner)
130 }
131}
132
133impl<From, To> Display for Rotation<From, To> {
134 fn fmt(&self, f: &mut Formatter<'_>) -> fmt::Result {
135 write!(f, "Quaternion: {}", self.inner)
136 }
137}
138
139impl<To> Rotation<Ecef, To>
140where
141 To: CoordinateSystem<Convention = NedLike>,
142{
143 /// Constructs the rotation from [`Ecef`] to [`NedLike`] at the given latitude and longitude.
144 ///
145 /// The lat/lon is needed because the orientation of North with respect to ECEF depends on
146 /// where on the globe you are.
147 ///
148 /// See also
149 /// <https://en.wikipedia.org/wiki/Local_tangent_plane_coordinates#Local_north,_east,_down_(NED)_coordinates>.
150 ///
151 /// # Safety
152 ///
153 /// This function only produces a valid transform from [`Ecef`] to the NED-like `To` if
154 /// [`Coordinate::<To>::origin()`](Coordinate::origin) lies at the provided lat/lon. If that is
155 /// not the case, the returned `Rotation` will allow moving from [`Ecef`] to `To` without the
156 /// appropriate transformation of the components of the input, leading to outputs that are
157 /// typed to be in `To` but are in fact not.
158 ///
159 /// Furthermore, this function only applies rotation and _not_ translation, and is therefore
160 /// not appropriate for turning [`Ecef`] into `To` on its own. See
161 /// [`RigidBodyTransform::ecef_to_ned_at`].
162 unsafe fn ecef_to_ned_at(latitude: impl Into<Angle>, longitude: impl Into<Angle>) -> Self {
163 let phi = latitude.into().get::<radian>();
164 let lambda = longitude.into().get::<radian>();
165
166 let sin_phi = phi.sin();
167 let cos_phi = phi.cos();
168 let sin_lambda = lambda.sin();
169 let cos_lambda = lambda.cos();
170
171 // Equation 3 has column E, N, U
172 // With N, E, D = N, E, -U
173 // this yields
174 let matrix = Matrix3::new(
175 -cos_lambda * sin_phi,
176 -sin_lambda,
177 -cos_lambda * cos_phi,
178 -sin_lambda * sin_phi,
179 cos_lambda,
180 -sin_lambda * cos_phi,
181 cos_phi,
182 0.,
183 -sin_phi,
184 );
185 let rot = Rotation3::from_matrix(&matrix);
186
187 Self {
188 inner: UnitQuaternion::from_rotation_matrix(&rot),
189 from: PhantomData,
190 to: PhantomData,
191 }
192 }
193}
194
195impl<To> Rotation<Ecef, To>
196where
197 To: CoordinateSystem<Convention = EnuLike>,
198{
199 /// Constructs the rotation from [`Ecef`] to [`EnuLike`] at the given latitude and longitude.
200 ///
201 /// The lat/lon is needed because the orientation of East and North with respect to ECEF depends on
202 /// where on the globe you are.
203 ///
204 /// See also
205 /// <https://en.wikipedia.org/wiki/Local_tangent_plane_coordinates#Local_east,_north,_up_(ENU)_coordinates>.
206 ///
207 /// # Safety
208 ///
209 /// This function only produces a valid transform from [`Ecef`] to the ENU-like `To` if
210 /// [`Coordinate::<To>::origin()`](Coordinate::origin) lies at the provided lat/lon. If that is
211 /// not the case, the returned `Rotation` will allow moving from [`Ecef`] to `To` without the
212 /// appropriate transformation of the components of the input, leading to outputs that are
213 /// typed to be in `To` but are in fact not.
214 ///
215 /// Furthermore, this function only applies rotation and _not_ translation, and is therefore
216 /// not appropriate for turning [`Ecef`] into `To` on its own. See
217 /// [`RigidBodyTransform::ecef_to_enu_at`].
218 unsafe fn ecef_to_enu_at(latitude: impl Into<Angle>, longitude: impl Into<Angle>) -> Self {
219 let phi = latitude.into().get::<radian>();
220 let lambda = longitude.into().get::<radian>();
221
222 let sin_phi = phi.sin();
223 let cos_phi = phi.cos();
224 let sin_lambda = lambda.sin();
225 let cos_lambda = lambda.cos();
226
227 // Standard ENU transformation matrix from ECEF coordinates
228 // East, North, Up = E, N, U (no column swapping or negation like NED)
229 let matrix = Matrix3::new(
230 -sin_lambda,
231 -cos_lambda * sin_phi,
232 cos_lambda * cos_phi,
233 cos_lambda,
234 -sin_lambda * sin_phi,
235 sin_lambda * cos_phi,
236 0.,
237 cos_phi,
238 sin_phi,
239 );
240 let rot = Rotation3::from_matrix(&matrix);
241
242 Self {
243 inner: UnitQuaternion::from_rotation_matrix(&rot),
244 from: PhantomData,
245 to: PhantomData,
246 }
247 }
248}
249
250fn swap_x_y_negate_z_quaternion() -> UnitQuaternion {
251 use nalgebra::{Matrix3, Rotation3, UnitQuaternion};
252
253 const SWAP_X_Y_NEGATE_Z: [[f64; 3]; 3] = [
254 [0.0, 1.0, 0.0], // swap x and y
255 [1.0, 0.0, 0.0], // swap x and y
256 [0.0, 0.0, -1.0], // negate z
257 ];
258 let m = Matrix3::from_row_slice(&SWAP_X_Y_NEGATE_Z.concat());
259 UnitQuaternion::from_rotation_matrix(&Rotation3::from_matrix(&m))
260}
261
262impl<From, To> Rotation<From, To>
263where
264 To: CoordinateSystem<Convention = EnuLike>,
265{
266 /// Converts a rotation from an [`EnuLike`] coordinate system into the equivalent rotation in the
267 /// [`NedLike`] coordinate system that shares the same origin.
268 ///
269 /// # Safety
270 ///
271 /// This function only provides a valid rotation if the [`EnuLike`] and [`NedLike`] coordinate
272 /// systems share the same origin. If this is not the case, the resulting rotation will lead to
273 /// incorrect transformations.
274 #[must_use]
275 pub unsafe fn into_ned_equivalent<NedTo>(self) -> Rotation<From, NedTo>
276 where
277 NedTo: CoordinateSystem<Convention = NedLike>,
278 {
279 // Chain the rotations: From -> ENU -> NED
280 Rotation {
281 inner: self.inner * swap_x_y_negate_z_quaternion(),
282 from: PhantomData::<From>,
283 to: PhantomData::<NedTo>,
284 }
285 }
286}
287
288impl<From, To> Rotation<From, To>
289where
290 To: CoordinateSystem<Convention = NedLike>,
291{
292 /// Converts a rotation from a [`NedLike`] coordinate system into the equivalent rotation in the
293 /// [`EnuLike`] coordinate system that shares the same origin.
294 ///
295 /// # Safety
296 ///
297 /// This function only provides a valid rotation if the [`NedLike`] and [`EnuLike`] coordinate
298 /// systems share the same origin. If this is not the case, the resulting rotation will lead to
299 /// incorrect transformations.
300 #[must_use]
301 pub unsafe fn into_enu_equivalent<EnuTo>(self) -> Rotation<From, EnuTo>
302 where
303 EnuTo: CoordinateSystem<Convention = EnuLike>,
304 {
305 // Chain the rotations: From -> NED -> ENU
306 Rotation {
307 inner: self.inner * swap_x_y_negate_z_quaternion(),
308 from: PhantomData::<From>,
309 to: PhantomData::<EnuTo>,
310 }
311 }
312}
313
314impl<From, To> Rotation<From, To> {
315 /// Constructs a rotation between two [`CoordinateSystem`]s using ([intrinsic]) yaw, pitch, and
316 /// roll [Tait-Bryan angles][tb].
317 ///
318 /// Perhaps counter-intuitively, this is the rotation _of_ `From` _in_ `To`. That is, it is the
319 /// rotation that must be applied to points in `To` to place them in `From`.
320 ///
321 /// If your brain is more engineering-oriented, prefer the alternatives listed in the [type
322 /// docs](Rotation).
323 ///
324 /// Perhaps counter-intuitively, the angles provided here should represent the rotation that
325 /// must be applied to an object with zero [`Bearing`] **in `To`** to arrivate at a [`Bearing`]
326 /// with the given angles **in `From`**. This is because we take the _inverse_ of this rotation
327 /// to go from `From` into `To`, which in turn stems from mathematical norms.
328 ///
329 /// The three rotations are defined as follows:
330 ///
331 /// - yaw is rotation about the Z axis of `In`;
332 /// - pitch is rotation about the Y axis; and
333 /// - roll is rotation about the X axis.
334 ///
335 /// Since we are using [intrinsic] rotations (by convention given the naming of the arguments),
336 /// pitch is with respect to the Y axis _after_ applying the yaw, and roll is with respect to X
337 /// after applying both yaw and pitch.
338 ///
339 /// To determine the direction of rotation (ie, in which direction a positive angle goes), you
340 /// can use the [right-hand rule for rotations][rhrot]: curl your fingers and stick your thumb
341 /// out in the positive direction of the axis you want to check rotation around (eg, positive Z
342 /// for yaw). The direction your fingers curl is the direction of (positive) rotation.
343 ///
344 /// Be aware that rotational angles have high ambiguities in literature and are easy to use
345 /// wrong, especially because different fields tend to use the same term with different
346 /// meanings (eg, "Euler angles" mean something else in aerospace than in mathematics).
347 ///
348 /// See also [`engineering::Orientation::from_tait_bryan_angles`].
349 ///
350 /// [intrinsic]: https://dominicplein.medium.com/extrinsic-intrinsic-rotation-do-i-multiply-from-right-or-left-357c38c1abfd
351 /// [tb]: https://en.wikipedia.org/wiki/Euler_angles#Tait%E2%80%93Bryan_angles
352 /// [aero]: https://en.wikipedia.org/wiki/Aircraft_principal_axes
353 /// [enu]: https://en.wikipedia.org/wiki/Axes_conventions#World_reference_frames_for_attitude_description
354 /// [rhrot]: https://en.wikipedia.org/wiki/Right-hand_rule#Rotations
355 ///
356 /// # Safety
357 ///
358 /// Calling this method asserts that the provided rotational angles represent a correct way to
359 /// transform any input from `From` to `To` (and crucially, that no translation is needed). If
360 /// this is _not_ the correct transform, then this allows moving values between different
361 /// coordinate system types without adjusting the values correctly, leading to a defeat of
362 /// their type safety.
363 #[doc(alias = "from_nautical_angles")]
364 #[doc(alias = "from_cardan_angles")]
365 #[doc(alias = "from_ypr")]
366 #[deprecated = "Prefer `tait_bryan_builder` to avoid argument-order confusion"]
367 pub unsafe fn from_tait_bryan_angles(
368 yaw: impl Into<Angle>,
369 pitch: impl Into<Angle>,
370 roll: impl Into<Angle>,
371 ) -> Self {
372 Self {
373 // we have intrinstic Tait-Bryan angles, and we want to construct a unit quaternion.
374 // Looking at the implementation, nalgebra::UnitQuaternion::from_euler_angles uses the
375 // same construction as Wikipedia gives for "Euler angles (in 3-2-1 sequence) to
376 // quaternion conversion":
377 //
378 // <https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Euler_angles_(in_3-2-1_sequence)_to_quaternion_conversion>
379 //
380 // suggesting that it uses 3-2-1, so z-y-x, so Tait-Bryan not "classic" Euler angles.
381 // furthermore, the naming of the arguments uses the words "roll", "pitch", and "yaw",
382 // which suggests they represent z, y', and x'' (by convention), which matches the
383 // documentation we've written for this function. so, we can simply pass our arguments
384 // in unchanged (minding the order).
385 //
386 // it would be nice if nalgebra's docs were more explicit about this. if they do,
387 // probably through one of these issues, we should update reasoning here accordingly to
388 // instill more confidence.
389 //
390 // - https://github.com/dimforge/nalgebra/issues/1294
391 // - https://github.com/dimforge/nalgebra/issues/1446
392 inner: UnitQuaternion::from_euler_angles(
393 roll.into().get::<radian>(),
394 pitch.into().get::<radian>(),
395 yaw.into().get::<radian>(),
396 ),
397 from: PhantomData::<From>,
398 to: PhantomData::<To>,
399 }
400 }
401
402 /// Asserts that the rotational transform from `From` to `To` is one that returns the original
403 /// point or vector when applied.
404 ///
405 /// # Safety
406 ///
407 /// Like [`RigidBodyTransform::identity`], this allows you to claim that the "correct"
408 /// rotational transform between the coordinate systems `From` and `To` is the identity
409 /// function (and that no translation is needed). If this is _not_ the correct transform, then
410 /// this allows moving values between different coordinate system types without adjusting the
411 /// values correctly, leading to a defeat of their type safety.
412 #[must_use]
413 pub unsafe fn identity() -> Self {
414 Self {
415 inner: UnitQuaternion::identity(),
416 from: PhantomData::<From>,
417 to: PhantomData::<To>,
418 }
419 }
420
421 /// Changes the target coordinate system of the rotation to `<NewTo>` with no changes to the
422 /// rotational angles.
423 ///
424 /// This is useful when you have two coordinate systems that you know have exactly equivalent
425 /// axes, and you need the types to "work out". This can be the case, for instance, when two
426 /// crates have both separately declared a NED-like coordinate system centered on the same
427 /// object, and you have a rotation from some coordinate system into one of them, but you want
428 /// the end type to be in the other.
429 ///
430 /// This is not how you _generally_ want to convert between coordinate systems. For that,
431 /// you'll want to use [`RigidBodyTransform`].
432 ///
433 /// This is exactly equivalent to re-constructing the rotation with the same rotational angles
434 /// using `<NewTo>` instead of `<To>`, just more concise and legible. That is, it is exactly
435 /// equal to:
436 ///
437 /// ```
438 /// use sguaba::{system, math::Rotation};
439 /// use uom::si::f64::Angle;
440 /// use uom::si::angle::degree;
441 /// use approx::assert_relative_eq;
442 ///
443 /// system!(struct PlaneFrd using NED);
444 /// system!(struct PlaneNedFromCrate1 using NED);
445 /// system!(struct PlaneNedFromCrate2 using NED);
446 ///
447 /// // SAFETY
448 /// // we're claiming, without any factual basis for doing so,
449 /// // that this _is_ the plane's orientation.
450 /// let rotation_into_1 = unsafe {
451 /// Rotation::<PlaneFrd, PlaneNedFromCrate1>::from_tait_bryan_angles(
452 /// Angle::new::<degree>(30.),
453 /// Angle::new::<degree>(45.),
454 /// Angle::new::<degree>(90.),
455 /// )
456 /// };
457 ///
458 /// let (yaw, pitch, roll) = rotation_into_1.to_tait_bryan_angles();
459 /// assert_relative_eq!(
460 /// unsafe { Rotation::<PlaneFrd, PlaneNedFromCrate2>::from_tait_bryan_angles(yaw, pitch, roll) },
461 /// unsafe { rotation_into_1.is_also_into::<PlaneNedFromCrate2>() }
462 /// );
463 /// ```
464 ///
465 /// # Safety
466 ///
467 /// This asserts that the transform `From` to `To` is the same as the transform from `From` to
468 /// `NewTo`. However, if that is _not_ the case, the resulting transform would allow violating
469 /// type safety by moving, say, a coordinate into `NewTo` without correctly adjusting its
470 /// values.
471 #[must_use]
472 pub unsafe fn is_also_into<NewTo>(self) -> Rotation<From, NewTo> {
473 Rotation {
474 inner: self.inner,
475 from: self.from,
476 to: PhantomData::<NewTo>,
477 }
478 }
479
480 /// Changes the origin coordinate system of the rotation to `<NewFrom>` with no changes to the
481 /// rotational angles.
482 ///
483 /// This is useful when you have two coordinate systems that you know have exactly equivalent
484 /// axes, and you need the types to "work out". This can be the case, for instance, when two
485 /// crates have both separately declared a NED-like coordinate system centered on the same
486 /// object, and you have a rotation into some coordinate system from one of them, but need to
487 /// transform from something typed to be in the other.
488 ///
489 /// This is not how you _generally_ want to convert between coordinate systems. For that,
490 /// you'll want to use [`RigidBodyTransform`].
491 ///
492 /// This is exactly equivalent to re-constructing the rotation with the same rotational angles
493 /// using `<NewFrom>` instead of `<From>`, just more concise and legible. That is, it is exactly
494 /// equal to:
495 ///
496 /// ```
497 /// use sguaba::{system, math::Rotation};
498 /// use uom::si::f64::Angle;
499 /// use uom::si::angle::degree;
500 /// use approx::assert_relative_eq;
501 ///
502 /// system!(struct PlaneFrd using NED);
503 /// system!(struct PlaneNedFromCrate1 using NED);
504 /// system!(struct PlaneNedFromCrate2 using NED);
505 ///
506 /// // SAFETY
507 /// // we're claiming, without any factual basis for doing so,
508 /// // that this _is_ the plane's orientation.
509 /// let rotation_into_1 = unsafe {
510 /// Rotation::<PlaneNedFromCrate1, PlaneFrd>::from_tait_bryan_angles(
511 /// Angle::new::<degree>(30.),
512 /// Angle::new::<degree>(45.),
513 /// Angle::new::<degree>(90.),
514 /// )
515 /// };
516 ///
517 /// let (yaw, pitch, roll) = rotation_into_1.to_tait_bryan_angles();
518 /// assert_relative_eq!(
519 /// unsafe { Rotation::<PlaneNedFromCrate2, PlaneFrd>::from_tait_bryan_angles(yaw, pitch, roll) },
520 /// unsafe { rotation_into_1.is_also_from::<PlaneNedFromCrate2>() }
521 /// );
522 /// ```
523 ///
524 /// # Safety
525 ///
526 /// This asserts that the transform `From` to `To` is the same as the transform from `NewFrom`
527 /// to `To`. However, if that is _not_ the case, the resulting transform would allow violating
528 /// type safety by moving, say, a coordinate from `NewFrom` without correctly adjusting its
529 /// values.
530 #[must_use]
531 pub unsafe fn is_also_from<NewFrom>(self) -> Rotation<NewFrom, To> {
532 Rotation {
533 inner: self.inner,
534 from: PhantomData::<NewFrom>,
535 to: self.to,
536 }
537 }
538
539 /// Casts the coordinate system type parameter `From` of the rotation to the equivalent
540 /// coordinate system `AlsoFrom`.
541 ///
542 /// See [`EquivalentTo`] for details on when this is useful (and safe).
543 ///
544 /// Note that this performs no modifications to the transform itself, as that should be
545 /// unnecessary when `EquivalentTo` is implemented.
546 #[must_use]
547 pub fn cast_type_of_from<AlsoFrom>(self) -> Rotation<AlsoFrom, To>
548 where
549 From: EquivalentTo<AlsoFrom>,
550 {
551 Rotation {
552 inner: self.inner,
553 from: PhantomData::<AlsoFrom>,
554 to: self.to,
555 }
556 }
557
558 /// Casts the coordinate system type parameter `To` of the rotation to the equivalent
559 /// coordinate system `AlsoTo`.
560 ///
561 /// See [`EquivalentTo`] for details on when this is useful (and safe).
562 ///
563 /// Note that this performs no modifications to the rotation itself, as that should be
564 /// unnecessary when `EquivalentTo` is implemented.
565 #[must_use]
566 pub fn cast_type_of_to<AlsoTo>(self) -> Rotation<From, AlsoTo>
567 where
568 To: EquivalentTo<AlsoTo>,
569 {
570 Rotation {
571 inner: self.inner,
572 from: self.from,
573 to: PhantomData::<AlsoTo>,
574 }
575 }
576
577 /// Returns the equal-but-opposite transform to this one.
578 ///
579 /// That is, a rotation _from_ the [`CoordinateSystem`] `To` _into_ the coordinate system
580 /// `From`.
581 #[must_use]
582 pub fn inverse(&self) -> Rotation<To, From> {
583 Rotation {
584 inner: self.inner.inverse(),
585 from: PhantomData::<To>,
586 to: PhantomData::<From>,
587 }
588 }
589
590 /// Linearly interpolate between this rotation and another one.
591 ///
592 /// Conceptually returns `self * (1.0 - t) + rhs * t`, i.e., the linear blend of the two
593 /// rotations using the scalar value `t`.
594 ///
595 /// Note that this function inherently normalizes the underlying rotation such that it remains
596 /// a unit quaternion.
597 ///
598 /// The value for `t` is not restricted to the range [0, 1].
599 #[must_use]
600 pub fn nlerp(&self, rhs: &Self, t: f64) -> Self {
601 Self {
602 inner: self.inner.nlerp(&rhs.inner, t),
603 from: self.from,
604 to: self.to,
605 }
606 }
607
608 /// Returns the yaw-pitch-roll [Tait-Bryan angles][tb] that describe this rotation.
609 ///
610 /// See [`Rotation::from_tait_bryan_angles`] for documentation about the exact meaning of yaw,
611 /// pitch, and roll here.
612 ///
613 /// The angles returned are, perhaps counter-intuitively but also in alignment with
614 /// [`Rotation::from_tait_bryan_angles`], the rotations that must be performed to go from `To`
615 /// _into_ `From`.
616 ///
617 /// [tb]: https://en.wikipedia.org/wiki/Euler_angles#Tait%E2%80%93Bryan_angles
618 #[must_use]
619 pub fn to_tait_bryan_angles(&self) -> (Angle, Angle, Angle) {
620 let (roll, pitch, yaw) = self.inner.euler_angles();
621 (
622 Angle::new::<radian>(yaw),
623 Angle::new::<radian>(pitch),
624 Angle::new::<radian>(roll),
625 )
626 }
627
628 /// Returns the [Euler angles] describing this rotation.
629 ///
630 /// The use of this method is discouraged as Eulers angles are both hard to work with and do
631 /// not have a single, canonical definition across domains (eg, [in aerospace]).
632 ///
633 /// The angles returned are, perhaps counter-intuitively but in alignment with
634 /// [`Rotation::from_tait_bryan_angles`], the rotations that must be performed to go
635 /// from `To` _into_ `From`.
636 ///
637 /// [Euler angles]: https://en.wikipedia.org/wiki/Euler_angles
638 /// [in aerospace]: https://en.wikipedia.org/wiki/Aircraft_principal_axes
639 #[must_use]
640 pub fn euler_angles(&self) -> (Angle, Angle, Angle) {
641 let (roll, pitch, yaw) = self.inner.euler_angles();
642 (
643 Angle::new::<radian>(yaw),
644 Angle::new::<radian>(pitch),
645 Angle::new::<radian>(roll),
646 )
647 }
648
649 /// Provides a type-safe builder for constructing a rotation from Tait-Bryan angles.
650 ///
651 /// This builder enforces the correct intrinsic order (yaw → pitch → roll) at compile time
652 /// and provides named parameters to prevent argument order confusion.
653 ///
654 /// # Examples
655 ///
656 /// ```rust
657 /// use sguaba::{system, math::Rotation};
658 /// use uom::si::{f64::Angle, angle::degree};
659 ///
660 /// system!(struct PlaneNed using NED);
661 /// system!(struct PlaneFrd using FRD);
662 ///
663 /// let rotation = unsafe {
664 /// Rotation::<PlaneNed, PlaneFrd>::tait_bryan_builder()
665 /// .yaw(Angle::new::<degree>(90.0))
666 /// .pitch(Angle::new::<degree>(45.0))
667 /// .roll(Angle::new::<degree>(5.0))
668 /// .build()
669 /// };
670 /// ```
671 ///
672 /// The following examples should fail to compile because the angles are not provided
673 /// in the correct order:
674 ///
675 /// ```compile_fail
676 /// # use sguaba::{system, math::Rotation};
677 /// # use uom::si::{f64::Angle, angle::degree};
678 /// # system!(struct PlaneNed using NED);
679 /// # system!(struct PlaneFrd using FRD);
680 /// // Cannot call pitch before yaw - pitch() method doesn't exist on NeedsYaw state
681 /// let rotation = unsafe {
682 /// Rotation::<PlaneNed, PlaneFrd>::tait_bryan_builder()
683 /// .pitch(Angle::new::<degree>(45.0))
684 /// .yaw(Angle::new::<degree>(90.0))
685 /// .roll(Angle::new::<degree>(5.0))
686 /// .build()
687 /// };
688 /// ```
689 ///
690 /// ```compile_fail
691 /// # use sguaba::{system, math::Rotation};
692 /// # use uom::si::{f64::Angle, angle::degree};
693 /// # system!(struct PlaneNed using NED);
694 /// # system!(struct PlaneFrd using FRD);
695 /// // Cannot call build before setting all angles - build() method doesn't exist on NeedsPitch state
696 /// let rotation = unsafe {
697 /// Rotation::<PlaneNed, PlaneFrd>::tait_bryan_builder()
698 /// .yaw(Angle::new::<degree>(90.0))
699 /// .build()
700 /// };
701 /// ```
702 ///
703 /// ```compile_fail
704 /// # use sguaba::{system, math::Rotation};
705 /// # use uom::si::{f64::Angle, angle::degree};
706 /// # system!(struct PlaneNed using NED);
707 /// # system!(struct PlaneFrd using FRD);
708 /// // Cannot call roll before pitch - roll() method doesn't exist on NeedsPitch state
709 /// let rotation = unsafe {
710 /// Rotation::<PlaneNed, PlaneFrd>::tait_bryan_builder()
711 /// .yaw(Angle::new::<degree>(90.0))
712 /// .roll(Angle::new::<degree>(5.0))
713 /// .pitch(Angle::new::<degree>(45.0))
714 /// .build()
715 /// };
716 /// ```
717 ///
718 /// # Safety
719 ///
720 /// The builder's `build()` method is `unsafe` for the same reasons as
721 /// [`from_tait_bryan_angles`](Self::from_tait_bryan_angles): you are asserting
722 /// a relationship between coordinate systems `From` and `To`.
723 pub fn tait_bryan_builder(
724 ) -> tait_bryan_builder::TaitBryanBuilder<tait_bryan_builder::NeedsYaw, Rotation<From, To>>
725 {
726 tait_bryan_builder::TaitBryanBuilder::new()
727 }
728}
729
730impl<From, To> Rotation<From, To> {
731 /// Transforms an element in [`CoordinateSystem`] `From` into `To`.
732 #[doc(alias = "apply")]
733 pub fn transform<T>(&self, in_from: T) -> <T as Mul<Self>>::Output
734 where
735 T: Mul<Self>,
736 {
737 in_from * *self
738 }
739
740 /// Transforms an element in [`CoordinateSystem`] `To` into `From`.
741 ///
742 /// This is equivalent to (but more efficient than) first inverting the transform with
743 /// [`RigidBodyTransform::inverse`] and then calling [`RigidBodyTransform::transform`].
744 #[doc(alias = "undo")]
745 pub fn inverse_transform<T>(&self, in_to: T) -> <Self as Mul<T>>::Output
746 where
747 Self: Mul<T>,
748 {
749 *self * in_to
750 }
751}
752
753#[cfg(any(test, feature = "approx"))]
754impl<From, To> AbsDiffEq<Self> for Rotation<From, To> {
755 type Epsilon = <f64 as AbsDiffEq>::Epsilon;
756
757 fn default_epsilon() -> Self::Epsilon {
758 UnitQuaternion::default_epsilon()
759 }
760
761 fn abs_diff_eq(&self, other: &Self, epsilon: Self::Epsilon) -> bool {
762 self.inner.abs_diff_eq(&other.inner, epsilon)
763 }
764}
765
766#[cfg(any(test, feature = "approx"))]
767impl<From, To> RelativeEq for Rotation<From, To> {
768 fn default_max_relative() -> Self::Epsilon {
769 UnitQuaternion::default_max_relative()
770 }
771
772 fn relative_eq(
773 &self,
774 other: &Self,
775 epsilon: Self::Epsilon,
776 max_relative: Self::Epsilon,
777 ) -> bool {
778 self.inner.relative_eq(&other.inner, epsilon, max_relative)
779 }
780}
781
782impl<From, To> Neg for Rotation<From, To> {
783 type Output = Rotation<To, From>;
784
785 fn neg(self) -> Self::Output {
786 self.inverse()
787 }
788}
789
790// Rotation<From, Over> * Rotation<Over, To> -> Rotation<From, To>
791//
792// self.inner is equivalent to a rotation matrix whose rows are `From` and columns are `Over`.
793// rhs.inner is equivalent to a rotation matrix whose rows are `Over` and columns are `To`
794// to arrive at a matrix whose rows are `From` and columns are `To` (which is what we store in
795// `Rotation<From, To>`), we need:
796//
797// (From x Over) * (Over x To)
798//
799// which is then self.inner * rhs.inner.
800impl<From, Over, To> Mul<Rotation<Over, To>> for Rotation<From, Over> {
801 type Output = Rotation<From, To>;
802
803 fn mul(self, rhs: Rotation<Over, To>) -> Self::Output {
804 Self::Output {
805 inner: self.inner * rhs.inner,
806 from: self.from,
807 to: rhs.to,
808 }
809 }
810}
811
812// Rotation<From, To> * Bearing<To> -> Bearing<From>
813impl<From, To> Mul<Bearing<To>> for Rotation<From, To>
814where
815 From: crate::systems::BearingDefined,
816 To: crate::systems::BearingDefined,
817{
818 type Output = Bearing<From>;
819
820 fn mul(self, rhs: Bearing<To>) -> Self::Output {
821 (self * rhs.to_unit_vector())
822 .bearing_at_origin()
823 .expect("magnitude should still be 1 after rotation")
824 }
825}
826
827// Bearing<From> * Rotation<From, To> -> Bearing<To>
828impl<From, To> Mul<Rotation<From, To>> for Bearing<From>
829where
830 From: crate::systems::BearingDefined,
831 To: crate::systems::BearingDefined,
832{
833 type Output = Bearing<To>;
834
835 fn mul(self, rhs: Rotation<From, To>) -> Self::Output {
836 (self.to_unit_vector() * rhs)
837 .bearing_at_origin()
838 .expect("magnitude should still be 1 after rotation")
839 }
840}
841
842/// Defines a [rigid body transform][isometry] between two [`CoordinateSystem`]s.
843///
844/// A rigid transform may include both translation and [rotation](Rotation).
845///
846/// There are generally three ways to construct a rigid body transform:
847///
848/// 1. by using [`engineering::Pose::map_as_zero_in`] when you already have an
849/// [`engineering::Pose`];
850/// 2. by using [`RigidBodyTransform::ecef_to_ned_at`] when you wish to translate between [`Ecef`]
851/// and a [`NedLike`] [`CoordinateSystem`]; or
852/// 3. by using [`RigidBodyTransform::new`] to construct transforms from arbitrary translation and
853/// rotation.
854///
855/// Mathematically speaking, this is a type-safe wrapper around an [Euclidian isometry][isometry].
856///
857/// Transforms can be chained with other transforms (including [`Rotation`]s) using `*` (ie, the
858/// [`Mul`] trait) or with [`RigidBodyTransform::and_then`] (they're equivalent). They can also be
859/// applied to [`Coordinate`], [`Vector`], and other types either by multiplication (or division
860/// for inverse transforms) or by using [`RigidBodyTransform::transform`] (or
861/// [`RigidBodyTransform::inverse_transform`]).
862///
863/// <div class="warning">
864///
865/// Note that this type implements `Deserialize` despite having `unsafe` constructors -- this is
866/// because doing otherwise would be extremely unergonomic. However, when deserializing, the
867/// coordinate system of the deserialized value is _not_ checked, so this is a foot-gun to be
868/// mindful of.
869///
870/// </div>
871///
872/// <div class="warning">
873///
874/// The order of the operands to `*` matter, and do not match the mathematical convention.
875/// Specifically, matrix multiply for transforms traditionally have the transform on the left and
876/// the vector to transform on the right. However, doing so here would lead to a type signature of
877///
878/// ```rust,ignore
879/// let _: Coordinate<To> = RigidBodyTransform<From, To> * Coordinate<From>;
880/// ```
881///
882/// Which violates the expectation that a matrix multiply eliminates the "middle" component (ie,
883/// (m × n)(n × p) = (m × p)). So, we require that the transform is on the _right_ to go from
884/// `From` into `To`, and that the transform is on the _left_ to go from `To` into `From`.
885///
886/// </div>
887///
888/// [isometry]: https://en.wikipedia.org/wiki/Rigid_transformation
889#[derive(Debug)]
890#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
891// don't require From/To: Serialize/Deserialize since we skip it anyway
892#[cfg_attr(feature = "serde", serde(bound = ""))]
893// no need for the "inner": indirection
894#[cfg_attr(feature = "serde", serde(transparent))]
895pub struct RigidBodyTransform<From, To> {
896 /// This is _actually_ the isometry from `To` into `From`, which means we need to take the
897 /// _inverse_ transform to go from `From` into `To`. For more details about this, see the docs
898 /// on `Rotation.inner`.
899 pub(crate) inner: Isometry3,
900 #[cfg_attr(feature = "serde", serde(skip))]
901 pub(crate) from: PhantomData<From>,
902 #[cfg_attr(feature = "serde", serde(skip))]
903 pub(crate) to: PhantomData<To>,
904}
905
906// manual impls of Clone and Copy to avoid requiring In: Copy + Clone
907impl<From, To> Clone for RigidBodyTransform<From, To> {
908 fn clone(&self) -> Self {
909 *self
910 }
911}
912impl<From, To> Copy for RigidBodyTransform<From, To> {}
913
914impl<To> RigidBodyTransform<Ecef, To>
915where
916 To: CoordinateSystem<Convention = NedLike>,
917{
918 /// Constructs the transformation from [`Ecef`] to [`NedLike`] at the given latitude and
919 /// longitude.
920 ///
921 /// The lat/lon is needed because the orientation of North with respect to ECEF depends on
922 /// where on the globe you are, and because the transform of something like (0, 0, 0) in
923 /// [`NedLike`] into ECEF (and vice-verse) requires knowing the ECEF coordinates of this
924 /// [`NedLike`]'s origin.
925 ///
926 /// See also
927 /// <https://en.wikipedia.org/wiki/Local_tangent_plane_coordinates#Local_north,_east,_down_(NED)_coordinates>.
928 ///
929 /// # Safety
930 ///
931 /// This function only produces a valid transform from [`Ecef`] to the NED-like `To` if
932 /// [`Coordinate::<To>::origin()`](Coordinate::origin) lies at the provided lat/lon. If that is
933 /// not the case, the returned `RigidBodyTransform` will allow moving from [`Ecef`] to `To`
934 /// without the appropriate transformation of the components of the input, leading to outputs
935 /// that are typed to be in `To` but are in fact not.
936 #[must_use]
937 pub unsafe fn ecef_to_ned_at(position: &Wgs84) -> Self {
938 let ecef = Coordinate::<Ecef>::from_wgs84(position);
939 let translation = Vector::from(ecef);
940
941 // SAFETY: same safety caveat as us + we will also apply the necessary translation.
942 let rotation = unsafe { Rotation::ecef_to_ned_at(position.latitude, position.longitude) };
943
944 // SAFETY: this is indeed a correct transform from ECEF to an NED at `position`.
945 unsafe { Self::new(translation, rotation) }
946 }
947}
948
949impl<To> RigidBodyTransform<Ecef, To>
950where
951 To: CoordinateSystem<Convention = EnuLike>,
952{
953 /// Constructs the transformation from [`Ecef`] to [`EnuLike`] at the given WGS84 position.
954 ///
955 /// The position is needed because the orientation of East and North with respect to ECEF depends on
956 /// where on the globe you are.
957 ///
958 /// See also
959 /// <https://en.wikipedia.org/wiki/Local_tangent_plane_coordinates#Local_east,_north,_up_(ENU)_coordinates>.
960 ///
961 /// # Safety
962 ///
963 /// This function only produces a valid transform from [`Ecef`] to the ENU-like `To` if
964 /// [`Coordinate::<To>::origin()`](Coordinate::origin) lies at the provided position. If that is
965 /// not the case, the returned `RigidBodyTransform` will allow moving from [`Ecef`] to `To`
966 /// without the appropriate transformation of the components of the input, leading to outputs
967 /// that are typed to be in `To` but are in fact not.
968 #[must_use]
969 pub unsafe fn ecef_to_enu_at(position: &Wgs84) -> Self {
970 let ecef = Coordinate::<Ecef>::from_wgs84(position);
971 let translation = Vector::from(ecef);
972
973 // SAFETY: same safety caveat as us + we will also apply the necessary translation.
974 let rotation = unsafe { Rotation::ecef_to_enu_at(position.latitude, position.longitude) };
975
976 // SAFETY: this is indeed a correct transform from ECEF to an ENU at `position`.
977 unsafe { Self::new(translation, rotation) }
978 }
979}
980
981impl<From, To> RigidBodyTransform<From, To> {
982 /// Constructs a transform directly from a translation and a rotation.
983 ///
984 /// The translation here should be what must be applied to coordinates and vectors in `To` to
985 /// transform them into coordinates and vectors in `From`. In other words, the _inverse_ of
986 /// this translation and rotation will be applied in the `transform` methods to go from `From`
987 /// to `To`.
988 ///
989 /// # Safety
990 ///
991 /// This method is marked as `unsafe` for the same reason [`engineering::Pose::map_as_zero_in`]
992 /// is; if you construct a transform incorrectly, it allows moving between different
993 /// type-enforced coordinate systems without performing the correct conversions, leading to a
994 /// defeat of type safety.
995 #[must_use]
996 pub unsafe fn new(translation: Vector<From>, rotation: Rotation<From, To>) -> Self {
997 Self {
998 inner: Isometry3::from_parts(Translation3::from(translation.inner), rotation.inner),
999 from: PhantomData::<From>,
1000 to: PhantomData::<To>,
1001 }
1002 }
1003
1004 /// Chains two transforms to produce a new transform that can transform directly from `From` to
1005 /// `NewTo`.
1006 ///
1007 /// ```rust
1008 /// use sguaba::{
1009 /// system, Coordinate, Vector,
1010 /// math::{RigidBodyTransform, Rotation},
1011 /// systems::{Ecef, Wgs84},
1012 /// };
1013 /// use uom::si::f64::{Angle, Length};
1014 /// use uom::si::{angle::degree, length::meter};
1015 ///
1016 /// system!(struct PlaneFrd using FRD);
1017 /// system!(struct PlaneNed using NED);
1018 ///
1019 /// // we can construct a transform from ECEF to PlaneNed
1020 /// // (we can construct the ECEF from a WGS84 lat/lon)
1021 /// let location = Wgs84::builder()
1022 /// .latitude(Angle::new::<degree>(0.)).expect("latitude is in-range")
1023 /// .longitude(Angle::new::<degree>(10.))
1024 /// .altitude(Length::new::<meter>(0.))
1025 /// .build();
1026 ///
1027 /// // SAFETY: we're claiming that `location` is the location of `PlaneNed`'s origin.
1028 /// let ecef_to_ned = unsafe { RigidBodyTransform::ecef_to_ned_at(&location) };
1029 ///
1030 /// // we can also construct a (rotation) transform from PlaneNed to PlaneFrd
1031 /// // assuming we know what direction the plane is facing.
1032 /// // SAFETY: we're claiming that these angles are the orientation of the plane in NED.
1033 /// let ned_to_frd = unsafe {
1034 /// Rotation::<PlaneNed, PlaneFrd>::from_tait_bryan_angles(
1035 /// Angle::new::<degree>(0.),
1036 /// Angle::new::<degree>(45.),
1037 /// Angle::new::<degree>(23.),
1038 /// )
1039 /// };
1040 ///
1041 /// // and we can chain the two to give us a single transform that goes
1042 /// // from ECEF to PlaneFrd in a single computation.
1043 /// let ecef_to_frd = ecef_to_ned.and_then(ned_to_frd);
1044 /// ```
1045 pub fn and_then<NewTo, Transform>(self, rhs: Transform) -> RigidBodyTransform<From, NewTo>
1046 where
1047 Self: Mul<Transform, Output = RigidBodyTransform<From, NewTo>>,
1048 {
1049 self * rhs
1050 }
1051
1052 /// Asserts that the transform from `From` to `To` is one that returns the original point or
1053 /// vector when applied.
1054 ///
1055 /// # Safety
1056 ///
1057 /// This allows you to claim that the "correct" transform between the coordinate systems `From`
1058 /// and `To` is the identity function. If this is _not_ the correct transform, then this allows
1059 /// moving values between different coordinate system types without adjusting the values
1060 /// correctly, leading to a defeat of their type safety.
1061 #[must_use]
1062 pub unsafe fn identity() -> Self {
1063 Self::new(Vector::zero(), Rotation::identity())
1064 }
1065
1066 /// Casts the coordinate system type parameter `From` of the transform to the equivalent
1067 /// coordinate system `AlsoFrom`.
1068 ///
1069 /// See [`EquivalentTo`] for details on when this is useful (and safe).
1070 ///
1071 /// Note that this performs no modifications to the transform itself, as that should be
1072 /// unnecessary when `EquivalentTo` is implemented.
1073 #[must_use]
1074 pub fn cast_type_of_from<AlsoFrom>(self) -> RigidBodyTransform<AlsoFrom, To>
1075 where
1076 From: EquivalentTo<AlsoFrom>,
1077 {
1078 RigidBodyTransform {
1079 inner: self.inner,
1080 from: PhantomData::<AlsoFrom>,
1081 to: self.to,
1082 }
1083 }
1084
1085 /// Casts the coordinate system type parameter `To` of the transform to the equivalent
1086 /// coordinate system `AlsoTo`.
1087 ///
1088 /// See [`EquivalentTo`] for details on when this is useful (and safe).
1089 ///
1090 /// Note that this performs no modifications to the transform itself, as that should be
1091 /// unnecessary when `EquivalentTo` is implemented.
1092 #[must_use]
1093 pub fn cast_type_of_to<AlsoTo>(self) -> RigidBodyTransform<From, AlsoTo>
1094 where
1095 To: EquivalentTo<AlsoTo>,
1096 {
1097 RigidBodyTransform {
1098 inner: self.inner,
1099 from: self.from,
1100 to: PhantomData::<AlsoTo>,
1101 }
1102 }
1103
1104 /// Returns the equal-but-opposite transform to this one.
1105 ///
1106 /// That is, a transform _from_ the [`CoordinateSystem`] `To` _into_ the coordinate system
1107 /// `From`.
1108 #[must_use]
1109 pub fn inverse(&self) -> RigidBodyTransform<To, From> {
1110 RigidBodyTransform::<To, From> {
1111 inner: self.inner.inverse(),
1112 from: PhantomData,
1113 to: PhantomData,
1114 }
1115 }
1116
1117 /// Linearly interpolate between this transform and another one.
1118 ///
1119 /// Conceptually returns `self * (1.0 - t) + rhs * t`, i.e., the linear blend of the two
1120 /// transforms using the scalar value `t`.
1121 ///
1122 /// Internally, this linearly interpolates the translation and rotation separately, and
1123 /// normalizes the rotation in the process (see [`Rotation::nlerp`]).
1124 ///
1125 /// The value for `t` is not restricted to the range [0, 1].
1126 #[must_use]
1127 pub fn lerp(&self, rhs: &Self, t: f64) -> Self {
1128 // SAFETY: if `self` and `rhs` are both correct transforms from `From` to `To`, lerping
1129 // between them should also be a valid transform.
1130 unsafe {
1131 Self::new(
1132 self.translation().lerp(&rhs.translation(), t),
1133 self.rotation().nlerp(&rhs.rotation(), t),
1134 )
1135 }
1136 }
1137
1138 /// Returns the translation of [`Coordinate::origin`] in `To` relative to the
1139 /// [`Coordinate::origin`] in `From`.
1140 ///
1141 /// That is, perhaps counter-intuitively but in alignment with [`RigidBodyTransform::new`], the
1142 /// translation that must be performed to go from `To` _into_ `From`.
1143 #[must_use]
1144 pub fn translation(&self) -> Vector<From> {
1145 Vector::from_nalgebra_vector(self.inner.translation.vector)
1146 }
1147
1148 /// Returns the rotation of the coordinate system `To` with respect to the coordinate system
1149 /// `From`.
1150 #[must_use]
1151 pub fn rotation(&self) -> Rotation<From, To> {
1152 Rotation {
1153 inner: self.inner.rotation,
1154 from: self.from,
1155 to: self.to,
1156 }
1157 }
1158}
1159
1160impl<From, To> RigidBodyTransform<From, To> {
1161 /// Transforms an element in [`CoordinateSystem`] `From` into `To`.
1162 ///
1163 /// <div class="warning">
1164 ///
1165 /// Note that this transformation behaves differently for vectors than it does for coordinates.
1166 /// Following the convention in computer vision, a vector defines a displacement _without an
1167 /// explicit origin_. Thus, when transformed into a different coordinate system the
1168 /// displacement points in a different direction _but retains its length_. In other words,
1169 /// vectors are only subjected to the rotation part of the transform.
1170 ///
1171 /// Note further that a bearing is transformed exactly the way it would be if it were a unit
1172 /// vector in the direction of the bearing.
1173 ///
1174 /// </div>
1175 #[doc(alias = "apply")]
1176 pub fn transform<T>(&self, in_from: T) -> <T as Mul<Self>>::Output
1177 where
1178 T: Mul<Self>,
1179 {
1180 in_from * *self
1181 }
1182
1183 /// Transforms an element in [`CoordinateSystem`] `To` into `From`.
1184 ///
1185 /// This is equivalent to (but more efficient than) first inverting the transform with
1186 /// [`RigidBodyTransform::inverse`] and then calling [`RigidBodyTransform::transform`].
1187 ///
1188 /// <div class="warning">
1189 ///
1190 /// Note that this transformation behaves differently for vectors than it does for coordinates.
1191 /// Following the convention in computer vision, a vector defines a displacement _without an
1192 /// explicit origin_. Thus, when transformed into a different coordinate system the
1193 /// displacement points in a different direction _but retains its length_. In other words,
1194 /// vectors are only subjected to the rotation part of the transform.
1195 ///
1196 /// Note further that a bearing is transformed exactly the way it would be if it were a unit
1197 /// vector in the direction of the bearing.
1198 ///
1199 /// </div>
1200 #[doc(alias = "undo")]
1201 pub fn inverse_transform<T>(&self, in_to: T) -> <Self as Mul<T>>::Output
1202 where
1203 Self: Mul<T>,
1204 {
1205 *self * in_to
1206 }
1207}
1208
1209impl<From, To> PartialEq<Self> for RigidBodyTransform<From, To> {
1210 fn eq(&self, other: &Self) -> bool {
1211 self.inner.eq(&other.inner)
1212 }
1213}
1214
1215impl<From, To> Display for RigidBodyTransform<From, To> {
1216 fn fmt(&self, f: &mut Formatter<'_>) -> fmt::Result {
1217 write!(
1218 f,
1219 "Position: {}, Orientation: {}",
1220 self.translation(),
1221 self.rotation()
1222 )
1223 }
1224}
1225
1226impl<From, To> Neg for RigidBodyTransform<From, To> {
1227 type Output = RigidBodyTransform<To, From>;
1228
1229 fn neg(self) -> Self::Output {
1230 self.inverse()
1231 }
1232}
1233
1234// recall from the docs on `Rotation.inner` that conversions of `From` -> `To` use _inverse_
1235// transforms, and conversions from `To` -> `From` use regular `transform`.
1236//
1237// further recall that we want to have eliminated "dimensions" be adjacent in the input to match
1238// matrix expectations (ie, (m × n)(n × p) = (m × p)).
1239
1240// Coordinate<From> * Rotation<From, To> -> Coordinate<To>
1241impl<From, To> Mul<Rotation<From, To>> for Coordinate<From> {
1242 type Output = Coordinate<To>;
1243
1244 fn mul(self, rhs: Rotation<From, To>) -> Self::Output {
1245 Coordinate::from_nalgebra_point(rhs.inner.inverse_transform_point(&self.point))
1246 }
1247}
1248
1249// Rotation<From, To> * Coordinate<To> -> Coordinate<From>
1250impl<From, To> Mul<Coordinate<To>> for Rotation<From, To> {
1251 type Output = Coordinate<From>;
1252
1253 fn mul(self, rhs: Coordinate<To>) -> Self::Output {
1254 Coordinate::from_nalgebra_point(self.inner.transform_point(&rhs.point))
1255 }
1256}
1257
1258impl<From, To> Mul<Rotation<From, To>> for Vector<From> {
1259 type Output = Vector<To>;
1260
1261 fn mul(self, rhs: Rotation<From, To>) -> Self::Output {
1262 Vector::from_nalgebra_vector(rhs.inner.inverse_transform_vector(&self.inner))
1263 }
1264}
1265
1266impl<From, To> Mul<Vector<To>> for Rotation<From, To> {
1267 type Output = Vector<From>;
1268
1269 fn mul(self, rhs: Vector<To>) -> Self::Output {
1270 Vector::from_nalgebra_vector(self.inner.transform_vector(&rhs.inner))
1271 }
1272}
1273
1274impl<From, To> Mul<RigidBodyTransform<From, To>> for Coordinate<From> {
1275 type Output = Coordinate<To>;
1276
1277 fn mul(self, rhs: RigidBodyTransform<From, To>) -> Self::Output {
1278 Coordinate::from_nalgebra_point(rhs.inner.inverse_transform_point(&self.point))
1279 }
1280}
1281
1282impl<From, To> Mul<Coordinate<To>> for RigidBodyTransform<From, To> {
1283 type Output = Coordinate<From>;
1284
1285 fn mul(self, rhs: Coordinate<To>) -> Self::Output {
1286 Coordinate::from_nalgebra_point(self.inner.transform_point(&rhs.point))
1287 }
1288}
1289
1290impl<From, To> Mul<RigidBodyTransform<From, To>> for Vector<From> {
1291 type Output = Vector<To>;
1292
1293 fn mul(self, rhs: RigidBodyTransform<From, To>) -> Self::Output {
1294 Vector::from_nalgebra_vector(rhs.inner.inverse_transform_vector(&self.inner))
1295 }
1296}
1297
1298impl<From, To> Mul<Vector<To>> for RigidBodyTransform<From, To> {
1299 type Output = Vector<From>;
1300
1301 fn mul(self, rhs: Vector<To>) -> Self::Output {
1302 Vector::from_nalgebra_vector(self.inner.transform_vector(&rhs.inner))
1303 }
1304}
1305
1306// RigidBodyTransform<From, To> * Bearing<To> -> Bearing<From>
1307impl<From, To> Mul<Bearing<To>> for RigidBodyTransform<From, To>
1308where
1309 From: crate::systems::BearingDefined,
1310 To: crate::systems::BearingDefined,
1311{
1312 type Output = Bearing<From>;
1313
1314 fn mul(self, rhs: Bearing<To>) -> Self::Output {
1315 (self * rhs.to_unit_vector())
1316 .bearing_at_origin()
1317 .expect("magnitude should still be 1 after rotation")
1318 }
1319}
1320
1321// Bearing<From> * RigidBodyTransform<From, To> -> Bearing<To>
1322impl<From, To> Mul<RigidBodyTransform<From, To>> for Bearing<From>
1323where
1324 From: crate::systems::BearingDefined,
1325 To: crate::systems::BearingDefined,
1326{
1327 type Output = Bearing<To>;
1328
1329 fn mul(self, rhs: RigidBodyTransform<From, To>) -> Self::Output {
1330 (self.to_unit_vector() * rhs)
1331 .bearing_at_origin()
1332 .expect("magnitude should still be 1 after rotation")
1333 }
1334}
1335
1336// RigidBodyTransform<From, Over> * RigidBodyTransform<Over, To> -> RigidBodyTransform<From, To>
1337//
1338// like for Rotation, a RigidBodyTransform is a matrix multiply. the same ordering of the operands
1339// should hold for RigidBodyTransform as did for Rotation to end up with the columns and rows
1340// adding up, so we maintain the order used there.
1341impl<From, Over, To> Mul<RigidBodyTransform<Over, To>> for RigidBodyTransform<From, Over> {
1342 type Output = RigidBodyTransform<From, To>;
1343
1344 fn mul(self, rhs: RigidBodyTransform<Over, To>) -> Self::Output {
1345 Self::Output {
1346 inner: self.inner * rhs.inner,
1347 from: PhantomData::<From>,
1348 to: PhantomData::<To>,
1349 }
1350 }
1351}
1352
1353// RigidBodyTransform<From, Over> * Rotation<Over, To> -> RigidBodyTransform<From, To>
1354//
1355// here, too, the same ordering of the operands to the matrix multiply hold
1356impl<From, Over, To> Mul<Rotation<Over, To>> for RigidBodyTransform<From, Over> {
1357 type Output = RigidBodyTransform<From, To>;
1358
1359 fn mul(self, rhs: Rotation<Over, To>) -> Self::Output {
1360 Self::Output {
1361 inner: self.inner * rhs.inner,
1362 from: PhantomData::<From>,
1363 to: PhantomData::<To>,
1364 }
1365 }
1366}
1367
1368#[cfg(any(test, feature = "approx"))]
1369impl<From, To> AbsDiffEq<Self> for RigidBodyTransform<From, To> {
1370 type Epsilon = <f64 as AbsDiffEq>::Epsilon;
1371
1372 fn default_epsilon() -> Self::Epsilon {
1373 Isometry3::default_epsilon()
1374 }
1375
1376 fn abs_diff_eq(&self, other: &Self, epsilon: Self::Epsilon) -> bool {
1377 self.inner.abs_diff_eq(&other.inner, epsilon)
1378 }
1379}
1380
1381#[cfg(any(test, feature = "approx"))]
1382impl<From, To> RelativeEq for RigidBodyTransform<From, To> {
1383 fn default_max_relative() -> Self::Epsilon {
1384 Isometry3::default_max_relative()
1385 }
1386
1387 fn relative_eq(
1388 &self,
1389 other: &Self,
1390 epsilon: Self::Epsilon,
1391 max_relative: Self::Epsilon,
1392 ) -> bool {
1393 self.inner.relative_eq(&other.inner, epsilon, max_relative)
1394 }
1395}
1396
1397/// Unified builder for constructing both [`Rotation`] and [`engineering::Orientation`] from Tait-Bryan angles.
1398///
1399/// This builder enforces the intrinsic Tait-Bryan angle order (yaw → pitch → roll) at compile time
1400/// while providing named parameters to prevent argument order confusion.
1401///
1402/// The builder uses type states to ensure angles are set in the correct order and can construct
1403/// either a [`Rotation`] (with `unsafe`) or an [`engineering::Orientation`] (safe).
1404pub mod tait_bryan_builder {
1405 use super::*;
1406 use crate::engineering::Orientation;
1407 use std::marker::PhantomData;
1408 use uom::si::f64::Angle;
1409 use uom::ConstZero;
1410
1411 /// State marker indicating yaw angle is needed next
1412 pub struct NeedsYaw;
1413
1414 /// State marker indicating pitch angle is needed next
1415 pub struct NeedsPitch;
1416
1417 /// State marker indicating roll angle is needed next
1418 pub struct NeedsRoll;
1419
1420 /// State marker indicating all angles are set and ready to build
1421 pub struct Complete;
1422
1423 /// Unified builder for Tait-Bryan angle construction with compile-time ordering enforcement.
1424 ///
1425 /// This builder ensures that Tait-Bryan angles are provided in the correct intrinsic order:
1426 /// yaw (rotation about Z), then pitch (rotation about Y'), then roll (rotation about X'').
1427 ///
1428 /// The builder can construct either [`engineering::Orientation`] or [`Rotation`] depending
1429 /// on the target type parameter.
1430 pub struct TaitBryanBuilder<State, Target> {
1431 yaw: Angle,
1432 pitch: Angle,
1433 roll: Angle,
1434 _state: PhantomData<State>,
1435 _target: PhantomData<fn() -> Target>,
1436 }
1437
1438 // Manual implementations to avoid requiring derives on State and Target types
1439 impl<State, Target> Clone for TaitBryanBuilder<State, Target> {
1440 fn clone(&self) -> Self {
1441 *self
1442 }
1443 }
1444
1445 impl<State, Target> Copy for TaitBryanBuilder<State, Target> {}
1446
1447 impl<Target> std::fmt::Debug for TaitBryanBuilder<NeedsYaw, Target> {
1448 fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
1449 f.debug_struct("TaitBryanBuilder<NeedsYaw>").finish()
1450 }
1451 }
1452
1453 impl<Target> std::fmt::Debug for TaitBryanBuilder<NeedsPitch, Target> {
1454 fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
1455 f.debug_struct("TaitBryanBuilder<NeedsPitch>")
1456 .field("yaw", &self.yaw)
1457 .finish()
1458 }
1459 }
1460
1461 impl<Target> std::fmt::Debug for TaitBryanBuilder<NeedsRoll, Target> {
1462 fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
1463 f.debug_struct("TaitBryanBuilder<NeedsRoll>")
1464 .field("yaw", &self.yaw)
1465 .field("pitch", &self.pitch)
1466 .finish()
1467 }
1468 }
1469
1470 impl<Target> std::fmt::Debug for TaitBryanBuilder<Complete, Target> {
1471 fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
1472 f.debug_struct("TaitBryanBuilder<Complete>")
1473 .field("yaw", &self.yaw)
1474 .field("pitch", &self.pitch)
1475 .field("roll", &self.roll)
1476 .finish()
1477 }
1478 }
1479
1480 // State transition methods - these work for any target type
1481 impl<Target> TaitBryanBuilder<NeedsYaw, Target> {
1482 /// Creates a new builder needing a yaw angle.
1483 pub(crate) fn new() -> Self {
1484 Self {
1485 yaw: Angle::ZERO,
1486 pitch: Angle::ZERO,
1487 roll: Angle::ZERO,
1488 _state: PhantomData,
1489 _target: PhantomData,
1490 }
1491 }
1492
1493 /// Sets the yaw angle (rotation about Z axis).
1494 ///
1495 /// In most coordinate systems, positive yaw rotates clockwise when viewed from above.
1496 /// The exact meaning depends on the specific coordinate system being used.
1497 pub fn yaw(mut self, angle: impl Into<Angle>) -> TaitBryanBuilder<NeedsPitch, Target> {
1498 self.yaw = angle.into();
1499 TaitBryanBuilder {
1500 yaw: self.yaw,
1501 pitch: self.pitch,
1502 roll: self.roll,
1503 _state: PhantomData,
1504 _target: PhantomData,
1505 }
1506 }
1507 }
1508
1509 impl<Target> TaitBryanBuilder<NeedsPitch, Target> {
1510 /// Sets the pitch angle (rotation about Y' axis after yaw is applied).
1511 ///
1512 /// In most coordinate systems, positive pitch rotates the nose up.
1513 /// This is an intrinsic rotation applied after the yaw rotation.
1514 pub fn pitch(mut self, angle: impl Into<Angle>) -> TaitBryanBuilder<NeedsRoll, Target> {
1515 self.pitch = angle.into();
1516 TaitBryanBuilder {
1517 yaw: self.yaw,
1518 pitch: self.pitch,
1519 roll: self.roll,
1520 _state: PhantomData,
1521 _target: PhantomData,
1522 }
1523 }
1524 }
1525
1526 impl<Target> TaitBryanBuilder<NeedsRoll, Target> {
1527 /// Sets the roll angle (rotation about X'' axis after yaw and pitch are applied).
1528 ///
1529 /// In most coordinate systems, positive roll rotates clockwise about the forward axis.
1530 /// This is an intrinsic rotation applied after both yaw and pitch rotations.
1531 pub fn roll(mut self, angle: impl Into<Angle>) -> TaitBryanBuilder<Complete, Target> {
1532 self.roll = angle.into();
1533 TaitBryanBuilder {
1534 yaw: self.yaw,
1535 pitch: self.pitch,
1536 roll: self.roll,
1537 _state: PhantomData,
1538 _target: PhantomData,
1539 }
1540 }
1541 }
1542
1543 // Specialized build methods for each target type
1544 impl<In> TaitBryanBuilder<Complete, Orientation<In>> {
1545 /// Builds an [`engineering::Orientation`] from the provided Tait-Bryan angles.
1546 pub fn build(self) -> Orientation<In> {
1547 #[allow(deprecated)]
1548 Orientation::from_tait_bryan_angles(self.yaw, self.pitch, self.roll)
1549 }
1550 }
1551
1552 impl<From, To> TaitBryanBuilder<Complete, Rotation<From, To>> {
1553 /// Builds a [`Rotation`] from the provided Tait-Bryan angles.
1554 ///
1555 /// # Safety
1556 ///
1557 /// This is `unsafe` because you are asserting a relationship between the coordinate
1558 /// systems `From` and `To`. The constructed rotation will allow type-safe conversion
1559 /// between these coordinate systems, so this assertion must be correct.
1560 ///
1561 /// Specifically, you are asserting that applying the yaw, pitch, and roll rotations
1562 /// (in that intrinsic order) to the axes of coordinate system `From` will align them
1563 /// with the axes of coordinate system `To`.
1564 pub unsafe fn build(self) -> Rotation<From, To> {
1565 #[allow(deprecated)]
1566 Rotation::from_tait_bryan_angles(self.yaw, self.pitch, self.roll)
1567 }
1568 }
1569}
1570
1571#[cfg(test)]
1572mod tests {
1573 use crate::builder::bearing::Components;
1574 use crate::coordinate_systems::{Ecef, Enu, Frd, Ned};
1575 use crate::coordinates::Coordinate;
1576 use crate::geodetic::Wgs84;
1577 use crate::math::{RigidBodyTransform, Rotation};
1578 use crate::util::BoundedAngle;
1579 use crate::vectors::Vector;
1580 use crate::{coordinate, Point3};
1581 use crate::{system, Bearing};
1582 use crate::{vector, Vector3};
1583 use approx::assert_abs_diff_eq;
1584 use approx::assert_relative_eq;
1585 use rstest::rstest;
1586 use uom::si::f64::{Angle, Length};
1587 use uom::si::{angle::degree, length::meter};
1588
1589 fn m(meters: f64) -> Length {
1590 Length::new::<meter>(meters)
1591 }
1592 fn d(degrees: f64) -> Angle {
1593 Angle::new::<degree>(degrees)
1594 }
1595
1596 system!(struct PlaneFrd using FRD);
1597 system!(struct PlaneNed using NED);
1598 system!(struct PlaneEnu using ENU);
1599 system!(struct PlaneBNed using NED);
1600 system!(struct SensorFrd using FRD);
1601 system!(struct EmitterFrd using FRD);
1602
1603 #[rstest]
1604 // Given as coordinates System A -> Orientation of B in A -> System B
1605 // Yaw only
1606 #[case(
1607 Point3::new(1., 0., 0.),
1608 (d(0.), d(0.), d(0.)),
1609 Point3::new(1., 0., 0.)
1610 )]
1611 #[case(
1612 Point3::new(1., 0., 0.),
1613 (d(90.), d(0.), d(0.)),
1614 Point3::new(0., -1., 0.)
1615 )]
1616 #[case(
1617 Point3::new(1., 0., 0.),
1618 (d(180.), d(0.), d(0.)),
1619 Point3::new(-1., 0., 0.)
1620 )]
1621 #[case(
1622 Point3::new(1., 0., 0.),
1623 (d(270.), d(0.), d(0.)),
1624 Point3::new(0., 1., 0.)
1625 )]
1626 #[case(
1627 Point3::new(1., 0., 0.),
1628 (d(360.), d(0.), d(0.)),
1629 Point3::new(1., 0., 0.)
1630 )]
1631 // Pitch only
1632 #[case(
1633 Point3::new(1., 0., 0.),
1634 (d(0.), d(90.), d(0.)),
1635 Point3::new(0., 0., 1.)
1636 )]
1637 #[case(
1638 Point3::new(1., 0., 0.),
1639 (d(0.), d(180.), d(0.)),
1640 Point3::new(-1., 0., 0.)
1641 )]
1642 #[case(
1643 Point3::new(1., 0., 0.),
1644 (d(0.), d(270.), d(0.)),
1645 Point3::new(0., 0., -1.)
1646 )]
1647 #[case(
1648 Point3::new(1., 0., 0.),
1649 (d(0.), d(360.), d(0.)),
1650 Point3::new(1., 0., 0.)
1651 )]
1652 // Roll only
1653 #[case( // No effect on x-axis
1654 Point3::new(1., 0., 0.),
1655 (d(0.), d(0.), d(69.)),
1656 Point3::new(1., 0., 0.)
1657 )]
1658 #[case(
1659 Point3::new(0., 1., 0.),
1660 (d(0.), d(0.), d(90.)),
1661 Point3::new(0., 0., -1.)
1662 )]
1663 #[case(
1664 Point3::new(0., 1., 0.),
1665 (d(0.), d(0.), d(180.)),
1666 Point3::new(0., -1., 0.)
1667 )]
1668 #[case(
1669 Point3::new(0., 1., 0.),
1670 (d(0.), d(0.), d(270.)),
1671 Point3::new(0., 0., 1.)
1672 )]
1673 #[case(
1674 Point3::new(0., 1., 0.),
1675 (d(0.), d(0.), d(360.)),
1676 Point3::new(0., 1., 0.)
1677 )]
1678 // Rotate pitch and yaw
1679 // Front axis now points left
1680 #[case(
1681 Point3::new(1., 0., 0.),
1682 (d(90.), d(180.), d(0.)),
1683 Point3::new(0., -1., 0.)
1684 )]
1685 // Right axis now points backwards
1686 #[case(
1687 Point3::new(0., 1., 0.),
1688 (d(90.), d(180.), d(0.)),
1689 Point3::new(-1., 0., 0.)
1690 )]
1691 // Downward axis now points up
1692 #[case(
1693 Point3::new(0., 0., 1.),
1694 (d(90.), d(180.), d(0.)),
1695 Point3::new(0., 0., -1.)
1696 )]
1697 // front-axis is now to the right and 45 degrees up
1698 #[case(
1699 Point3::new(0., 10., 0.),
1700 (d(90.), d(45.), d(0.)),
1701 Point3::new(7.0710678118654755, 0., 7.071067811865475)
1702 )]
1703 // front-axis is now to the right and 45 degrees up
1704 #[case(
1705 Point3::new(10., 0., 0.),
1706 (d(90.), d(45.), d(0.)),
1707 Point3::new(0., -10., 0.)
1708 )]
1709 // Rotate all three axis
1710 #[case(
1711 Point3::new(- 0.00028087357950656866, 10.000385238610235, - 2.2283317053339857e-5),
1712 (d(39.), d(45.), d(55.)),
1713 Point3::new(4.450, 8.103, - 3.814)
1714 )]
1715 /// Test that we can transform a coordinate in FRD system A to the equivalent coordinate in FRD system B, given the orientation of B in A.
1716 fn earth_bound_and_frd_coordinate_transforms_work(
1717 #[case] point_in_a: Point3,
1718 #[case] ypr: (Angle, Angle, Angle),
1719 #[case] point_in_b: Point3,
1720 ) {
1721 let (yaw, pitch, roll) = ypr;
1722 let frd_orientation = unsafe {
1723 Rotation::<SensorFrd, EmitterFrd>::tait_bryan_builder()
1724 .yaw(yaw)
1725 .pitch(pitch)
1726 .roll(roll)
1727 .build()
1728 };
1729
1730 // Sanity-check that to_tait_bryan_angles does what we expect, but only if we're already
1731 // giving normalized input (otherwise the unit quaternion will do it for us and the
1732 // comparison will fail).
1733 if pitch <= d(90.) {
1734 let (y, p, r) = frd_orientation.to_tait_bryan_angles();
1735 for (a, b) in [(y, yaw), (p, pitch), (r, roll)] {
1736 assert_abs_diff_eq!(&BoundedAngle::new(a), &BoundedAngle::new(b));
1737 }
1738 }
1739
1740 // Orientation transform works between FRD coordinates
1741 let frd_a = Coordinate::<SensorFrd>::from_nalgebra_point(point_in_a);
1742 let frd_b = frd_orientation.transform(frd_a);
1743 let frd_a_again = frd_orientation.inverse_transform(frd_b);
1744 assert_relative_eq!(
1745 frd_b,
1746 Coordinate::<EmitterFrd>::from_nalgebra_point(point_in_b),
1747 );
1748 assert_relative_eq!(frd_a_again, frd_a);
1749
1750 let (yaw_converted, pitch_converted, roll_converted) = frd_orientation.euler_angles();
1751 let frd_orientation_converted = unsafe {
1752 Rotation::<SensorFrd, EmitterFrd>::tait_bryan_builder()
1753 .yaw(yaw_converted)
1754 .pitch(pitch_converted)
1755 .roll(roll_converted)
1756 .build()
1757 };
1758 assert_relative_eq!(frd_orientation, frd_orientation_converted);
1759
1760 // Orientation works between NED and FRD coordinates
1761 let ned_orientation = unsafe {
1762 Rotation::<Ned, Frd>::tait_bryan_builder()
1763 .yaw(yaw)
1764 .pitch(pitch)
1765 .roll(roll)
1766 .build()
1767 };
1768
1769 let ned = Coordinate::<Ned>::from_nalgebra_point(point_in_a);
1770 let frd = ned_orientation.transform(ned);
1771 let ned_again = ned_orientation.inverse_transform(frd);
1772 assert_relative_eq!(frd, Coordinate::<Frd>::from_nalgebra_point(point_in_b));
1773 assert_relative_eq!(ned_again, ned);
1774
1775 // Use the point in b as translation. Could be arbitrary point instead.
1776 let translation = Vector3::new(1., 0., 0.);
1777 // NED pose does the same thing but adds a translation
1778 let ned_pose = unsafe {
1779 RigidBodyTransform::<Ned, Frd>::new(
1780 Vector::from_nalgebra_vector(translation),
1781 ned_orientation,
1782 )
1783 };
1784
1785 let frd_after_pose = ned_pose.transform(ned);
1786 assert_relative_eq!(
1787 frd_after_pose,
1788 frd - ned_orientation.transform(Vector::<Ned>::from_nalgebra_vector(translation)),
1789 );
1790 // Check from FRD to NED
1791 let ned_again_after_pose = ned_pose.inverse_transform(frd_after_pose);
1792 assert_relative_eq!(ned, ned_again_after_pose);
1793
1794 // Check that orientation works between ENU and FRD coordinates. These work with the
1795 // same test cases because Rotation::<Ned, Frd> and Rotation::<Enu, Frd> build the
1796 // same quaternions.
1797 let enu_orientation = unsafe {
1798 Rotation::<Enu, Frd>::tait_bryan_builder()
1799 .yaw(yaw)
1800 .pitch(pitch)
1801 .roll(roll)
1802 .build()
1803 };
1804
1805 let enu = Coordinate::<Enu>::from_nalgebra_point(point_in_a);
1806 let frd = enu_orientation.transform(enu);
1807 let enu_again = enu_orientation.inverse_transform(frd);
1808 assert_relative_eq!(frd, Coordinate::<Frd>::from_nalgebra_point(point_in_b));
1809 assert_relative_eq!(enu_again, enu);
1810
1811 // Use the point in b as translation. Could be arbitrary point instead.
1812 let translation = Vector3::new(1., 0., 0.);
1813 // ENU pose does the same thing but adds a translation
1814 let enu_pose = unsafe {
1815 RigidBodyTransform::<Enu, Frd>::new(
1816 Vector::from_nalgebra_vector(translation),
1817 enu_orientation,
1818 )
1819 };
1820
1821 let frd_after_pose = enu_pose.transform(enu);
1822 assert_relative_eq!(
1823 frd_after_pose,
1824 frd - enu_orientation.transform(Vector::<Enu>::from_nalgebra_vector(translation)),
1825 );
1826 // Check from FRD to ENU
1827 let enu_again_after_pose = enu_pose.inverse_transform(frd_after_pose);
1828 assert_relative_eq!(enu, enu_again_after_pose)
1829 }
1830
1831 #[test]
1832 fn orientation_multiplication_works() {
1833 // Transforms a NED to an FRD coordinate of an object with this yaw, pitch, roll.
1834 let ned_to_frd = unsafe {
1835 Rotation::<PlaneNed, PlaneFrd>::tait_bryan_builder()
1836 .yaw(d(90.))
1837 .pitch(d(90.))
1838 .roll(d(0.))
1839 .build()
1840 };
1841
1842 // Transforms a ECEF coordinate to a NED coordinate for a NED at a particular latitude and longitude.
1843 let ecef_to_ned = unsafe { Rotation::<Ecef, PlaneNed>::ecef_to_ned_at(d(52.), d(-3.)) };
1844
1845 // Chains both transformations to transform a ECEF coordinate to a Frd Coordinate via NED.
1846 let ecef_to_frd = ecef_to_ned * ned_to_frd;
1847
1848 let forward = coordinate!(f = m(1.), r = m(0.), d = m(0.); in PlaneFrd);
1849 let right = coordinate!(f = m(0.), r = m(1.), d = m(0.); in PlaneFrd);
1850 let down = coordinate!(f = m(0.), r = m(0.), d = m(1.); in PlaneFrd);
1851
1852 // check that the FRD axis are at the right spots in NED.
1853 let forward_in_ned = ned_to_frd.inverse_transform(forward);
1854 let right_in_ned = ned_to_frd.inverse_transform(right);
1855 let down_in_ned = ned_to_frd.inverse_transform(down);
1856
1857 assert_relative_eq!(
1858 forward_in_ned,
1859 -coordinate!(n = m(0.), e = m(0.), d = m(1.))
1860 );
1861 assert_relative_eq!(right_in_ned, -coordinate!(n = m(1.), e = m(0.), d = m(0.)));
1862 assert_relative_eq!(down_in_ned, coordinate!(n = m(0.), e = m(1.), d = m(0.)));
1863
1864 // Turn the NED to ECEF
1865 let forward_in_ecef = ecef_to_ned.inverse_transform(forward_in_ned);
1866 let right_in_ecef = ecef_to_ned.inverse_transform(right_in_ned);
1867 let down_in_ecef = ecef_to_ned.inverse_transform(down_in_ned);
1868
1869 // check that the inverse works
1870 let frd_to_ecef = ecef_to_frd.inverse();
1871
1872 // Check that the chain did the same.
1873 assert_relative_eq!(forward_in_ecef, ecef_to_frd.inverse_transform(forward));
1874 assert_relative_eq!(
1875 frd_to_ecef.transform(forward),
1876 ecef_to_frd.inverse_transform(forward)
1877 );
1878
1879 assert_relative_eq!(right_in_ecef, ecef_to_frd.inverse_transform(right));
1880 assert_relative_eq!(
1881 frd_to_ecef.transform(right),
1882 ecef_to_frd.inverse_transform(right)
1883 );
1884
1885 assert_relative_eq!(down_in_ecef, ecef_to_frd.inverse_transform(down));
1886 assert_relative_eq!(
1887 frd_to_ecef.transform(down),
1888 ecef_to_frd.inverse_transform(down)
1889 );
1890
1891 // Now test if we can go to another FRD
1892
1893 // Pose of a second frd in another ned
1894 let ned_to_frd_2 = unsafe {
1895 Rotation::<PlaneBNed, SensorFrd>::tait_bryan_builder()
1896 .yaw(d(-45.))
1897 .pitch(d(0.))
1898 .roll(d(0.))
1899 .build()
1900 };
1901 // NED of the other FRDs object
1902 let ecef_to_ned_2 =
1903 unsafe { Rotation::<Ecef, PlaneBNed>::ecef_to_ned_at(d(54.), d(-3.67)) };
1904
1905 let ecef_to_frd_2 = ecef_to_ned_2 * ned_to_frd_2;
1906
1907 // What is the orientation of 2 in 1?
1908 let frd_1_to_frd_2 = ecef_to_frd.inverse() * ecef_to_frd_2;
1909
1910 // Manually do the transforms
1911 let forward_in_ned_2 = ecef_to_ned_2.transform(forward_in_ecef);
1912 let right_in_ned_2 = ecef_to_ned_2.transform(right_in_ecef);
1913 let down_in_ned_2 = ecef_to_ned_2.transform(down_in_ecef);
1914
1915 let forward_in_frd_2 = ned_to_frd_2.transform(forward_in_ned_2);
1916 let right_in_frd_2 = ned_to_frd_2.transform(right_in_ned_2);
1917 let down_in_frd_2 = ned_to_frd_2.transform(down_in_ned_2);
1918
1919 let forward_chained = frd_1_to_frd_2.transform(forward);
1920 let right_chained = frd_1_to_frd_2.transform(right);
1921 let down_chained = frd_1_to_frd_2.transform(down);
1922
1923 // Now check if the chained transform did the same thing.
1924 assert_relative_eq!(forward_in_frd_2, forward_chained);
1925 assert_relative_eq!(right_in_frd_2, right_chained);
1926 assert_relative_eq!(down_in_frd_2, down_chained);
1927 }
1928
1929 impl From<&nav_types::ECEF<f64>> for Coordinate<Ecef> {
1930 fn from(value: &nav_types::ECEF<f64>) -> Self {
1931 coordinate!(x = m(value.x()), y = m(value.y()), z = m(value.z()))
1932 }
1933 }
1934
1935 #[rstest]
1936 #[case(d(47.9948211), d(7.8211606), m(1000.))]
1937 #[case(d(67.112282), d(19.880389), m(0.))]
1938 #[case(d(84.883074), d(-29.160550), m(2000.))]
1939 #[case(d(-27.270950), d(143.722880), m(100.))]
1940 fn orientation_ecef_to_ned_construction(
1941 #[case] lat: Angle,
1942 #[case] long: Angle,
1943 #[case] alt: Length,
1944 ) {
1945 // This test uses nav_types to check if the computations match.
1946
1947 let ecef_to_ned = unsafe { Rotation::<Ecef, PlaneNed>::ecef_to_ned_at(lat, long) };
1948
1949 let location = nav_types::WGS84::from_degrees_and_meters(
1950 lat.get::<degree>(),
1951 long.get::<degree>(),
1952 alt.get::<meter>(),
1953 );
1954 let location_ecef = nav_types::ECEF::from(location);
1955
1956 let north = nav_types::NED::new(1., 0., 0.);
1957 let east = nav_types::NED::new(0., 1., 0.);
1958 let down = nav_types::NED::new(0., 0., 1.);
1959 let origin = nav_types::NED::new(0., 0., 0.);
1960
1961 // Get the axis points of the NED local in ECEF using nav_types.
1962 let ned_origin_in_ecef = location_ecef + origin;
1963 let ned_origin_in_ecef = Coordinate::<Ecef>::from(&ned_origin_in_ecef);
1964
1965 let ned_north_in_ecef = location_ecef + north;
1966 let ned_north_in_ecef = Coordinate::<Ecef>::from(&ned_north_in_ecef);
1967
1968 let ned_east_in_ecef = location_ecef + east;
1969 let ned_east_in_ecef = Coordinate::<Ecef>::from(&ned_east_in_ecef);
1970
1971 let ned_down_in_ecef = location_ecef + down;
1972 let ned_down_in_ecef = Coordinate::<Ecef>::from(&ned_down_in_ecef);
1973
1974 // The orientation part does not perform the translation from earth center to NED origin.
1975 // Nav_types does. This is why we subtract the NED origin for testing the orientation.
1976
1977 let result_origin = ecef_to_ned.inverse_transform(Coordinate::<PlaneNed>::origin());
1978 // The origin is not changed because this is only the orientation, not pose.
1979 // Ie. there is no translation between ECEF and PlaneNed. The plane is at the center of the earth on this test.
1980 assert_relative_eq!(Coordinate::<Ecef>::origin(), result_origin);
1981 assert_relative_eq!(
1982 ecef_to_ned.transform(Coordinate::<Ecef>::origin()),
1983 Coordinate::<PlaneNed>::origin()
1984 );
1985
1986 let point_on_north =
1987 Coordinate::<PlaneNed>::origin() + Vector::<PlaneNed>::ned_north_axis();
1988 let result_north = ecef_to_ned.inverse_transform(point_on_north);
1989 // nav_types does the NED at the correct position and not the center of the earth. We remove the translation here.
1990 let expected_north = ned_north_in_ecef - ned_origin_in_ecef;
1991 assert_relative_eq!(result_north, Coordinate::<Ecef>::origin() + expected_north);
1992
1993 let point_on_east = Coordinate::<PlaneNed>::origin() + Vector::<PlaneNed>::ned_east_axis();
1994 let result_east = ecef_to_ned.inverse_transform(point_on_east);
1995 // nav_types does the NED at the correct position and not the center of the earth. We remove the translation here.
1996 let expected_east = ned_east_in_ecef - ned_origin_in_ecef;
1997 assert_relative_eq!(result_east, Coordinate::<Ecef>::origin() + expected_east);
1998
1999 let point_on_down = Coordinate::<PlaneNed>::origin() + Vector::<PlaneNed>::ned_down_axis();
2000 let result_down = ecef_to_ned.inverse_transform(point_on_down);
2001 // nav_types does the NED at the correct position and not the center of the earth. We remove the translation here.
2002 let expected_down = ned_down_in_ecef - ned_origin_in_ecef;
2003 assert_relative_eq!(result_down, Coordinate::<Ecef>::origin() + expected_down);
2004
2005 // Construct this as pose instead of just orientation.
2006 // This time the translation should be in there as well, so we can compare directly to nav_types output.
2007 let pose = unsafe {
2008 RigidBodyTransform::<Ecef, PlaneNed>::ecef_to_ned_at(
2009 &Wgs84::builder()
2010 .latitude(lat)
2011 .expect("latitude is in-range")
2012 .longitude(long)
2013 .altitude(alt)
2014 .build(),
2015 )
2016 };
2017
2018 let result_ned_north_in_ecef = pose.inverse_transform(point_on_north);
2019 assert_relative_eq!(result_ned_north_in_ecef, ned_north_in_ecef);
2020
2021 let result_ned_east_in_ecef = pose.inverse_transform(point_on_east);
2022 assert_relative_eq!(result_ned_east_in_ecef, ned_east_in_ecef);
2023
2024 let result_ned_down_in_ecef = pose.inverse_transform(point_on_down);
2025 assert_relative_eq!(result_ned_down_in_ecef, ned_down_in_ecef);
2026 }
2027
2028 #[test]
2029 fn pose_serde() {
2030 let pose = unsafe {
2031 RigidBodyTransform::new(
2032 vector!(n = m(50.), e = m(45.), d = m(10.)),
2033 Rotation::<PlaneNed, PlaneFrd>::tait_bryan_builder()
2034 .yaw(d(15.))
2035 .pitch(d(0.))
2036 .roll(d(1.))
2037 .build(),
2038 )
2039 };
2040
2041 let ser = serde_yaml::to_string(&pose).unwrap();
2042
2043 let de = serde_yaml::from_str::<RigidBodyTransform<PlaneNed, PlaneFrd>>(&ser).unwrap();
2044 assert_eq!(pose, de);
2045 }
2046
2047 #[test]
2048 fn bearing_rotation() {
2049 // assume forward is currently pointing east
2050 let ned_to_frd = unsafe {
2051 Rotation::<Ned, Frd>::tait_bryan_builder()
2052 .yaw(d(90.))
2053 .pitch(d(0.))
2054 .roll(d(0.))
2055 .build()
2056 };
2057
2058 // a bearing pointing East should have an azimuth of 0° to forward
2059 // and since the plane has no pitch relative to horizon, elevation shouldn't change
2060 assert_relative_eq!(
2061 Bearing::<Ned>::build(Components {
2062 azimuth: d(90.),
2063 elevation: d(45.)
2064 })
2065 .unwrap()
2066 * ned_to_frd,
2067 Bearing::<Frd>::build(Components {
2068 azimuth: d(0.),
2069 elevation: d(45.)
2070 })
2071 .unwrap()
2072 );
2073
2074 // a bearing pointing South should have an azimuth of 90° to forward
2075 // elevation still shouldn't change
2076 assert_relative_eq!(
2077 Bearing::<Ned>::build(Components {
2078 azimuth: d(180.),
2079 elevation: d(45.)
2080 })
2081 .unwrap()
2082 * ned_to_frd,
2083 Bearing::<Frd>::build(Components {
2084 azimuth: d(90.),
2085 elevation: d(45.)
2086 })
2087 .unwrap()
2088 );
2089
2090 // conversely, a bearing pointing Forward should have an azimuth of 90° to North
2091 assert_relative_eq!(
2092 ned_to_frd
2093 * Bearing::<Frd>::build(Components {
2094 azimuth: d(0.),
2095 elevation: d(45.)
2096 })
2097 .unwrap(),
2098 Bearing::<Ned>::build(Components {
2099 azimuth: d(90.),
2100 elevation: d(45.)
2101 })
2102 .unwrap()
2103 );
2104
2105 // and one pointing backwards should have an azimuth of -90° to North
2106 assert_relative_eq!(
2107 ned_to_frd
2108 * Bearing::<Frd>::build(Components {
2109 azimuth: d(180.),
2110 elevation: d(45.)
2111 })
2112 .unwrap(),
2113 Bearing::<Ned>::build(Components {
2114 azimuth: d(-90.),
2115 elevation: d(45.)
2116 })
2117 .unwrap()
2118 );
2119
2120 // if the plane is pitched, elevation _does_ change
2121 // (we'll keep yaw 0° for now)
2122 let ned_to_frd = unsafe {
2123 Rotation::<Ned, Frd>::tait_bryan_builder()
2124 .yaw(d(0.))
2125 .pitch(d(45.))
2126 .roll(d(0.))
2127 .build()
2128 };
2129
2130 // along the horizon should be seen as -45° compared to FR-plane
2131 assert_relative_eq!(
2132 Bearing::<Ned>::build(Components {
2133 azimuth: d(0.),
2134 elevation: d(0.)
2135 })
2136 .unwrap()
2137 * ned_to_frd,
2138 Bearing::<Frd>::build(Components {
2139 azimuth: d(0.),
2140 elevation: d(-45.)
2141 })
2142 .unwrap()
2143 );
2144
2145 // 45° to the horizon should be parallel to FR-plane
2146 assert_relative_eq!(
2147 Bearing::<Ned>::build(Components {
2148 azimuth: d(0.),
2149 elevation: d(45.)
2150 })
2151 .unwrap()
2152 * ned_to_frd,
2153 Bearing::<Frd>::build(Components {
2154 azimuth: d(0.),
2155 elevation: d(0.)
2156 })
2157 .unwrap()
2158 );
2159
2160 // and vice-versa
2161 assert_relative_eq!(
2162 ned_to_frd
2163 * Bearing::<Frd>::build(Components {
2164 azimuth: d(0.),
2165 elevation: d(-45.)
2166 })
2167 .unwrap(),
2168 Bearing::<Ned>::build(Components {
2169 azimuth: d(0.),
2170 elevation: d(0.)
2171 })
2172 .unwrap()
2173 );
2174 assert_relative_eq!(
2175 ned_to_frd
2176 * Bearing::<Frd>::build(Components {
2177 azimuth: d(0.),
2178 elevation: d(0.)
2179 })
2180 .unwrap(),
2181 Bearing::<Ned>::build(Components {
2182 azimuth: d(0.),
2183 elevation: d(45.)
2184 })
2185 .unwrap()
2186 );
2187
2188 // since rotations are intrinsic, things get weird with yaw/azimuth _plus_ elevation
2189 // in particular, if the plane is pitched up at a yaw, or is pitched but has an observation
2190 // at a given azimuth, the resulting FRD observations aren't trivial to compute as bearing
2191 // relative to NED. one that's "easy" for humans to think about is if the yaw is 180, since
2192 // it just "flips" the azimuth and predictably changes the elevation, so that's what we'll
2193 // use in these tests. we'll continue with no roll.
2194 let ned_to_frd = unsafe {
2195 Rotation::<Ned, Frd>::tait_bryan_builder()
2196 .yaw(d(180.)) // pointed South
2197 .pitch(d(45.)) // FRD "up" 0 is NED "up" 45
2198 .roll(d(0.))
2199 .build()
2200 };
2201
2202 // sanity-check: directly in front should match orientation of plane
2203 assert_relative_eq!(
2204 ned_to_frd
2205 * Bearing::<Frd>::build(Components {
2206 azimuth: d(0.),
2207 elevation: d(0.)
2208 })
2209 .unwrap(),
2210 Bearing::<Ned>::build(Components {
2211 azimuth: d(180.),
2212 elevation: d(45.)
2213 })
2214 .unwrap()
2215 );
2216 // directly behind should be North and "flip" pitch
2217 assert_relative_eq!(
2218 ned_to_frd
2219 * Bearing::<Frd>::build(Components {
2220 azimuth: d(180.),
2221 elevation: d(0.)
2222 })
2223 .unwrap(),
2224 Bearing::<Ned>::build(Components {
2225 azimuth: d(0.),
2226 elevation: d(-45.)
2227 })
2228 .unwrap()
2229 );
2230 // and vice-versa
2231 assert_relative_eq!(
2232 Bearing::<Ned>::build(Components {
2233 azimuth: d(180.),
2234 elevation: d(45.)
2235 })
2236 .unwrap()
2237 * ned_to_frd,
2238 Bearing::<Frd>::build(Components {
2239 azimuth: d(0.),
2240 elevation: d(0.)
2241 })
2242 .unwrap()
2243 );
2244 assert_relative_eq!(
2245 Bearing::<Ned>::build(Components {
2246 azimuth: d(0.),
2247 elevation: d(-45.)
2248 })
2249 .unwrap()
2250 * ned_to_frd,
2251 Bearing::<Frd>::build(Components {
2252 azimuth: d(180.),
2253 elevation: d(0.)
2254 })
2255 .unwrap()
2256 );
2257
2258 // an observation to the left with zero elevation should be East
2259 // and should _also_ have zero elevation
2260 assert_relative_eq!(
2261 ned_to_frd
2262 * Bearing::<Frd>::build(Components {
2263 azimuth: d(-90.),
2264 elevation: d(0.)
2265 })
2266 .unwrap(),
2267 Bearing::<Ned>::build(Components {
2268 azimuth: d(90.),
2269 elevation: d(0.)
2270 })
2271 .unwrap()
2272 );
2273 assert_relative_eq!(
2274 Bearing::<Ned>::build(Components {
2275 azimuth: d(90.),
2276 elevation: d(0.)
2277 })
2278 .unwrap()
2279 * ned_to_frd,
2280 Bearing::<Frd>::build(Components {
2281 azimuth: d(-90.),
2282 elevation: d(0.)
2283 })
2284 .unwrap()
2285 );
2286
2287 // an observation directly below us should have our pitch but flipped, and should have an
2288 // azimuth of _South_ since it's _not_ aligned with NED's Z axis (which would make it get
2289 // set to 0).
2290 assert_relative_eq!(
2291 ned_to_frd
2292 * Bearing::<Frd>::build(Components {
2293 azimuth: d(0.),
2294 elevation: d(-90.)
2295 })
2296 .unwrap(),
2297 Bearing::<Ned>::build(Components {
2298 azimuth: d(180.),
2299 elevation: d(-45.)
2300 })
2301 .unwrap()
2302 );
2303 // and vice-versa
2304 // although here we have to be forgiving with the azimuth because we end up with a bearing
2305 // that points straight down (-90°) in FRD, in which case the azimuth is unpredictable.
2306 assert_relative_eq!(
2307 BoundedAngle::new(
2308 (Bearing::<Ned>::build(Components {
2309 azimuth: d(180.),
2310 elevation: d(-45.)
2311 })
2312 .unwrap()
2313 * ned_to_frd)
2314 .elevation()
2315 ),
2316 BoundedAngle::new(d(-90.))
2317 );
2318
2319 // now the same with roll
2320 // this too makes computing what's expected tricky for the human brain. so, we pick a roll
2321 // of 180° which essentially just flips elevation _and_ azimuth in this configuration.
2322 let ned_to_frd = unsafe {
2323 Rotation::<Ned, Frd>::tait_bryan_builder()
2324 .yaw(d(180.)) // pointed South
2325 .pitch(d(45.)) // FRD "up" 0 is NED "up" 45
2326 .roll(d(180.)) // upside-down
2327 .build()
2328 };
2329
2330 // directly in front should still match orientation of plane
2331 assert_relative_eq!(
2332 ned_to_frd
2333 * Bearing::<Frd>::build(Components {
2334 azimuth: d(0.),
2335 elevation: d(0.)
2336 })
2337 .unwrap(),
2338 Bearing::<Ned>::build(Components {
2339 azimuth: d(180.),
2340 elevation: d(45.)
2341 })
2342 .unwrap()
2343 );
2344 // directly behind should still be North and "flip" pitch
2345 assert_relative_eq!(
2346 ned_to_frd
2347 * Bearing::<Frd>::build(Components {
2348 azimuth: d(180.),
2349 elevation: d(0.)
2350 })
2351 .unwrap(),
2352 Bearing::<Ned>::build(Components {
2353 azimuth: d(0.),
2354 elevation: d(-45.)
2355 })
2356 .unwrap()
2357 );
2358 // and vice-versa
2359 assert_relative_eq!(
2360 Bearing::<Ned>::build(Components {
2361 azimuth: d(180.),
2362 elevation: d(45.)
2363 })
2364 .unwrap()
2365 * ned_to_frd,
2366 Bearing::<Frd>::build(Components {
2367 azimuth: d(0.),
2368 elevation: d(0.)
2369 })
2370 .unwrap()
2371 );
2372 assert_relative_eq!(
2373 Bearing::<Ned>::build(Components {
2374 azimuth: d(0.),
2375 elevation: d(-45.)
2376 })
2377 .unwrap()
2378 * ned_to_frd,
2379 Bearing::<Frd>::build(Components {
2380 azimuth: d(180.),
2381 elevation: d(0.)
2382 })
2383 .unwrap()
2384 );
2385
2386 // an observation to the left with zero elevation should now be West
2387 // and should _also_ have zero elevation
2388 assert_relative_eq!(
2389 ned_to_frd
2390 * Bearing::<Frd>::build(Components {
2391 azimuth: d(-90.),
2392 elevation: d(0.)
2393 })
2394 .unwrap(),
2395 Bearing::<Ned>::build(Components {
2396 azimuth: d(-90.),
2397 elevation: d(0.)
2398 })
2399 .unwrap()
2400 );
2401 assert_relative_eq!(
2402 Bearing::<Ned>::build(Components {
2403 azimuth: d(-90.),
2404 elevation: d(0.)
2405 })
2406 .unwrap()
2407 * ned_to_frd,
2408 Bearing::<Frd>::build(Components {
2409 azimuth: d(-90.),
2410 elevation: d(0.)
2411 })
2412 .unwrap()
2413 );
2414
2415 // an observation directly below us now _actually_ points "up" by the same amount as our
2416 // pitch. it also has an azimuth that is flipped (ie, North not South) since the inverse of
2417 // the pitch crosses the XZ plane.
2418 assert_relative_eq!(
2419 ned_to_frd
2420 * Bearing::<Frd>::build(Components {
2421 azimuth: d(0.),
2422 elevation: d(-90.)
2423 })
2424 .unwrap(),
2425 Bearing::<Ned>::build(Components {
2426 azimuth: d(0.),
2427 elevation: d(45.)
2428 })
2429 .unwrap()
2430 );
2431 // and vice-versa, though again we have to be forgiving about azimuth
2432 assert_relative_eq!(
2433 BoundedAngle::new(
2434 (Bearing::<Ned>::build(Components {
2435 azimuth: d(0.),
2436 elevation: d(45.)
2437 })
2438 .unwrap()
2439 * ned_to_frd)
2440 .elevation()
2441 ),
2442 BoundedAngle::new(d(-90.))
2443 );
2444 }
2445
2446 #[rstest]
2447 #[case(d(47.9948211), d(7.8211606), m(1000.))]
2448 #[case(d(67.112282), d(19.880389), m(0.))]
2449 #[case(d(84.883074), d(-29.160550), m(2000.))]
2450 #[case(d(-27.270950), d(143.722880), m(100.))]
2451 fn orientation_ecef_to_enu_construction(
2452 #[case] lat: Angle,
2453 #[case] long: Angle,
2454 #[case] alt: Length,
2455 ) {
2456 // This test uses nav_types to check if the computations match.
2457
2458 let ecef_to_enu = unsafe { Rotation::<Ecef, PlaneEnu>::ecef_to_enu_at(lat, long) };
2459
2460 let location = nav_types::WGS84::from_degrees_and_meters(
2461 lat.get::<degree>(),
2462 long.get::<degree>(),
2463 alt.get::<meter>(),
2464 );
2465 let location_ecef = nav_types::ECEF::from(location);
2466
2467 let east = nav_types::ENU::new(1., 0., 0.);
2468 let north = nav_types::ENU::new(0., 1., 0.);
2469 let up = nav_types::ENU::new(0., 0., 1.);
2470 let origin = nav_types::ENU::new(0., 0., 0.);
2471
2472 // Get the axis points of the NED local in ECEF using nav_types.
2473 let enu_origin_in_ecef = location_ecef + origin;
2474 let enu_origin_in_ecef = Coordinate::<Ecef>::from(&enu_origin_in_ecef);
2475
2476 let enu_east_in_ecef = location_ecef + east;
2477 let enu_east_in_ecef = Coordinate::<Ecef>::from(&enu_east_in_ecef);
2478
2479 let enu_north_in_ecef = location_ecef + north;
2480 let enu_north_in_ecef = Coordinate::<Ecef>::from(&enu_north_in_ecef);
2481
2482 let enu_up_in_ecef = location_ecef + up;
2483 let enu_up_in_ecef = Coordinate::<Ecef>::from(&enu_up_in_ecef);
2484
2485 let result_origin = ecef_to_enu.inverse_transform(Coordinate::<PlaneEnu>::origin());
2486
2487 assert_relative_eq!(Coordinate::<Ecef>::origin(), result_origin);
2488 assert_relative_eq!(
2489 ecef_to_enu.transform(Coordinate::<Ecef>::origin()),
2490 Coordinate::<PlaneEnu>::origin()
2491 );
2492
2493 let point_on_east = Coordinate::<PlaneEnu>::origin() + Vector::<PlaneEnu>::enu_east_axis();
2494 let result_east = ecef_to_enu.inverse_transform(point_on_east);
2495 // nav_types does the ENU at the correct position and not the center of the earth. We remove the translation here.
2496 let expected_east = enu_east_in_ecef - enu_origin_in_ecef;
2497 assert_relative_eq!(result_east, Coordinate::<Ecef>::origin() + expected_east);
2498
2499 let point_on_north =
2500 Coordinate::<PlaneEnu>::origin() + Vector::<PlaneEnu>::enu_north_axis();
2501 let result_north = ecef_to_enu.inverse_transform(point_on_north);
2502 // nav_types does the ENU at the correct position and not the center of the earth. We remove the translation here.
2503 let expected_north = enu_north_in_ecef - enu_origin_in_ecef;
2504 assert_relative_eq!(result_north, Coordinate::<Ecef>::origin() + expected_north);
2505
2506 let point_on_up = Coordinate::<PlaneEnu>::origin() + Vector::<PlaneEnu>::enu_up_axis();
2507 let result_up = ecef_to_enu.inverse_transform(point_on_up);
2508 // nav_types does the ENU at the correct position and not the center of the earth. We remove the translation here.
2509 let expected_up = enu_up_in_ecef - enu_origin_in_ecef;
2510 assert_relative_eq!(result_up, Coordinate::<Ecef>::origin() + expected_up);
2511
2512 // Construct this as pose instead of just orientation.
2513 // This time the translation should be in there as well, so we can compare directly to nav_types output.
2514 let pose = unsafe {
2515 RigidBodyTransform::<Ecef, PlaneEnu>::ecef_to_enu_at(
2516 &Wgs84::builder()
2517 .latitude(lat)
2518 .expect("latitude is in-range")
2519 .longitude(long)
2520 .altitude(alt)
2521 .build(),
2522 )
2523 };
2524
2525 let result_enu_east_in_ecef = pose.inverse_transform(point_on_east);
2526 assert_relative_eq!(result_enu_east_in_ecef, enu_east_in_ecef);
2527
2528 let result_enu_north_in_ecef = pose.inverse_transform(point_on_north);
2529 assert_relative_eq!(result_enu_north_in_ecef, enu_north_in_ecef);
2530
2531 let result_enu_up_in_ecef = pose.inverse_transform(point_on_up);
2532 assert_relative_eq!(result_enu_up_in_ecef, enu_up_in_ecef);
2533 }
2534
2535 #[test]
2536 fn enu_ned_conversion_relationship() {
2537 let lat = d(52.);
2538 let long = d(-3.);
2539
2540 let ecef_to_enu = unsafe { Rotation::<Ecef, PlaneEnu>::ecef_to_enu_at(lat, long) };
2541 let ecef_to_ned = unsafe { Rotation::<Ecef, PlaneNed>::ecef_to_ned_at(lat, long) };
2542
2543 let enu_point = coordinate!(e = m(10.), n = m(20.), u = m(5.); in PlaneEnu);
2544 let ned_point = coordinate!(n = m(20.), e = m(10.), d = m(-5.); in PlaneNed);
2545
2546 let enu_in_ecef = ecef_to_enu.inverse_transform(enu_point);
2547 let ned_in_ecef = ecef_to_ned.inverse_transform(ned_point);
2548
2549 assert_relative_eq!(enu_in_ecef, ned_in_ecef);
2550 }
2551
2552 #[test]
2553 fn enu_pose_serde() {
2554 // Test serialization/deserialization of ENU poses
2555 let pose = unsafe {
2556 RigidBodyTransform::new(
2557 vector!(e = m(50.), n = m(45.), u = m(10.)),
2558 Rotation::<PlaneEnu, PlaneFrd>::tait_bryan_builder()
2559 .yaw(d(15.))
2560 .pitch(d(0.))
2561 .roll(d(1.))
2562 .build(),
2563 )
2564 };
2565
2566 let ser = serde_yaml::to_string(&pose).unwrap();
2567 let de = serde_yaml::from_str::<RigidBodyTransform<PlaneEnu, PlaneFrd>>(&ser).unwrap();
2568 assert_eq!(pose, de);
2569 }
2570
2571 #[test]
2572 fn bearing_rotation_enu_to_frd() {
2573 // assume forward is pointing North
2574 let enu_to_frd_pointing_north_rolled_upright = unsafe {
2575 Rotation::<Enu, Frd>::tait_bryan_builder()
2576 .yaw(d(90.))
2577 .pitch(d(0.))
2578 .roll(d(180.))
2579 .build()
2580 };
2581
2582 // a bearing pointing North
2583 assert_relative_eq!(
2584 Bearing::<Enu>::build(Components {
2585 azimuth: d(0.),
2586 elevation: d(0.)
2587 })
2588 .unwrap()
2589 * enu_to_frd_pointing_north_rolled_upright,
2590 Bearing::<Frd>::build(Components {
2591 azimuth: d(0.),
2592 elevation: d(0.)
2593 })
2594 .unwrap()
2595 );
2596
2597 // a bearing pointing 3° off East
2598 assert_relative_eq!(
2599 Bearing::<Enu>::build(Components {
2600 azimuth: d(93.),
2601 elevation: d(0.)
2602 })
2603 .unwrap()
2604 * enu_to_frd_pointing_north_rolled_upright,
2605 Bearing::<Frd>::build(Components {
2606 azimuth: d(93.),
2607 elevation: d(0.)
2608 })
2609 .unwrap()
2610 );
2611
2612 // assume forward is pointing West
2613 let enu_to_frd_pointing_west_rolled_upright = unsafe {
2614 Rotation::<Enu, Frd>::tait_bryan_builder()
2615 .yaw(d(180.)) // FRD X must rotate 180° to point West in ENU
2616 .pitch(d(0.))
2617 .roll(d(180.))
2618 .build()
2619 };
2620
2621 // a bearing pointing West and Up
2622 assert_relative_eq!(
2623 Bearing::<Enu>::build(Components {
2624 azimuth: d(270.),
2625 elevation: d(30.)
2626 })
2627 .unwrap()
2628 * enu_to_frd_pointing_west_rolled_upright,
2629 Bearing::<Frd>::build(Components {
2630 azimuth: d(0.),
2631 elevation: d(30.)
2632 })
2633 .unwrap()
2634 );
2635
2636 // a bearing pointing South and Down
2637 assert_relative_eq!(
2638 Bearing::<Enu>::build(Components {
2639 azimuth: d(180.),
2640 elevation: d(-62.)
2641 })
2642 .unwrap()
2643 * enu_to_frd_pointing_west_rolled_upright,
2644 Bearing::<Frd>::build(Components {
2645 azimuth: d(-90.),
2646 elevation: d(-62.)
2647 })
2648 .unwrap()
2649 );
2650
2651 // assume forward is pointing North East at a 30° elevation
2652 let enu_to_frd_pointing_north_east_and_up_rolled_upright = unsafe {
2653 Rotation::<Enu, Frd>::tait_bryan_builder()
2654 .yaw(d(45.))
2655 .pitch(d(-30.)) // rotating FRD to point up
2656 .roll(d(180.))
2657 .build()
2658 };
2659
2660 // a bearing pointing North East and Down, slightly off from the FRD
2661 assert_relative_eq!(
2662 Bearing::<Enu>::build(Components {
2663 azimuth: d(46.),
2664 elevation: d(-10.)
2665 })
2666 .unwrap()
2667 * enu_to_frd_pointing_north_east_and_up_rolled_upright,
2668 Bearing::<Frd>::build(Components {
2669 azimuth: d(1.2855),
2670 elevation: d(-39.9944)
2671 })
2672 .unwrap(),
2673 epsilon = 0.0001_f64.to_radians() // FRD bearing is approximate
2674 );
2675
2676 // assume forward is pointing North
2677 let enu_to_frd_pointing_north_inverted = unsafe {
2678 Rotation::<Enu, Frd>::tait_bryan_builder()
2679 .yaw(d(90.))
2680 .pitch(d(0.))
2681 .roll(d(0.))
2682 .build()
2683 };
2684
2685 // a bearing pointing 3° off East, a roll of 0° in ENU means the frame is "upside down" compared to FRD.
2686 assert_relative_eq!(
2687 Bearing::<Enu>::build(Components {
2688 azimuth: d(93.),
2689 elevation: d(0.)
2690 })
2691 .unwrap()
2692 * enu_to_frd_pointing_north_inverted,
2693 Bearing::<Frd>::build(Components {
2694 azimuth: d(267.),
2695 elevation: d(0.)
2696 })
2697 .unwrap()
2698 );
2699
2700 // assume forward is pointing North East at a 30° elevation but inverted
2701 let enu_to_frd_pointing_north_east_and_inverted = unsafe {
2702 Rotation::<Enu, Frd>::tait_bryan_builder()
2703 .yaw(d(45.))
2704 .pitch(d(-30.)) // rotating FRD to point up
2705 .roll(d(0.))
2706 .build()
2707 };
2708
2709 // a bearing pointing North East and Down, a roll of 0° in ENU means the frame is "upside down" compared to FRD.
2710 assert_relative_eq!(
2711 Bearing::<Enu>::build(Components {
2712 azimuth: d(45.),
2713 elevation: d(-10.)
2714 })
2715 .unwrap()
2716 * enu_to_frd_pointing_north_east_and_inverted,
2717 Bearing::<Frd>::build(Components {
2718 azimuth: d(0.),
2719 elevation: d(40.)
2720 })
2721 .unwrap()
2722 );
2723 }
2724
2725 #[test]
2726 fn enu_to_ned_equivalent_gives_same_rotation() {
2727 let lat = d(52.);
2728 let lon = d(-3.);
2729
2730 // Check quaternion equality of chained rotation
2731 let ecef_to_ned = unsafe { Rotation::<Ecef, PlaneNed>::ecef_to_ned_at(lat, lon) };
2732 let ecef_to_enu = unsafe { Rotation::<Ecef, PlaneEnu>::ecef_to_enu_at(lat, lon) };
2733 let ecef_to_ned_via_enu = unsafe { ecef_to_enu.into_ned_equivalent::<PlaneNed>() };
2734 assert_relative_eq!(
2735 ecef_to_ned_via_enu.inner,
2736 ecef_to_ned.inner,
2737 epsilon = 1e-10
2738 );
2739
2740 // Check a single coordinate in chained rotation
2741 let enu_coord_actual = coordinate!(e = m(4.), n = m(7.), u = m(1.); in PlaneEnu);
2742 let ned_coord_expected = coordinate!(n = m(7.), e = m(4.), d = m(-1.); in PlaneNed);
2743 let ned_coord_actual =
2744 ecef_to_ned_via_enu.transform(ecef_to_enu.inverse_transform(enu_coord_actual));
2745 assert_relative_eq!(ned_coord_actual, ned_coord_expected);
2746
2747 // Check round trip
2748 let enu_round_trip = unsafe { ecef_to_ned_via_enu.into_enu_equivalent::<PlaneEnu>() };
2749 assert_relative_eq!(enu_round_trip.inner, ecef_to_enu.inner, epsilon = 1e-10);
2750 }
2751
2752 #[test]
2753 fn ned_to_enu_equivalent_gives_same_rotation() {
2754 let lat = d(47.);
2755 let lon = d(26.);
2756
2757 // Check quaternion equality
2758 let ecef_to_enu = unsafe { Rotation::<Ecef, PlaneEnu>::ecef_to_enu_at(lat, lon) };
2759 let ecef_to_ned = unsafe { Rotation::<Ecef, PlaneNed>::ecef_to_ned_at(lat, lon) };
2760 let ecef_to_enu_via_ned = unsafe { ecef_to_ned.into_enu_equivalent::<PlaneEnu>() };
2761 assert_relative_eq!(
2762 ecef_to_enu_via_ned.inner,
2763 ecef_to_enu.inner,
2764 epsilon = 1e-10
2765 );
2766
2767 // Check a single coordinate in chained rotation
2768 let ned_coord_actual = coordinate!(n = m(18.), e = m(-2.), d = m(5.); in PlaneNed);
2769 let enu_coord_expected = coordinate!(e = m(-2.), n = m(18.), u = m(-5.); in PlaneEnu);
2770 let enu_coord_actual =
2771 ecef_to_enu_via_ned.transform(ecef_to_ned.inverse_transform(ned_coord_actual));
2772 assert_relative_eq!(enu_coord_actual, enu_coord_expected);
2773
2774 // Check round trip
2775 let ned_round_trip = unsafe { ecef_to_enu_via_ned.into_ned_equivalent::<PlaneNed>() };
2776 assert_relative_eq!(ned_round_trip.inner, ecef_to_ned.inner, epsilon = 1e-10);
2777 }
2778
2779 #[test]
2780 fn tait_bryan_builder_works_for_rotation() {
2781 // Test that the builder produces the same result as direct construction
2782 let yaw = d(90.);
2783 let pitch = d(45.);
2784 let roll = d(30.);
2785
2786 #[allow(deprecated)]
2787 let rotation_direct =
2788 unsafe { Rotation::<PlaneNed, PlaneFrd>::from_tait_bryan_angles(yaw, pitch, roll) };
2789
2790 let rotation_builder = unsafe {
2791 Rotation::<PlaneNed, PlaneFrd>::tait_bryan_builder()
2792 .yaw(yaw)
2793 .pitch(pitch)
2794 .roll(roll)
2795 .build()
2796 };
2797
2798 assert_relative_eq!(rotation_direct.inner, rotation_builder.inner);
2799 }
2800
2801 #[test]
2802 fn tait_bryan_builder_works_for_orientation() {
2803 use crate::engineering::Orientation;
2804
2805 // Test that the builder produces the same result as direct construction
2806 let yaw = d(45.);
2807 let pitch = d(-30.);
2808 let roll = d(15.);
2809
2810 #[allow(deprecated)]
2811 let orientation_direct = Orientation::<PlaneNed>::from_tait_bryan_angles(yaw, pitch, roll);
2812
2813 let orientation_builder = Orientation::<PlaneNed>::tait_bryan_builder()
2814 .yaw(yaw)
2815 .pitch(pitch)
2816 .roll(roll)
2817 .build();
2818
2819 assert_relative_eq!(
2820 orientation_direct.inner.inner,
2821 orientation_builder.inner.inner
2822 );
2823 }
2824
2825 /// Test that the builder correctly compiles for valid usage
2826 #[test]
2827 fn tait_bryan_builder_enforces_order() {
2828 let builder = Rotation::<PlaneNed, PlaneFrd>::tait_bryan_builder();
2829
2830 // Can call yaw first
2831 let builder = builder.yaw(d(10.));
2832
2833 // Can call pitch after yaw
2834 let builder = builder.pitch(d(20.));
2835
2836 // Can call roll after pitch
2837 let builder = builder.roll(d(30.));
2838
2839 // Can call build after roll
2840 let _rotation = unsafe { builder.build() };
2841
2842 // There are compile_fail tests that check that other orders will not work
2843 }
2844
2845 #[test]
2846 fn tait_bryan_builder_debug() {
2847 // Test Debug shows only set fields per state
2848 let builder_needs_yaw = Rotation::<PlaneNed, PlaneFrd>::tait_bryan_builder();
2849 let debug_str = format!("{builder_needs_yaw:?}");
2850 assert!(debug_str.contains("TaitBryanBuilder<NeedsYaw>"));
2851 assert!(!debug_str.contains("yaw"));
2852 assert!(!debug_str.contains("pitch"));
2853 assert!(!debug_str.contains("roll"));
2854
2855 let builder_after_yaw = builder_needs_yaw.yaw(d(90.));
2856 let debug_str = format!("{builder_after_yaw:?}");
2857 assert!(debug_str.contains("TaitBryanBuilder<NeedsPitch>"));
2858 assert!(debug_str.contains("yaw"));
2859 assert!(!debug_str.contains("pitch"));
2860 assert!(!debug_str.contains("roll"));
2861
2862 let builder_after_pitch = builder_after_yaw.pitch(d(30.));
2863 let debug_str = format!("{builder_after_pitch:?}");
2864 assert!(debug_str.contains("TaitBryanBuilder<NeedsRoll>"));
2865 assert!(debug_str.contains("yaw"));
2866 assert!(debug_str.contains("pitch"));
2867 assert!(!debug_str.contains("roll"));
2868
2869 let builder_complete = builder_after_pitch.roll(d(15.));
2870 let debug_str = format!("{builder_complete:?}");
2871 assert!(debug_str.contains("TaitBryanBuilder<Complete>"));
2872 assert!(debug_str.contains("yaw"));
2873 assert!(debug_str.contains("pitch"));
2874 assert!(debug_str.contains("roll"));
2875 }
2876}