55 releases (32 breaking)

0.32.0 Sep 10, 2024
0.31.0 Nov 8, 2023
0.30.0 Apr 28, 2023
0.29.1 Dec 7, 2022
0.6.0 Nov 23, 2017

#84 in Algorithms

Download history 174/week @ 2024-07-26 157/week @ 2024-08-02 76/week @ 2024-08-09 74/week @ 2024-08-16 82/week @ 2024-08-23 118/week @ 2024-08-30 869/week @ 2024-09-06 1112/week @ 2024-09-13 517/week @ 2024-09-20 464/week @ 2024-09-27 200/week @ 2024-10-04 160/week @ 2024-10-11 162/week @ 2024-10-18 106/week @ 2024-10-25 247/week @ 2024-11-01 1550/week @ 2024-11-08

2,107 downloads per month
Used in 11 crates (8 directly)

Apache-2.0

155KB
2.5K SLoC

k: Kinematics library for rust-lang

Build Status crates.io codecov docs discord

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.

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.
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

OpenRR Community

Here is a discord server for OpenRR users and developers.

Dependencies

~9MB
~169K SLoC