Struct arcos_kdl::inverse_diff_kinematics::InverseDiffKinematicsSolver [−][src]
pub struct InverseDiffKinematicsSolver { /* fields omitted */ }
Expand description
Solver for inverse differential kinematcs. Calculate the joints rates from their current position and desired velocity at end-effector
chain
: chain to use by the solver
weight_task_space
: Weights in the task space
weight_joint_space
: How much to use each joint
jacobian
: Jacobian of the current chain
temp_qdots
: Temporal storage of qdot values
svd_result
: For calculating SVD
lambda
: parameter for tresholding singular values
epsilon
: (1e-300) allowed error in convergence of singular values
maxiter
: (150)Max allowed iteration for convergence of SV
n_joints
: Number of joints in the kinematic chain\
Implementations
Set the weight matrices for inverse kinematics
Set the Lambda parameter
Set parameters for convergence algorithm
Solver for inverse differential kinematics
This function uses the weighted damped least square inverse kinematics algorithm. From a Twist and current joint state, it calculates the velocities at each joint.
twist
: desired twist at the end effector
init_angles
: current state of each joint
Returns a result closure vector with the velocities at each joint.
Trait Implementations
Auto Trait Implementations
impl RefUnwindSafe for InverseDiffKinematicsSolver
impl Send for InverseDiffKinematicsSolver
impl Sync for InverseDiffKinematicsSolver
impl Unpin for InverseDiffKinematicsSolver
impl UnwindSafe for InverseDiffKinematicsSolver
Blanket Implementations
Mutably borrows from an owned value. Read more
The inverse inclusion map: attempts to construct self
from the equivalent element of its
superset. Read more
pub fn is_in_subset(&self) -> bool
pub fn is_in_subset(&self) -> bool
Checks if self
is actually part of its subset T
(and can be converted to it).
pub fn to_subset_unchecked(&self) -> SS
pub fn to_subset_unchecked(&self) -> SS
Use with care! Same as self.to_subset
but without any property checks. Always succeeds.
pub fn from_subset(element: &SS) -> SP
pub fn from_subset(element: &SS) -> SP
The inclusion map: converts self
to the equivalent element of its superset.