29 releases (15 breaking)

0.15.0 Jun 11, 2019
0.14.0 Mar 19, 2019
0.13.1 Jan 16, 2019
0.12.0 Dec 17, 2018
0.6.0 Nov 23, 2017

#59 in Algorithms

Download history 87/week @ 2019-02-26 29/week @ 2019-03-05 7/week @ 2019-03-12 75/week @ 2019-03-19 157/week @ 2019-03-26 68/week @ 2019-04-02 15/week @ 2019-04-09 15/week @ 2019-04-16 37/week @ 2019-04-23 5/week @ 2019-04-30 45/week @ 2019-05-07 70/week @ 2019-05-14 114/week @ 2019-05-21 64/week @ 2019-05-28 36/week @ 2019-06-04

235 downloads per month
Used in 2 crates

Apache-2.0

91KB
2K SLoC

k: Kinematics library for rust-lang Build Status crates.io

k has below functionalities.

  1. Forward kinematics
  2. Inverse kinematics
  3. URDF Loader

k uses nalgebra as math library.

See Document and examples/ for more details.

API is unstable.

Requirements to build examples

sudo apt install g++ cmake xorg-dev libglu1-mesa-dev

IK example with GUI

cargo run --release --example interactive_ik

ik_sample

Push below keys to move the end of the manipulator.

  • f: forward
  • b: backward
  • p: up
  • n: down
  • l: left
  • r: right
  • z: reset the manipulator state.

Create link tree from urdf and solve IK

extern crate k;

use k::prelude::*;

fn main() {
    // Load urdf file
    let chain = k::Chain::<f32>::from_urdf_file("urdf/sample.urdf").unwrap();
    println!("chain: {}", chain);

    // Set initial joint angles
    let angles = vec![0.2, 0.2, 0.0, -1.0, 0.0, 0.0, 0.2, 0.2, 0.0, -1.0, 0.0, 0.0];

    chain.set_joint_positions(&angles).unwrap();
    println!("initial angles={:?}", chain.joint_positions());

    let target_link = chain.find("l_wrist_pitch").unwrap();

    // Get the transform of the end of the manipulator (forward kinematics)
    chain.update_transforms();
    let mut target = target_link.world_transform().unwrap();

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

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

    // Create a set of joints from end joint
    let arm = k::SerialChain::from_end(target_link);
    // solve and move the manipulator angles
    solver.solve(&arm, &target).unwrap();
    println!("solved angles={:?}", chain.joint_positions());

    chain.update_transforms();
    let solved_pose = target_link.world_transform().unwrap();
    println!("solved target pos = {}", solved_pose.translation);
}

Dependencies

~7.5MB
~139K SLoC