| Crates.io | k |
| lib.rs | k |
| version | 0.32.0 |
| created_at | 2017-08-03 13:57:56.936853+00 |
| updated_at | 2024-09-10 01:56:25.804242+00 |
| description | k is for kinematics |
| homepage | |
| repository | https://github.com/openrr/k |
| max_upload_size | |
| id | 26252 |
| size | 345,974 |
k: Kinematics library for rust-langk has below functionalities.
k uses nalgebra as math library.
See Document and examples/ for more details.
sudo apt install g++ cmake xorg-dev libglu1-mesa-dev
cargo run --release --example interactive_ik

Push below keys to move the end of the manipulator.
f: forwardb: backwardp: upn: downl: leftr: rightz: 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);
}
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.

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

OpenRR CommunityHere is a discord server for OpenRR users and developers.