Trait k::InverseKinematicsSolver[][src]

pub trait InverseKinematicsSolver<T> where
    T: RealField
{ fn solve_with_constraints(
        &self,
        arm: &SerialChain<T>,
        target_pose: &Isometry3<T>,
        constraints: &Constraints
    ) -> Result<(), Error>; fn solve(
        &self,
        arm: &SerialChain<T>,
        target_pose: &Isometry3<T>
    ) -> Result<(), Error> { ... } }

IK solver

Required methods

fn solve_with_constraints(
    &self,
    arm: &SerialChain<T>,
    target_pose: &Isometry3<T>,
    constraints: &Constraints
) -> Result<(), Error>
[src]

Move the end transform of the arm to target_pose with constraints

Loading content...

Provided methods

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

Move the end transform of the arm to target_pose

Loading content...

Implementors

impl<T> InverseKinematicsSolver<T> for JacobianIkSolver<T> where
    T: RealField + SubsetOf<f64>, 
[src]

fn solve(
    &self,
    arm: &SerialChain<T>,
    target_pose: &Isometry3<T>
) -> Result<(), Error>
[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());

fn solve_with_constraints(
    &self,
    arm: &SerialChain<T>,
    target_pose: &Isometry3<T>,
    constraints: &Constraints
) -> Result<(), Error>
[src]

Set joint positions of arm to reach the target_pose with constraints

If you want to loose the constraints, use this method. For example, ignoring rotation with an axis. It enables to use the arms which has less than six DoF.

Example

use k::prelude::*;

let chain = k::Chain::<f32>::from_urdf_file("urdf/sample.urdf").unwrap();
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);
let positions = vec![0.1, 0.2, 0.0, -0.5, 0.0, -0.3];
arm.set_joint_positions(&positions).unwrap();
let mut target = arm.update_transforms().last().unwrap().clone();
target.translation.vector.x -= 0.1;
let solver = k::JacobianIkSolver::default();

let mut constraints = k::Constraints::default();
constraints.rotation_x = false;
constraints.rotation_z = false;
solver
   .solve_with_constraints(&arm, &target, &constraints)
   .unwrap_or_else(|err| {
       println!("Err: {}", err);
   });
Loading content...