Struct arcos_kdl::svd_eigen::SvdResult[][src]

pub struct SvdResult {
    pub u_matrix: DMatrix<f64>,
    pub s_vector: DVector<f64>,
    pub v_matrix: DMatrix<f64>,
    // some fields omitted
}
Expand description

Struct for storing SVD results.

This struct Implements the Special algorithm for SVD used in Weighted damped least square kinematics.

Fields

u_matrix: DMatrix<f64>

Matrix holding left singular vectors

s_vector: DVector<f64>

Vector holding singular values

v_matrix: DMatrix<f64>

Matrix holding right singular vectors

Implementations

Create a default empty SvdResult

Copy a Jacobian to the matrix holding the left singular vectors

Reduction to bidiagonal form using the Householder Rotations method

Store the right singular vectors in its matrix (before convergence iterations)

Store the left singular vectors in its matrix (before convergence iterations)

Find a diagonal matrix with the final singular values using an iterative Algorithm. Any changes in singular values order or magnitud is also reflected in singular vectors

SVD computation with damped least squares using huseholder rotations

Trait Implementations

Returns a copy of the value. Read more

Performs copy-assignment from source. Read more

Formats the value using the given formatter. Read more

Auto Trait Implementations

Blanket Implementations

Gets the TypeId of self. Read more

Immutably borrows from an owned value. Read more

Mutably borrows from an owned value. Read more

Performs the conversion.

Performs the conversion.

Should always be Self

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

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

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

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

The resulting type after obtaining ownership.

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

🔬 This is a nightly-only experimental API. (toowned_clone_into)

recently added

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

The type returned in the event of a conversion error.

Performs the conversion.

The type returned in the event of a conversion error.

Performs the conversion.