Struct gear::JointPathPlannerWithIK [] [src]

pub struct JointPathPlannerWithIK<K> where
    K: InverseKinematicsSolver<f64>, 
{ pub path_planner: DefaultJointPathPlanner<f64>, pub ik_solver: K, }

Joint path planner which supports inverse kinematics

Fields

Joint Path Planner to be used to find collision free path

Currently, JointPathPlanner<k::RcKinematicChain<f64>, k::LinkTree<f64>> is used.

Inverse kinematics solver to find the goal joint angles

Methods

impl<K> JointPathPlannerWithIK<K> where
    K: InverseKinematicsSolver<f64>, 
[src]

[src]

Create instance from JointPathPlannerBuilder and InverseKinematicsSolver

Example

// Create path planner with loading urdf file and set end link name
let planner = gear::JointPathPlannerBuilder::try_from_urdf_file("sample.urdf", "l_wrist2")
    .unwrap()
    .collision_check_margin(0.01)
    .finalize();
// Create inverse kinematics solver
let solver = gear::JacobianIKSolverBuilder::<f64>::new()
    .num_max_try(1000)
    .allowable_target_distance(0.01)
    .move_epsilon(0.00001)
    .jacobian_move_epsilon(0.001)
    .finalize();
// Create path planner with IK solver
let _planner = gear::JointPathPlannerWithIK::new(planner, solver);

[src]

[src]

[src]

[src]

Trait Implementations

impl<K> JointContainer<f64> for JointPathPlannerWithIK<K> where
    K: InverseKinematicsSolver<f64>, 
[src]

[src]

Set the angles of the joints Read more

[src]

Get the angles of the joints

[src]

Get the limits of the joints, if it exists.

[src]

Get the all names of the joints

impl<K> LinkContainer<f64> for JointPathPlannerWithIK<K> where
    K: InverseKinematicsSolver<f64>, 
[src]

Calculate the transforms of all of the links

Get the names of the links