pub struct RigidBodyTransform<From, To> { /* private fields */ }Expand description
Defines a rigid body transform between two CoordinateSystems.
A rigid transform may include both translation and rotation.
There are generally three ways to construct a rigid body transform:
- by using
engineering::Pose::map_as_zero_inwhen you already have anengineering::Pose; - by using
RigidBodyTransform::ecef_to_ned_atwhen you wish to translate betweenEcefand aNedLikeCoordinateSystem; or - by using
RigidBodyTransform::newto construct transforms from arbitrary translation and rotation.
Mathematically speaking, this is a type-safe wrapper around an Euclidian isometry.
Transforms can be chained with other transforms (including Rotations) using * (ie, the
Mul trait) or with RigidBodyTransform::and_then (they’re equivalent). They can also be
applied to Coordinate, Vector, and other types either by multiplication (or division
for inverse transforms) or by using RigidBodyTransform::transform (or
RigidBodyTransform::inverse_transform).
Note that this type implements Deserialize despite having unsafe constructors – this is
because doing otherwise would be extremely unergonomic. However, when deserializing, the
coordinate system of the deserialized value is not checked, so this is a foot-gun to be
mindful of.
The order of the operands to * matter, and do not match the mathematical convention.
Specifically, matrix multiply for transforms traditionally have the transform on the left and
the vector to transform on the right. However, doing so here would lead to a type signature of
let _: Coordinate<To> = RigidBodyTransform<From, To> * Coordinate<From>;Which violates the expectation that a matrix multiply eliminates the “middle” component (ie,
(m × n)(n × p) = (m × p)). So, we require that the transform is on the right to go from
From into To, and that the transform is on the left to go from To into From.
Implementations§
Source§impl<To> RigidBodyTransform<Ecef, To>where
To: CoordinateSystem<Convention = NedLike>,
impl<To> RigidBodyTransform<Ecef, To>where
To: CoordinateSystem<Convention = NedLike>,
Sourcepub unsafe fn ecef_to_ned_at(position: &Wgs84) -> Self
pub unsafe fn ecef_to_ned_at(position: &Wgs84) -> Self
Constructs the transformation from Ecef to NedLike at the given latitude and
longitude.
The lat/lon is needed because the orientation of North with respect to ECEF depends on
where on the globe you are, and because the transform of something like (0, 0, 0) in
NedLike into ECEF (and vice-verse) requires knowing the ECEF coordinates of this
NedLike’s origin.
§Safety
This function only produces a valid transform from Ecef to the NED-like To if
Coordinate::<To>::origin() lies at the provided lat/lon. If that is
not the case, the returned RigidBodyTransform will allow moving from Ecef to To
without the appropriate transformation of the components of the input, leading to outputs
that are typed to be in To but are in fact not.
Source§impl<To> RigidBodyTransform<Ecef, To>where
To: CoordinateSystem<Convention = EnuLike>,
impl<To> RigidBodyTransform<Ecef, To>where
To: CoordinateSystem<Convention = EnuLike>,
Sourcepub unsafe fn ecef_to_enu_at(position: &Wgs84) -> Self
pub unsafe fn ecef_to_enu_at(position: &Wgs84) -> Self
Constructs the transformation from Ecef to EnuLike at the given WGS84 position.
The position is needed because the orientation of East and North with respect to ECEF depends on where on the globe you are.
§Safety
This function only produces a valid transform from Ecef to the ENU-like To if
Coordinate::<To>::origin() lies at the provided position. If that is
not the case, the returned RigidBodyTransform will allow moving from Ecef to To
without the appropriate transformation of the components of the input, leading to outputs
that are typed to be in To but are in fact not.
Source§impl<From, To> RigidBodyTransform<From, To>
impl<From, To> RigidBodyTransform<From, To>
Sourcepub unsafe fn new(
translation: Vector<From>,
rotation: Rotation<From, To>,
) -> Self
pub unsafe fn new( translation: Vector<From>, rotation: Rotation<From, To>, ) -> Self
Constructs a transform directly from a translation and a rotation.
The translation here should be what must be applied to coordinates and vectors in To to
transform them into coordinates and vectors in From. In other words, the inverse of
this translation and rotation will be applied in the transform methods to go from From
to To.
§Safety
This method is marked as unsafe for the same reason engineering::Pose::map_as_zero_in
is; if you construct a transform incorrectly, it allows moving between different
type-enforced coordinate systems without performing the correct conversions, leading to a
defeat of type safety.
Sourcepub fn and_then<NewTo, Transform>(
self,
rhs: Transform,
) -> RigidBodyTransform<From, NewTo>where
Self: Mul<Transform, Output = RigidBodyTransform<From, NewTo>>,
pub fn and_then<NewTo, Transform>(
self,
rhs: Transform,
) -> RigidBodyTransform<From, NewTo>where
Self: Mul<Transform, Output = RigidBodyTransform<From, NewTo>>,
Chains two transforms to produce a new transform that can transform directly from From to
NewTo.
use sguaba::{
system, Coordinate, Vector,
math::{RigidBodyTransform, Rotation},
systems::{Ecef, Wgs84},
};
use uom::si::f64::{Angle, Length};
use uom::si::{angle::degree, length::meter};
system!(struct PlaneFrd using FRD);
system!(struct PlaneNed using NED);
// we can construct a transform from ECEF to PlaneNed
// (we can construct the ECEF from a WGS84 lat/lon)
let location = Wgs84::builder()
.latitude(Angle::new::<degree>(0.)).expect("latitude is in-range")
.longitude(Angle::new::<degree>(10.))
.altitude(Length::new::<meter>(0.))
.build();
// SAFETY: we're claiming that `location` is the location of `PlaneNed`'s origin.
let ecef_to_ned = unsafe { RigidBodyTransform::ecef_to_ned_at(&location) };
// we can also construct a (rotation) transform from PlaneNed to PlaneFrd
// assuming we know what direction the plane is facing.
// SAFETY: we're claiming that these angles are the orientation of the plane in NED.
let ned_to_frd = unsafe {
Rotation::<PlaneNed, PlaneFrd>::from_tait_bryan_angles(
Angle::new::<degree>(0.),
Angle::new::<degree>(45.),
Angle::new::<degree>(23.),
)
};
// and we can chain the two to give us a single transform that goes
// from ECEF to PlaneFrd in a single computation.
let ecef_to_frd = ecef_to_ned.and_then(ned_to_frd);Sourcepub unsafe fn identity() -> Self
pub unsafe fn identity() -> Self
Asserts that the transform from From to To is one that returns the original point or
vector when applied.
§Safety
This allows you to claim that the “correct” transform between the coordinate systems From
and To is the identity function. If this is not the correct transform, then this allows
moving values between different coordinate system types without adjusting the values
correctly, leading to a defeat of their type safety.
Sourcepub fn cast_type_of_from<AlsoFrom>(self) -> RigidBodyTransform<AlsoFrom, To>where
From: EquivalentTo<AlsoFrom>,
pub fn cast_type_of_from<AlsoFrom>(self) -> RigidBodyTransform<AlsoFrom, To>where
From: EquivalentTo<AlsoFrom>,
Casts the coordinate system type parameter From of the transform to the equivalent
coordinate system AlsoFrom.
See EquivalentTo for details on when this is useful (and safe).
Note that this performs no modifications to the transform itself, as that should be
unnecessary when EquivalentTo is implemented.
Sourcepub fn cast_type_of_to<AlsoTo>(self) -> RigidBodyTransform<From, AlsoTo>where
To: EquivalentTo<AlsoTo>,
pub fn cast_type_of_to<AlsoTo>(self) -> RigidBodyTransform<From, AlsoTo>where
To: EquivalentTo<AlsoTo>,
Casts the coordinate system type parameter To of the transform to the equivalent
coordinate system AlsoTo.
See EquivalentTo for details on when this is useful (and safe).
Note that this performs no modifications to the transform itself, as that should be
unnecessary when EquivalentTo is implemented.
Sourcepub fn inverse(&self) -> RigidBodyTransform<To, From>
pub fn inverse(&self) -> RigidBodyTransform<To, From>
Returns the equal-but-opposite transform to this one.
That is, a transform from the CoordinateSystem To into the coordinate system
From.
Sourcepub fn lerp(&self, rhs: &Self, t: f64) -> Self
pub fn lerp(&self, rhs: &Self, t: f64) -> Self
Linearly interpolate between this transform and another one.
Conceptually returns self * (1.0 - t) + rhs * t, i.e., the linear blend of the two
transforms using the scalar value t.
Internally, this linearly interpolates the translation and rotation separately, and
normalizes the rotation in the process (see Rotation::nlerp).
The value for t is not restricted to the range [0, 1].
Sourcepub fn translation(&self) -> Vector<From>
pub fn translation(&self) -> Vector<From>
Returns the translation of Coordinate::origin in To relative to the
Coordinate::origin in From.
That is, perhaps counter-intuitively but in alignment with RigidBodyTransform::new, the
translation that must be performed to go from To into From.
Source§impl<From, To> RigidBodyTransform<From, To>
impl<From, To> RigidBodyTransform<From, To>
Sourcepub fn transform<T>(&self, in_from: T) -> <T as Mul<Self>>::Outputwhere
T: Mul<Self>,
pub fn transform<T>(&self, in_from: T) -> <T as Mul<Self>>::Outputwhere
T: Mul<Self>,
Transforms an element in CoordinateSystem From into To.
Note that this transformation behaves differently for vectors than it does for coordinates. Following the convention in computer vision, a vector defines a displacement without an explicit origin. Thus, when transformed into a different coordinate system the displacement points in a different direction but retains its length. In other words, vectors are only subjected to the rotation part of the transform.
Note further that a bearing is transformed exactly the way it would be if it were a unit vector in the direction of the bearing.
Sourcepub fn inverse_transform<T>(&self, in_to: T) -> <Self as Mul<T>>::Outputwhere
Self: Mul<T>,
pub fn inverse_transform<T>(&self, in_to: T) -> <Self as Mul<T>>::Outputwhere
Self: Mul<T>,
Transforms an element in CoordinateSystem To into From.
This is equivalent to (but more efficient than) first inverting the transform with
RigidBodyTransform::inverse and then calling RigidBodyTransform::transform.
Note that this transformation behaves differently for vectors than it does for coordinates. Following the convention in computer vision, a vector defines a displacement without an explicit origin. Thus, when transformed into a different coordinate system the displacement points in a different direction but retains its length. In other words, vectors are only subjected to the rotation part of the transform.
Note further that a bearing is transformed exactly the way it would be if it were a unit vector in the direction of the bearing.
Trait Implementations§
Source§impl<From, To> AbsDiffEq for RigidBodyTransform<From, To>
Available on crate features approx only.
impl<From, To> AbsDiffEq for RigidBodyTransform<From, To>
approx only.Source§fn default_epsilon() -> Self::Epsilon
fn default_epsilon() -> Self::Epsilon
Source§fn abs_diff_eq(&self, other: &Self, epsilon: Self::Epsilon) -> bool
fn abs_diff_eq(&self, other: &Self, epsilon: Self::Epsilon) -> bool
Source§fn abs_diff_ne(&self, other: &Rhs, epsilon: Self::Epsilon) -> bool
fn abs_diff_ne(&self, other: &Rhs, epsilon: Self::Epsilon) -> bool
AbsDiffEq::abs_diff_eq.Source§impl<From, To> Clone for RigidBodyTransform<From, To>
impl<From, To> Clone for RigidBodyTransform<From, To>
Source§impl<'de, From, To> Deserialize<'de> for RigidBodyTransform<From, To>
impl<'de, From, To> Deserialize<'de> for RigidBodyTransform<From, To>
Source§fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
Source§impl<From, To> Display for RigidBodyTransform<From, To>
impl<From, To> Display for RigidBodyTransform<From, To>
Source§impl<From, To> Mul<Bearing<To>> for RigidBodyTransform<From, To>where
From: BearingDefined,
To: BearingDefined,
impl<From, To> Mul<Bearing<To>> for RigidBodyTransform<From, To>where
From: BearingDefined,
To: BearingDefined,
Source§impl<From, To> Mul<Coordinate<To>> for RigidBodyTransform<From, To>
impl<From, To> Mul<Coordinate<To>> for RigidBodyTransform<From, To>
Source§type Output = Coordinate<From>
type Output = Coordinate<From>
* operator.Source§impl<From, To> Mul<Orientation<To>> for RigidBodyTransform<From, To>
impl<From, To> Mul<Orientation<To>> for RigidBodyTransform<From, To>
Source§impl<From, To> Mul<Pose<To>> for RigidBodyTransform<From, To>
impl<From, To> Mul<Pose<To>> for RigidBodyTransform<From, To>
Source§impl<From, To> Mul<RigidBodyTransform<From, To>> for Bearing<From>where
From: BearingDefined,
To: BearingDefined,
impl<From, To> Mul<RigidBodyTransform<From, To>> for Bearing<From>where
From: BearingDefined,
To: BearingDefined,
Source§impl<From, To> Mul<RigidBodyTransform<From, To>> for Coordinate<From>
impl<From, To> Mul<RigidBodyTransform<From, To>> for Coordinate<From>
Source§type Output = Coordinate<To>
type Output = Coordinate<To>
* operator.Source§impl<From, To> Mul<RigidBodyTransform<From, To>> for Orientation<From>
impl<From, To> Mul<RigidBodyTransform<From, To>> for Orientation<From>
Source§impl<From, To> Mul<RigidBodyTransform<From, To>> for Pose<From>
impl<From, To> Mul<RigidBodyTransform<From, To>> for Pose<From>
Source§impl<From, To> Mul<RigidBodyTransform<From, To>> for Vector<From>
impl<From, To> Mul<RigidBodyTransform<From, To>> for Vector<From>
Source§impl<From, Over, To> Mul<RigidBodyTransform<Over, To>> for RigidBodyTransform<From, Over>
impl<From, Over, To> Mul<RigidBodyTransform<Over, To>> for RigidBodyTransform<From, Over>
Source§type Output = RigidBodyTransform<From, To>
type Output = RigidBodyTransform<From, To>
* operator.Source§impl<From, Over, To> Mul<Rotation<Over, To>> for RigidBodyTransform<From, Over>
impl<From, Over, To> Mul<Rotation<Over, To>> for RigidBodyTransform<From, Over>
Source§impl<From, To> Mul<Vector<To>> for RigidBodyTransform<From, To>
impl<From, To> Mul<Vector<To>> for RigidBodyTransform<From, To>
Source§impl<From, To> Neg for RigidBodyTransform<From, To>
impl<From, To> Neg for RigidBodyTransform<From, To>
Source§impl<From, To> PartialEq for RigidBodyTransform<From, To>
impl<From, To> PartialEq for RigidBodyTransform<From, To>
Source§impl<From, To> RelativeEq for RigidBodyTransform<From, To>
Available on crate features approx only.
impl<From, To> RelativeEq for RigidBodyTransform<From, To>
approx only.Source§fn default_max_relative() -> Self::Epsilon
fn default_max_relative() -> Self::Epsilon
Source§fn relative_eq(
&self,
other: &Self,
epsilon: Self::Epsilon,
max_relative: Self::Epsilon,
) -> bool
fn relative_eq( &self, other: &Self, epsilon: Self::Epsilon, max_relative: Self::Epsilon, ) -> bool
Source§fn relative_ne(
&self,
other: &Rhs,
epsilon: Self::Epsilon,
max_relative: Self::Epsilon,
) -> bool
fn relative_ne( &self, other: &Rhs, epsilon: Self::Epsilon, max_relative: Self::Epsilon, ) -> bool
RelativeEq::relative_eq.Source§impl<From, To> Serialize for RigidBodyTransform<From, To>
impl<From, To> Serialize for RigidBodyTransform<From, To>
impl<From, To> Copy for RigidBodyTransform<From, To>
Auto Trait Implementations§
impl<From, To> Freeze for RigidBodyTransform<From, To>
impl<From, To> RefUnwindSafe for RigidBodyTransform<From, To>where
From: RefUnwindSafe,
To: RefUnwindSafe,
impl<From, To> Send for RigidBodyTransform<From, To>
impl<From, To> Sync for RigidBodyTransform<From, To>
impl<From, To> Unpin for RigidBodyTransform<From, To>
impl<From, To> UnsafeUnpin for RigidBodyTransform<From, To>
impl<From, To> UnwindSafe for RigidBodyTransform<From, To>where
From: UnwindSafe,
To: UnwindSafe,
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
Source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
self is actually part of its subset T (and can be converted to it).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self to the equivalent element of its superset.