Skip to main content

Vector

Struct Vector 

Source
pub struct Vector<In, Time = Z0>
where Time: Integer,
{ /* private fields */ }
Expand description

Defines a vector (ie, direction with magnitude) in the coordinate system specified by In.

You can construct one using Cartesian or spherical components, or using bearing + range. You can also use the vector! macro for a concise constructor with named arguments.

Depending on the convention of the coordinate system (eg, NedLike, FrdLike, or RightHandedXyzLike), you’ll have different appropriately-named accessors for the vector’s cartesian components like Vector::ned_north or Vector::frd_front.

§Working with different Vector units

sguaba supports vectors representing different physical quantities:

  • Length vectors (Vector<In>, Vector<In, Z0>, or LengthVector) for positions and displacements
  • Velocity vectors (Vector<In, N1> or VelocityVector) for velocities
  • Acceleration vectors (Vector<In, N2> or AccelerationVector) for accelerations

All vector operations (addition, scaling, transforms) are supported for all units.

§Length Vector


let displacement = vector!(
    f = Length::new::<meter>(10.0),
    r = Length::new::<meter>(5.0),
    d = Length::new::<meter>(0.0);
    in PlaneFrd
);

§Velocity Vector


let velocity = vector!(
    f = Velocity::new::<meter_per_second>(100.0), // forward
    r = Velocity::new::<meter_per_second>(0.0),   // right
    d = Velocity::new::<meter_per_second>(5.0);   // down
    in PlaneFrd
);

§Acceleration Vector


// Commanded acceleration (climb has negative d in FRD)
let acceleration = vector!(
    f = Acceleration::new::<meter_per_second_squared>(2.0),  // speed up
    r = Acceleration::new::<meter_per_second_squared>(0.0),
    d = Acceleration::new::<meter_per_second_squared>(-1.0); // climb
    in PlaneFrd
);

// Can use other acceleration units, such as standard gravity
let gravity = vector!(
    n = Acceleration::new::<meter_per_second_squared>(0.0),
    e = Acceleration::new::<meter_per_second_squared>(0.0),
    d = Acceleration::new::<uom::si::acceleration::standard_gravity>(1.);
    in PlaneNed
);

§Type safety with units

The type system prevents mixing incompatible units:


// Cannot put meters in a velocity vector - this will not compile
let bad_velocity = vector!(
    f = Length::new::<meter>(10.0), // Length, not Velocity!
    r = Velocity::new::<meter_per_second>(5.0),
    d = Velocity::new::<meter_per_second>(0.0);
    in PlaneFrd
);

// Cannot add length and acceleration vectors - this will not compile
let velocity = vector!(
    f = Velocity::new::<meter_per_second>(10.0),
    r = Velocity::new::<meter_per_second>(0.0),
    d = Velocity::new::<meter_per_second>(0.0);
    in PlaneFrd
);
let acceleration = vector!(
    f = Acceleration::new::<meter_per_second_squared>(2.0),
    r = Acceleration::new::<meter_per_second_squared>(0.0),
    d = Acceleration::new::<meter_per_second_squared>(0.0);
    in PlaneFrd
);
let bad_sum = velocity + acceleration; // Different Time parameters!

Only LengthVector can be created from Coordinate, as coordinates are inherently just describing positions in a coordinate system, which are displacements (ie, lengths) from origin:


let coordinate = coordinate!(
    f = Length::new::<meter>(10.0),
    r = Length::new::<meter>(5.0),
    d = Length::new::<meter>(0.0);
    in PlaneFrd
);

// This compiles fine
let _: LengthVector<PlaneFrd> = coordinate.into();

// This will not compile as that `impl From` does not exist
let _: VelocityVector<PlaneFrd> = coordinate.into();

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.

Implementations§

Source§

impl<In, Time> Vector<In, Time>
where Time: Integer, Self: LengthBasedComponents<In, Time>,

Source

pub fn build( components: <In::Convention as HasComponents<Time>>::Components, ) -> Self

Constructs a Vector at the given (x, y, z) Cartesian point in the CoordinateSystem In.

Source

pub fn builder() -> Builder<In, Unset, Unset, Unset, Time>
where In: CoordinateSystem,

Provides a constructor for a Coordinate in the CoordinateSystem In.

Source

pub fn from_cartesian( x: impl Into<Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>>, y: impl Into<Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>>, z: impl Into<Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>>, ) -> Self

👎Deprecated: prefer Vector::builder to avoid risk of argument order confusion

Constructs a vector with the given (x, y, z) cartesian components in the CoordinateSystem In.

Prefer Vector::builder, Vector::build, or vector to avoid risk of argument order confusion. This function will be removed in a future version of Sguaba in favor of those.

This method is permanently deprecated because it is particularly vulnerable to argument order confusion (eg, accidentally passing in the “down” component of a FRD vector first instead of last). Methods like Vector::builder and the vector! macro should be preferred instead, as they do not have this problem. However, this method is left for use-cases where those alternatives cannot be used, such as when writing code that is fully generic over the coordinate system, and thus cannot use the safer constructors provided by those APIs. If this applies to you, make sure you apply due diligence when writing out the argument ordering.

The meaning of x, y, and z is dictated by the “convention” of In. For example, in NedLike, x is North, y is East, and z is “down” (ie, in the direction of gravity).

Source

pub fn from_spherical( radius: impl Into<Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>>, polar: impl Into<Angle>, azimuth: impl Into<Angle>, ) -> Self

Constructs a vector with the given (r, θ, φ) spherical components in the CoordinateSystem In.

This constructor follows the physics convention for spherical coordinates, which defines

  • r as the radial distance, meaning the slant distance to origin;
  • θ (theta) as the polar angle meaning the angle with respect to positive polar axis (Z); and
  • φ (phi) as the azimuthal angle, meaning the angle of rotation from the initial meridian plane (positive X towards positive Y).

The axes and planes above are in turn dictated by the CoordinateSystem::Convention of In. For example, in NedLike, the polar angle is the angle relative to straight down and the azimuthal angle is the angle from North. In FrdLike, the polar angle is the angle relative to “down” and the azimuthal angle is the angle from forward.

Note that this convention does not necessarily match the conventions of each coordinate system. For example, in NedLike and FrdLike coordinate systems, we often talk about “azimuth and elevation”, but those are distinct from the spherical coordinates. In that context, the definition of azimuth (luckily) matches that of spherical coordinates, but elevation tends to be defined as the angle from the positive X axis rather than from the positive Z axis. If you want to define a coordinate based on azimuth and elevation, use Vector::from_bearing.

§Examples
use approx::assert_relative_eq;
use sguaba::{system, vector, Vector};
use uom::si::f64::{Angle, Length};
use uom::si::{angle::degree, length::meter};

system!(struct Ned using NED);

let zero = Length::new::<meter>(0.);
let unit = Length::new::<meter>(1.);
assert_relative_eq!(
    Vector::<Ned>::from_spherical(unit, Angle::new::<degree>(0.), Angle::new::<degree>(0.)),
    vector!(n = zero, e = zero, d = unit),
);
assert_relative_eq!(
    Vector::<Ned>::from_spherical(unit, Angle::new::<degree>(90.), Angle::new::<degree>(0.)),
    vector!(n = unit, e = zero, d = zero),
);
assert_relative_eq!(
    Vector::<Ned>::from_spherical(unit, Angle::new::<degree>(90.), Angle::new::<degree>(90.)),
    vector!(n = zero, e = unit, d = zero),
);
Source

pub fn from_bearing( bearing: Bearing<In>, range: impl Into<Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>>, ) -> Self
where In: BearingDefined,

Constructs a vector with the given azimuth, elevation, and range in the CoordinateSystem In.

This constructor is based on the bearing as it defined by the implementation of BearingDefined for In. For NedLike and FrdLike coordinate systems, this is:

  • azimuth is the angle clockwise as seen from “up” along the XY plane from the positive X axis (eg, North or Forward); and
  • elevation is the angle towards Z from the XY plane; and
  • r is the radial distance, meaning the slant distance to origin.

See also horizontal coordinate systems.

§Examples
use approx::assert_relative_eq;
use sguaba::{system, vector, Bearing, Vector};
use uom::si::f64::{Angle, Length};
use uom::si::{angle::degree, length::meter};

system!(struct Ned using NED);

let zero = Length::new::<meter>(0.);
let unit = Length::new::<meter>(1.);
assert_relative_eq!(
    Vector::<Ned>::from_bearing(
      Bearing::builder()
        .azimuth(Angle::new::<degree>(0.))
        .elevation(Angle::new::<degree>(0.)).expect("elevation is in-range")
        .build(),
      unit
    ),
    vector!(n = unit, e = zero, d = zero),
);
assert_relative_eq!(
    Vector::<Ned>::from_bearing(
      Bearing::builder()
        .azimuth(Angle::new::<degree>(90.))
        .elevation(Angle::new::<degree>(0.)).expect("elevation is in-range")
        .build(),
      unit
    ),
    vector!(n = zero, e = unit, d = zero),
);
assert_relative_eq!(
    Vector::<Ned>::from_bearing(
      Bearing::builder()
        .azimuth(Angle::new::<degree>(90.))
        .elevation(Angle::new::<degree>(90.)).expect("elevation is in-range")
        .build(),
      unit
    ),
    vector!(n = zero, e = zero, d = -unit),
);
Source

pub fn with_same_components_in<NewIn>(self) -> Vector<NewIn, Time>

Changes the coordinate system of the vector to <NewIn> with no changes to the components.

This is useful useful when the transform from one coordinate system to another only includes translation and not rotation, since vectors are unaffected by translation (see RigidBodyTransform::transform) and thus can be equivalently used in both.

It can also be useful when you have two coordinate systems that you know have exactly equivalent axes, and you need the types to “work out”. This can be the case, for instance, when two crates have both separately declared a NED-like coordinate system centered on the same object, and you need to move vectors between them. In such cases, however, prefer implementing EquivalentTo and using Vector::cast, as it is harder to accidentally misuse.

This is not how you generally want to convert between coordinate systems. For that, you’ll want to use RigidBodyTransform.

This is exactly equivalent to re-constructing the vector with the same component values using <NewIn> instead of <In, Time>, just more concise and legible. That is, it is exactly equal to:

use sguaba::{system, vector, Bearing, Vector};
use uom::si::f64::{Angle, Length};
use uom::si::{angle::degree, length::meter};

system!(struct PlaneNedFromCrate1 using NED);
system!(struct PlaneNedFromCrate2 using NED);

let zero = Length::new::<meter>(0.);
let unit = Length::new::<meter>(1.);
let vector_in_1 = vector!(n = unit, e = zero, d = unit; in PlaneNedFromCrate1);

assert_eq!(
    vector! {
      n = vector_in_1.ned_north(),
      e = vector_in_1.ned_east(),
      d = vector_in_1.ned_down();
      in PlaneNedFromCrate2
    },
    vector_in_1.with_same_components_in::<PlaneNedFromCrate2>()
);
Source

pub fn cast<NewIn>(self) -> Vector<NewIn, Time>
where In: EquivalentTo<NewIn>,

Casts the coordinate system type parameter of the vector to the equivalent coordinate system NewIn.

See EquivalentTo for details on when this is useful (and safe).

Note that this performs no transform on the vector’s components, as that should be unnecessary when EquivalentTo is implemented.

use sguaba::{system, vector, systems::EquivalentTo, Vector};
use uom::si::{f64::Length, length::meter};

system!(struct PlaneNedFromCrate1 using NED);
system!(struct PlaneNedFromCrate2 using NED);

// SAFETY: these are truly the same thing just defined in different places
unsafe impl EquivalentTo<PlaneNedFromCrate1> for PlaneNedFromCrate2 {}
unsafe impl EquivalentTo<PlaneNedFromCrate2> for PlaneNedFromCrate1 {}

let zero = Length::new::<meter>(0.);
let unit = Length::new::<meter>(1.);
let vector_in_1 = vector!(n = unit, e = zero, d = unit; in PlaneNedFromCrate1);

assert_eq!(
    vector! {
      n = vector_in_1.ned_north(),
      e = vector_in_1.ned_east(),
      d = vector_in_1.ned_down();
      in PlaneNedFromCrate2
    },
    vector_in_1.cast::<PlaneNedFromCrate2>()
);
Source

pub fn normalized(&self) -> Self

Returns a unit vector with the same direction as this vector.

Source

pub fn dot(&self, rhs: &Self) -> f64

Computes the dot (scalar) product between this vector and another.

Note that this method’s return value is unitless since the unit of the dot product is not meaningful in terms of the units of the underlying components.

Source

pub fn lerp(&self, rhs: &Self, t: f64) -> Self

Linearly interpolate between this vector and another vector.

Specifically, returns self * (1.0 - t) + rhs * t, i.e., the linear blend of the two vectors using the scalar value t.

The value for t is not restricted to the range [0, 1].

Source

pub fn bearing_at_origin(&self) -> Option<Bearing<In>>
where In: BearingDefined,

Computes the bearing of the vector as if the vector starts at the origin of In.

Returns None if the vector has zero length, as the azimuth is then ill-defined.

Returns an azimuth of zero if the vector points directly along the Z axis.

Source

pub fn orientation_at_origin( &self, roll: impl Into<Angle>, ) -> Option<Orientation<In>>

Computes the orientation of the vector as if the vector starts at the origin of In.

Since vectors do not include roll information, the desired roll must be passed in. It’s worth reading the documentation on Orientation for a reminder about the meaning of roll here. Very briefly, it is intrinsic, and 0° roll means the object’s positive Z axis is aligned with In’s positive Z axis.

Returns None if the vector has zero length, as the yaw is then ill-defined.

Returns a yaw of zero if the vector points directly along the Z axis.

Source

pub fn zero() -> Self

Constructs a vector in coordinate system In whose components are all 0.

This is the additive identity for In under vector addition, meaning adding this vector to any coordinate or vector in In will yield the origin coordinate or vector unchanged.

Source§

impl<In, Time: Integer> Vector<In, Time>
where In: CoordinateSystem<Convention = RightHandedXyzLike>, Self: LengthBasedComponents<In, Time>,

Source

pub fn x( &self, ) -> Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>

Source

pub fn y( &self, ) -> Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>

Source

pub fn z( &self, ) -> Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>

Source

pub fn x_axis() -> Vector<In, Time>

Source

pub fn y_axis() -> Vector<In, Time>

Source

pub fn z_axis() -> Vector<In, Time>

Source§

impl<In, Time: Integer> Vector<In, Time>
where In: CoordinateSystem<Convention = NedLike>, Self: LengthBasedComponents<In, Time>,

Source

pub fn ned_north( &self, ) -> Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>

Source

pub fn ned_east( &self, ) -> Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>

Source

pub fn ned_down( &self, ) -> Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>

Source

pub fn ned_north_axis() -> Vector<In, Time>

Source

pub fn ned_east_axis() -> Vector<In, Time>

Source

pub fn ned_down_axis() -> Vector<In, Time>

Source§

impl<In, Time: Integer> Vector<In, Time>
where In: CoordinateSystem<Convention = FrdLike>, Self: LengthBasedComponents<In, Time>,

Source

pub fn frd_front( &self, ) -> Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>

Source

pub fn frd_right( &self, ) -> Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>

Source

pub fn frd_down( &self, ) -> Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>

Source

pub fn frd_front_axis() -> Vector<In, Time>

Source

pub fn frd_right_axis() -> Vector<In, Time>

Source

pub fn frd_down_axis() -> Vector<In, Time>

Source§

impl<In, Time: Integer> Vector<In, Time>
where In: CoordinateSystem<Convention = EnuLike>, Self: LengthBasedComponents<In, Time>,

Source

pub fn enu_east( &self, ) -> Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>

Source

pub fn enu_north( &self, ) -> Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>

Source

pub fn enu_up( &self, ) -> Quantity<ISQ<P1, Z0, Time, Z0, Z0, Z0, Z0, dyn Kind>, SI<V>, V>

Source

pub fn enu_east_axis() -> Vector<In, Time>

Source

pub fn enu_north_axis() -> Vector<In, Time>

Source

pub fn enu_up_axis() -> Vector<In, Time>

Source§

impl<In> Vector<In, Z0>

Source

pub fn to_cartesian(&self) -> [Length; 3]

Returns the cartesian components of this vector in XYZ order.

To turn this into a simple (ie, unitless) [f64; 3], use array::map combined with .get::<meter>().

Source

pub fn magnitude(&self) -> Length

Computes the magnitude of the vector (ie, its length).

Source§

impl<In> Vector<In, N1>

Source

pub fn to_cartesian(&self) -> [Velocity; 3]

Returns the cartesian components of this velocity vector in XYZ order.

To turn this into a simple (ie, unitless) [f64; 3], use array::map combined with .get::<meter_per_second>().

Source

pub fn magnitude(&self) -> Velocity

Computes the magnitude of the vector (ie, its velocity).

Source§

impl<In> Vector<In, N2>

Source

pub fn to_cartesian(&self) -> [Acceleration; 3]

Returns the cartesian components of this vector in XYZ order.

To turn this into a simple (ie, unitless) [f64; 3], use array::map combined with .get::<meter_per_second_squared>().

Source

pub fn magnitude(&self) -> Acceleration

Computes the magnitude of the vector (ie, its acceleration).

Trait Implementations§

Source§

impl<In, Time: Integer> AbsDiffEq for Vector<In, Time>

Available on crate features approx only.
Source§

type Epsilon = <f64 as AbsDiffEq>::Epsilon

Used for specifying relative comparisons.
Source§

fn default_epsilon() -> Self::Epsilon

The default tolerance to use when testing values that are close together. Read more
Source§

fn abs_diff_eq(&self, other: &Self, epsilon: Self::Epsilon) -> bool

A test for equality that uses the absolute difference to compute the approximate equality of two numbers.
Source§

fn abs_diff_ne(&self, other: &Rhs, epsilon: Self::Epsilon) -> bool

The inverse of AbsDiffEq::abs_diff_eq.
Source§

impl<In> Add<Vector<In>> for Coordinate<In>

Source§

type Output = Coordinate<In>

The resulting type after applying the + operator.
Source§

fn add(self, rhs: Vector<In>) -> Self::Output

Performs the + operation. Read more
Source§

impl<In, Time: Integer> Add for Vector<In, Time>

Source§

type Output = Vector<In, Time>

The resulting type after applying the + operator.
Source§

fn add(self, rhs: Self) -> Self::Output

Performs the + operation. Read more
Source§

impl<In> AddAssign<Vector<In>> for Coordinate<In>

Source§

fn add_assign(&mut self, rhs: Vector<In>)

Performs the += operation. Read more
Source§

impl<In, Time: Integer> AddAssign for Vector<In, Time>

Source§

fn add_assign(&mut self, rhs: Self)

Performs the += operation. Read more
Source§

impl<In, Time: Integer> Clone for Vector<In, Time>

Source§

fn clone(&self) -> Self

Returns a duplicate of the value. Read more
1.0.0 · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl<In: Debug, Time> Debug for Vector<In, Time>
where Time: Integer + Debug,

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Source§

impl<In, Time> Default for Vector<In, Time>
where Time: Integer, Self: LengthBasedComponents<In, Time>,

Source§

fn default() -> Self

Returns the “default value” for a type. Read more
Source§

impl<'de, In, Time> Deserialize<'de> for Vector<In, Time>
where Time: Integer,

Source§

fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>
where __D: Deserializer<'de>,

Deserialize this value from the given Serde deserializer. Read more
Source§

impl<In, Time: Integer> Display for Vector<In, Time>

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Source§

impl<In, Time: Integer> Div<Quantity<dyn Dimension<M = Z0, L = PInt<UInt<UTerm, B1>>, T = Z0, N = Z0, Th = Z0, I = Z0, Kind = dyn Kind, J = Z0>, dyn Units<f64, electric_current = ampere, length = meter, amount_of_substance = mole, mass = kilogram, time = second, luminous_intensity = candela, thermodynamic_temperature = kelvin>, f64>> for Vector<In, Time>

Source§

type Output = Vector<In, Time>

The resulting type after applying the / operator.
Source§

fn div(self, rhs: Length) -> Self::Output

Performs the / operation. Read more
Source§

impl<In, Time: Integer> Div<f64> for Vector<In, Time>

Source§

type Output = Vector<In, Time>

The resulting type after applying the / operator.
Source§

fn div(self, scalar: f64) -> Self::Output

Performs the / operation. Read more
Source§

impl<In> From<Coordinate<In>> for Vector<In, Z0>

Source§

fn from(value: Coordinate<In>) -> Self

Converts to this type from the input type.
Source§

impl<In, Time: Integer> Mul<Quantity<dyn Dimension<M = Z0, L = PInt<UInt<UTerm, B1>>, T = Z0, N = Z0, Th = Z0, I = Z0, Kind = dyn Kind, J = Z0>, dyn Units<f64, electric_current = ampere, length = meter, amount_of_substance = mole, mass = kilogram, time = second, luminous_intensity = candela, thermodynamic_temperature = kelvin>, f64>> for Vector<In, Time>

Source§

type Output = Vector<In, Time>

The resulting type after applying the * operator.
Source§

fn mul(self, rhs: Length) -> Self::Output

Performs the * operation. Read more
Source§

impl<In> Mul<Quantity<dyn Dimension<M = Z0, L = Z0, T = PInt<UInt<UTerm, B1>>, N = Z0, Th = Z0, I = Z0, Kind = dyn Kind, J = Z0>, dyn Units<f64, electric_current = ampere, length = meter, amount_of_substance = mole, mass = kilogram, time = second, luminous_intensity = candela, thermodynamic_temperature = kelvin>, f64>> for Vector<In, N2>

Source§

type Output = Vector<In, NInt<UInt<UTerm, B1>>>

The resulting type after applying the * operator.
Source§

fn mul(self, duration: Time) -> Self::Output

Performs the * operation. Read more
Source§

impl<In> Mul<Quantity<dyn Dimension<M = Z0, L = Z0, T = PInt<UInt<UTerm, B1>>, N = Z0, Th = Z0, I = Z0, Kind = dyn Kind, J = Z0>, dyn Units<f64, electric_current = ampere, length = meter, amount_of_substance = mole, mass = kilogram, time = second, luminous_intensity = candela, thermodynamic_temperature = kelvin>, f64>> for Vector<In, N1>

Source§

type Output = Vector<In>

The resulting type after applying the * operator.
Source§

fn mul(self, duration: Time) -> Self::Output

Performs the * operation. Read more
Source§

impl<From, To> Mul<RigidBodyTransform<From, To>> for Vector<From>

Source§

type Output = Vector<To>

The resulting type after applying the * operator.
Source§

fn mul(self, rhs: RigidBodyTransform<From, To>) -> Self::Output

Performs the * operation. Read more
Source§

impl<From, To> Mul<Rotation<From, To>> for Vector<From>

Source§

type Output = Vector<To>

The resulting type after applying the * operator.
Source§

fn mul(self, rhs: Rotation<From, To>) -> Self::Output

Performs the * operation. Read more
Source§

impl<From, To> Mul<Vector<To>> for RigidBodyTransform<From, To>

Source§

type Output = Vector<From>

The resulting type after applying the * operator.
Source§

fn mul(self, rhs: Vector<To>) -> Self::Output

Performs the * operation. Read more
Source§

impl<From, To> Mul<Vector<To>> for Rotation<From, To>

Source§

type Output = Vector<From>

The resulting type after applying the * operator.
Source§

fn mul(self, rhs: Vector<To>) -> Self::Output

Performs the * operation. Read more
Source§

impl<In, Time: Integer> Mul<f64> for Vector<In, Time>

Source§

type Output = Vector<In, Time>

The resulting type after applying the * operator.
Source§

fn mul(self, scalar: f64) -> Self::Output

Performs the * operation. Read more
Source§

impl<In, Time: Integer> Neg for Vector<In, Time>

Source§

type Output = Vector<In, Time>

The resulting type after applying the - operator.
Source§

fn neg(self) -> Self::Output

Performs the unary - operation. Read more
Source§

impl<In, Time: Integer> PartialEq for Vector<In, Time>

Source§

fn eq(&self, other: &Self) -> bool

Tests for self and other values to be equal, and is used by ==.
1.0.0 · Source§

fn ne(&self, other: &Rhs) -> bool

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
Source§

impl<In, Time: Integer> RelativeEq for Vector<In, Time>

Available on crate features approx only.
Source§

fn default_max_relative() -> Self::Epsilon

The default relative tolerance for testing values that are far-apart. Read more
Source§

fn relative_eq( &self, other: &Self, epsilon: Self::Epsilon, max_relative: Self::Epsilon, ) -> bool

A test for equality that uses a relative comparison if the values are far apart.
Source§

fn relative_ne( &self, other: &Rhs, epsilon: Self::Epsilon, max_relative: Self::Epsilon, ) -> bool

The inverse of RelativeEq::relative_eq.
Source§

impl<In, Time> Serialize for Vector<In, Time>
where Time: Integer,

Source§

fn serialize<__S>(&self, __serializer: __S) -> Result<__S::Ok, __S::Error>
where __S: Serializer,

Serialize this value into the given Serde serializer. Read more
Source§

impl<In> Sub<Vector<In>> for Coordinate<In>

Source§

type Output = Coordinate<In>

The resulting type after applying the - operator.
Source§

fn sub(self, rhs: Vector<In>) -> Self::Output

Performs the - operation. Read more
Source§

impl<In, Time: Integer> Sub for Vector<In, Time>

Source§

type Output = Vector<In, Time>

The resulting type after applying the - operator.
Source§

fn sub(self, rhs: Self) -> Self::Output

Performs the - operation. Read more
Source§

impl<In> SubAssign<Vector<In>> for Coordinate<In>

Source§

fn sub_assign(&mut self, rhs: Vector<In>)

Performs the -= operation. Read more
Source§

impl<In, Time: Integer> SubAssign for Vector<In, Time>

Source§

fn sub_assign(&mut self, rhs: Self)

Performs the -= operation. Read more
Source§

impl<In, Time: Integer> Sum for Vector<In, Time>
where Self: LengthBasedComponents<In, Time>,

Source§

fn sum<I: Iterator<Item = Self>>(iter: I) -> Self

Takes an iterator and generates Self from the elements by “summing up” the items.
Source§

impl<In, Time: Integer> Copy for Vector<In, Time>

Auto Trait Implementations§

§

impl<In, Time> Freeze for Vector<In, Time>

§

impl<In, Time> RefUnwindSafe for Vector<In, Time>
where In: RefUnwindSafe,

§

impl<In, Time> Send for Vector<In, Time>
where In: Send,

§

impl<In, Time> Sync for Vector<In, Time>
where In: Sync,

§

impl<In, Time> Unpin for Vector<In, Time>
where In: Unpin,

§

impl<In, Time> UnsafeUnpin for Vector<In, Time>

§

impl<In, Time> UnwindSafe for Vector<In, Time>
where In: UnwindSafe,

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

Source§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
Source§

fn is_in_subset(&self) -> bool

Checks if self is actually part of its subset T (and can be converted to it).
Source§

fn to_subset_unchecked(&self) -> SS

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
Source§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
Source§

impl<T> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
Source§

impl<T> ToString for T
where T: Display + ?Sized,

Source§

fn to_string(&self) -> String

Converts the given value to a String. Read more
Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
Source§

impl<T, Right> ClosedAdd<Right> for T
where T: Add<Right, Output = T> + AddAssign<Right>,

Source§

impl<T, Right> ClosedAddAssign<Right> for T
where T: ClosedAdd<Right> + AddAssign<Right>,

Source§

impl<T> ClosedNeg for T
where T: Neg<Output = T>,

Source§

impl<T, Right> ClosedSub<Right> for T
where T: Sub<Right, Output = T> + SubAssign<Right>,

Source§

impl<T, Right> ClosedSubAssign<Right> for T
where T: ClosedSub<Right> + SubAssign<Right>,

Source§

impl<T> DeserializeOwned for T
where T: for<'de> Deserialize<'de>,

Source§

impl<System> EquivalentTo<System> for System

Source§

impl<T> Scalar for T
where T: 'static + Clone + PartialEq + Debug,