[][src]Struct k::JacobianIKSolver

pub struct JacobianIKSolver<T: Real> {
    pub allowable_target_distance: T,
    pub allowable_target_angle: T,
    pub jacobian_multiplier: T,
    pub num_max_try: usize,
}

Inverse Kinematics Solver using Jacobian matrix

Fields

allowable_target_distance: T

If the distance is smaller than this value, it is reached.

allowable_target_angle: T

If the angle distance is smaller than this value, it is reached.

jacobian_multiplier: T

multiplier for jacobian

num_max_try: usize

How many times the joints are tried to be moved

Methods

impl<T> JacobianIKSolver<T> where
    T: Real
[src]

pub fn new(
    allowable_target_distance: T,
    allowable_target_angle: T,
    jacobian_multiplier: T,
    num_max_try: usize
) -> JacobianIKSolver<T>
[src]

Create instance of JacobianIKSolver.

JacobianIKSolverBuilder is available instead of calling this new method.

Examples

let solver = k::JacobianIKSolver::new(0.01, 0.01, 0.5, 100);

Trait Implementations

impl<T> InverseKinematicsSolver<T> for JacobianIKSolver<T> where
    T: Real
[src]

fn solve(
    &self,
    arm: &SerialChain<T>,
    target_pose: &Isometry3<T>
) -> Result<(), IKError>
[src]

Set joint positions of arm to reach the target_pose

Examples

use k::prelude::*;

let chain = k::Chain::<f32>::from_urdf_file("urdf/sample.urdf").unwrap();
// Create sub-`Chain` to make it easy to use inverse kinematics
let target_joint_name = "r_wrist_pitch";
let r_wrist = chain.find(target_joint_name).unwrap();
let mut arm = k::SerialChain::from_end(r_wrist);
println!("arm: {}", arm);

// Set joint positions of `arm`
let positions = vec![0.1, 0.2, 0.0, -0.5, 0.0, -0.3];
arm.set_joint_positions(&positions).unwrap();
println!("initial positions={:?}", arm.joint_positions());

// Get the transform of the end of the manipulator (forward kinematics)
let mut target = arm.update_transforms().last().unwrap().clone();

println!("initial target pos = {}", target.translation);
println!("move x: -0.1");
target.translation.vector.x -= 0.1;

// Create IK solver with default settings
let solver = k::JacobianIKSolver::default();

// solve and move the manipulator positions
solver.solve(&arm, &target).unwrap();
println!("solved positions={:?}", arm.joint_positions());

impl<T> Default for JacobianIKSolver<T> where
    T: Real
[src]

impl<T: Clone + Real> Clone for JacobianIKSolver<T>
[src]

fn clone_from(&mut self, source: &Self)
1.0.0
[src]

Performs copy-assignment from source. Read more

impl<T: Debug + Real> Debug for JacobianIKSolver<T>
[src]

Auto Trait Implementations

impl<T> Send for JacobianIKSolver<T>

impl<T> Sync for JacobianIKSolver<T>

Blanket Implementations

impl<T> From for T
[src]

impl<T, U> Into for T where
    U: From<T>, 
[src]

impl<T> ToOwned for T where
    T: Clone
[src]

type Owned = T

impl<T, U> TryFrom for T where
    T: From<U>, 
[src]

type Error = !

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

The type returned in the event of a conversion error.

impl<T> Borrow for T where
    T: ?Sized
[src]

impl<T> BorrowMut for T where
    T: ?Sized
[src]

impl<T, U> TryInto for T where
    U: TryFrom<T>, 
[src]

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

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

The type returned in the event of a conversion error.

impl<T> Any for T where
    T: 'static + ?Sized
[src]

impl<T> Same for T

type Output = T

Should always be Self

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