Expand description
§k
: Kinematics library for rust-lang
k
has below functionalities.
- Forward kinematics
- Inverse kinematics
- 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
Push below keys to move the end of the manipulator.
f
: forwardb
: backwardp
: upn
: downl
: leftr
: rightz
: 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 Node
s 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
Community
Here is a discord server for OpenRR
users and developers.
Re-exports§
pub use crate::joint::Joint;
pub use crate::joint::JointType;
pub use crate::link::Link;
pub use crate::node::Node;
pub use crate::node::NodeBuilder;
pub use nalgebra::Isometry3;
pub use nalgebra::RealField as Real;
pub use nalgebra::RealField;
pub use nalgebra::Translation3;
pub use nalgebra::UnitQuaternion;
pub use nalgebra::Vector3;
pub use simba::scalar::SubsetOf;
pub use simba::scalar::SupersetOf;
pub use nalgebra;
pub use simba;
Modules§
- Iterators to iterate descendants and ancestors
- Joint related structs
link
can be used to show the shape of the robot, or collision checking libraries.- graph structure for kinematic chain
- Load basic traits of
k
- Load URDF format and create
k::Chain
Macros§
- set parents easily
Structs§
- Kinematic Chain using
Node
- A bundle of flags determining which coordinates are constrained for a target
- Inverse Kinematics Solver using Jacobian matrix
- Kinematic chain without any branch.
Enums§
- The reason of joint error
Traits§
- IK solver
Functions§
- Calculate the center of mass of the chain
- Utility function to create nullspace function using reference joint positions. This is just an example to use nullspace.
- Calculate Jacobian of the serial chain (manipulator).