Struct arcos_kdl::chains::Chain[][src]

pub struct Chain { /* fields omitted */ }
Expand description

Implementation of kinematic chains

segments: a vector with the segments of the chain
num_joints: number of joints (segments with movable joints)
num_ind_joints: Number of joints with independent movement
num_unlocked_joints: Num of enabled/unlocked joints
locked_joints: vector with bools indicating if the joint is locked
coupling_matrix: matrix correlating the joints with their couples\

Implementations

Default empty chain

Returns the total number of segments

Returns the number of segments with moveable joints

Returns the number of Independent moveable joints

Returns the coupling matrix

Add a new semgment at the end of the kinematic chain
(Where the end is where the end-effector would be)

Append an entire chain at the end of this chain

Get the segment at the index-th position

Get the vector with lock information

Set coupling information, locked joints and coupling relations

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

Deserialize this value from the given Serde deserializer. Read more

This method tests for self and other values to be equal, and is used by ==. Read more

This method tests for !=.

Serialize this value into the given Serde serializer. 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.