Skip to main content

SE2

Struct SE2 

Source
pub struct SE2 { /* private fields */ }
Expand description

SE(2) group element representing rigid body transformations in 2D.

Represented as a combination of 2D rotation and Vector2 translation.

Implementations§

Source§

impl SE2

Source

pub const DIM: usize = 2

Space dimension - dimension of the ambient space that the group acts on

Source

pub const DOF: usize = 3

Degrees of freedom - dimension of the tangent space

Source

pub const REP_SIZE: usize = 4

Representation size - size of the underlying data representation

Source

pub fn identity() -> SE2

Get the identity element of the group.

Returns the neutral element e such that e ∘ g = g ∘ e = g for any group element g.

Source

pub fn jacobian_identity() -> Matrix<f64, Const<3>, Const<3>, ArrayStorage<f64, 3, 3>>

Get the identity matrix for Jacobians.

Returns the identity matrix in the appropriate dimension for Jacobian computations.

Source

pub fn new( translation: Matrix<f64, Const<2>, Const<1>, ArrayStorage<f64, 2, 1>>, rotation: Unit<Complex<f64>>, ) -> SE2

Create a new SE2 element from translation and rotation.

§Arguments
  • translation - Translation vector [x, y]
  • rotation - Unit complex number representing rotation
Source

pub fn from_xy_angle(x: f64, y: f64, theta: f64) -> SE2

Create SE2 from translation components and angle.

Source

pub fn from_xy_complex(x: f64, y: f64, real: f64, imag: f64) -> SE2

Create SE2 from translation components and complex rotation.

Source

pub fn from_isometry(isometry: Isometry<f64, Unit<Complex<f64>>, 2>) -> SE2

Create SE2 directly from an Isometry2.

Source

pub fn from_translation_so2( translation: Matrix<f64, Const<2>, Const<1>, ArrayStorage<f64, 2, 1>>, rotation: SO2, ) -> SE2

Create SE2 from Vector2 and SO2 components.

Source

pub fn translation( &self, ) -> Matrix<f64, Const<2>, Const<1>, ArrayStorage<f64, 2, 1>>

Get the translation part as a Vector2.

Source

pub fn rotation_complex(&self) -> Unit<Complex<f64>>

Get the rotation part as UnitComplex.

Source

pub fn rotation_angle(&self) -> f64

Get the rotation angle.

Source

pub fn rotation_so2(&self) -> SO2

Get the rotation part as SO2.

Source

pub fn isometry(&self) -> Isometry<f64, Unit<Complex<f64>>, 2>

Get as an Isometry2 (convenience method).

Source

pub fn matrix(&self) -> Matrix<f64, Const<3>, Const<3>, ArrayStorage<f64, 3, 3>>

Get the transformation matrix (3x3 homogeneous matrix).

Source

pub fn rotation_matrix( &self, ) -> Matrix<f64, Const<2>, Const<2>, ArrayStorage<f64, 2, 2>>

Get the rotation matrix (2x2).

Source

pub fn x(&self) -> f64

Get the x component of translation.

Source

pub fn y(&self) -> f64

Get the y component of translation.

Source

pub fn real(&self) -> f64

Get the real part of the complex rotation.

Source

pub fn imag(&self) -> f64

Get the imaginary part of the complex rotation.

Source

pub fn angle(&self) -> f64

Get the rotation angle in radians.

Trait Implementations§

Source§

impl Clone for SE2

Source§

fn clone(&self) -> SE2

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 Display for SE2

Source§

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

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

impl From<Matrix<f64, Dyn, Const<1>, VecStorage<f64, Dyn, Const<1>>>> for SE2

Source§

fn from(data: Matrix<f64, Dyn, Const<1>, VecStorage<f64, Dyn, Const<1>>>) -> SE2

Converts to this type from the input type.
Source§

impl LieGroup for SE2

Source§

fn inverse( &self, jacobian: Option<&mut <SE2 as LieGroup>::JacobianMatrix>, ) -> SE2

Get the inverse.

§Arguments
  • jacobian - Optional Jacobian matrix of the inverse wrt this.
§Notes

For SE(2): g^{-1} = [R^T, -R^T * t; 0, 1]

Source§

fn compose( &self, other: &SE2, jacobian_self: Option<&mut <SE2 as LieGroup>::JacobianMatrix>, jacobian_other: Option<&mut <SE2 as LieGroup>::JacobianMatrix>, ) -> SE2

Composition of this and another SE2 element.

Source§

fn log( &self, jacobian: Option<&mut <SE2 as LieGroup>::JacobianMatrix>, ) -> <SE2 as LieGroup>::TangentVector

Get the SE2 corresponding Lie algebra element in vector form.

Source§

fn vee(&self) -> <SE2 as LieGroup>::TangentVector

Vee operator: log(g)^∨.

Maps a group element g ∈ G to its tangent vector log(g)^∨ ∈ 𝔤. For SE(2), this is the same as log().

Source§

fn is_approx(&self, other: &SE2, tolerance: f64) -> bool

Check if the element is approximately equal to another element.

§Arguments
  • other - The other element to compare with
  • tolerance - The tolerance for the comparison
Source§

type TangentVector = SE2Tangent

The tangent space vector type
Source§

type JacobianMatrix = Matrix<f64, Const<3>, Const<3>, ArrayStorage<f64, 3, 3>>

The Jacobian matrix type
Source§

type LieAlgebra = Matrix<f64, Const<3>, Const<3>, ArrayStorage<f64, 3, 3>>

Associated Lie algebra type
Source§

fn act( &self, vector: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, jacobian_self: Option<&mut <SE2 as LieGroup>::JacobianMatrix>, jacobian_vector: Option<&mut Matrix<f64, Const<3>, Const<3>, ArrayStorage<f64, 3, 3>>>, ) -> Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>

Act on a vector v: g ⊙ v. Read more
Source§

fn adjoint(&self) -> <SE2 as LieGroup>::JacobianMatrix

Adjoint matrix Ad(g). Read more
Source§

fn random() -> SE2

Generate a random element (useful for testing and initialization).
Source§

fn jacobian_identity() -> <SE2 as LieGroup>::JacobianMatrix

Get the identity matrix for Jacobians. Read more
Source§

fn zero_jacobian() -> <SE2 as LieGroup>::JacobianMatrix

Get a zero Jacobian matrix. Read more
Source§

fn normalize(&mut self)

Normalize/project the element to the manifold. Read more
Source§

fn is_valid(&self, tolerance: f64) -> bool

Check if the element is approximately on the manifold.
Source§

fn right_plus( &self, tangent: &Self::TangentVector, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_tangent: Option<&mut Self::JacobianMatrix>, ) -> Self

Right plus operation: g ⊞ φ = g ∘ exp(φ^∧). Read more
Source§

fn right_minus( &self, other: &Self, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_other: Option<&mut Self::JacobianMatrix>, ) -> Self::TangentVector

Right minus operation: g₁ ⊟ g₂ = log(g₂⁻¹ ∘ g₁)^∨. Read more
Source§

fn left_plus( &self, tangent: &Self::TangentVector, jacobian_tangent: Option<&mut Self::JacobianMatrix>, jacobian_self: Option<&mut Self::JacobianMatrix>, ) -> Self

Left plus operation: φ ⊞ g = exp(φ^∧) ∘ g. Read more
Source§

fn left_minus( &self, other: &Self, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_other: Option<&mut Self::JacobianMatrix>, ) -> Self::TangentVector

Left minus operation: g₁ ⊟ g₂ = log(g₁ ∘ g₂⁻¹)^∨. Read more
Source§

fn plus( &self, tangent: &Self::TangentVector, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_tangent: Option<&mut Self::JacobianMatrix>, ) -> Self

Convenience method for right_plus. Equivalent to g ⊞ φ.
Source§

fn minus( &self, other: &Self, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_other: Option<&mut Self::JacobianMatrix>, ) -> Self::TangentVector

Convenience method for right_minus. Equivalent to g₁ ⊟ g₂.
Source§

fn between( &self, other: &Self, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_other: Option<&mut Self::JacobianMatrix>, ) -> Self

Compute g₁⁻¹ ∘ g₂ (relative transformation). Read more
Source§

fn tangent_dim(&self) -> usize

Get the dimension of the tangent space for this manifold element. Read more
Source§

impl PartialEq for SE2

Source§

fn eq(&self, other: &SE2) -> 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 Tangent<SE2> for SE2Tangent

Source§

const DIM: usize = 3

Dimension of the tangent space

Source§

fn exp(&self, jacobian: Option<&mut <SE2 as LieGroup>::JacobianMatrix>) -> SE2

Get the SE2 element.

Source§

fn right_jacobian(&self) -> <SE2 as LieGroup>::JacobianMatrix

Right Jacobian Jr.

Source§

fn left_jacobian(&self) -> <SE2 as LieGroup>::JacobianMatrix

Left Jacobian Jl.

Source§

fn right_jacobian_inv(&self) -> <SE2 as LieGroup>::JacobianMatrix

Inverse of right Jacobian Jr⁻¹.

Source§

fn left_jacobian_inv(&self) -> <SE2 as LieGroup>::JacobianMatrix

Inverse of left Jacobian Jl⁻¹.

Source§

fn hat(&self) -> <SE2 as LieGroup>::LieAlgebra

Hat operator: φ^∧ (vector to matrix).

Source§

fn zero() -> <SE2 as LieGroup>::TangentVector

Zero tangent vector.

Source§

fn random() -> <SE2 as LieGroup>::TangentVector

Random tangent vector (useful for testing).

Source§

fn is_zero(&self, tolerance: f64) -> bool

Check if the tangent vector is approximately zero.

Source§

fn normalize(&mut self)

Normalize the tangent vector to unit norm.

Source§

fn normalized(&self) -> <SE2 as LieGroup>::TangentVector

Return a unit tangent vector in the same direction.

Source§

fn small_adj(&self) -> <SE2 as LieGroup>::JacobianMatrix

Small adjoint matrix for SE(2).

For SE(2), the small adjoint involves the angular component.

Source§

fn lie_bracket(&self, other: &SE2Tangent) -> <SE2 as LieGroup>::TangentVector

Lie bracket for SE(2).

Computes the Lie bracket [this, other] = this.small_adj() * other.

Source§

fn is_approx(&self, other: &SE2Tangent, tolerance: f64) -> bool

Check if this tangent vector is approximately equal to another.

§Arguments
  • other - The other tangent vector to compare with
  • tolerance - The tolerance for the comparison
Source§

fn generator(&self, i: usize) -> <SE2 as LieGroup>::LieAlgebra

Get the ith generator of the SE(2) Lie algebra.

§Arguments
  • i - Index of the generator (0, 1, or 2 for SE(2))
§Returns

The generator matrix

Source§

fn is_dynamic() -> bool

Whether this tangent type has dynamic (runtime-determined) dimension. Read more
Source§

impl StructuralPartialEq for SE2

Auto Trait Implementations§

§

impl Freeze for SE2

§

impl RefUnwindSafe for SE2

§

impl Send for SE2

§

impl Sync for SE2

§

impl Unpin for SE2

§

impl UnsafeUnpin for SE2

§

impl UnwindSafe for SE2

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> ByRef<T> for T

Source§

fn by_ref(&self) -> &T

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> DistributionExt for T
where T: ?Sized,

Source§

fn rand<T>(&self, rng: &mut (impl Rng + ?Sized)) -> T
where Self: Distribution<T>,

Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T> Instrument for T

Source§

fn instrument(self, span: Span) -> Instrumented<Self>

Instruments this type with the provided Span, returning an Instrumented wrapper. Read more
Source§

fn in_current_span(self) -> Instrumented<Self>

Instruments this type with the current Span, returning an Instrumented wrapper. Read more
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> IntoEither for T

Source§

fn into_either(self, into_left: bool) -> Either<Self, Self>

Converts self into a Left variant of Either<Self, Self> if into_left is true. Converts self into a Right variant of Either<Self, Self> otherwise. Read more
Source§

fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
where F: FnOnce(&Self) -> bool,

Converts self into a Left variant of Either<Self, Self> if into_left(&self) returns true. Converts self into a Right variant of Either<Self, Self> otherwise. Read more
Source§

impl<T> Pointable for T

Source§

const ALIGN: usize

The alignment of pointer.
Source§

type Init = T

The type for initializers.
Source§

unsafe fn init(init: <T as Pointable>::Init) -> usize

Initializes a with the given initializer. Read more
Source§

unsafe fn deref<'a>(ptr: usize) -> &'a T

Dereferences the given pointer. Read more
Source§

unsafe fn deref_mut<'a>(ptr: usize) -> &'a mut T

Mutably dereferences the given pointer. Read more
Source§

unsafe fn drop(ptr: usize)

Drops the object pointed to by the given pointer. Read more
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<V, T> VZip<V> for T
where V: MultiLane<T>,

Source§

fn vzip(self) -> V

Source§

impl<T> WithSubscriber for T

Source§

fn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self>
where S: Into<Dispatch>,

Attaches the provided Subscriber to this type, returning a WithDispatch wrapper. Read more
Source§

fn with_current_subscriber(self) -> WithDispatch<Self>

Attaches the current default Subscriber to this type, returning a WithDispatch wrapper. Read more