46 releases (25 breaking)

0.25.0 Jun 30, 2021
0.23.0 Mar 3, 2021
0.21.2 Dec 24, 2020
0.20.0 Nov 30, 2020
0.6.0 Nov 23, 2017

#23 in Algorithms

Download history 403/week @ 2021-06-22 480/week @ 2021-06-29 551/week @ 2021-07-06 654/week @ 2021-07-13 747/week @ 2021-07-20 553/week @ 2021-07-27 668/week @ 2021-08-03 526/week @ 2021-08-10 364/week @ 2021-08-17 504/week @ 2021-08-24 296/week @ 2021-08-31 358/week @ 2021-09-07 447/week @ 2021-09-14 742/week @ 2021-09-21 488/week @ 2021-09-28 718/week @ 2021-10-05

2,790 downloads per month
Used in 12 crates (8 directly)

Apache-2.0

145KB
2K SLoC

k: Kinematics library for rust-lang

Build and Test crates.io codecov docs

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

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);
}

Structure of API

Top level interface is Chain struct. It contains Nodes and they have the relations between nodes (parent/children). Actual data (joint angle(position), transform between nodes) is stored in Joint object inside nodes.

ik_sample

You can get local/world transform of nodes. See below figure to understand what is the node's local_transform() and world_transform().

ik_sample

Dependencies

~5.5MB
~131K SLoC