[][src]Struct k::Chain

pub struct Chain<T: Real> { /* fields omitted */ }

Kinematic Chain using Node

Examples

#[macro_use]
use k::*;
use k::prelude::*;

let l0 = JointBuilder::new()
    .name("joint_pitch0")
    .translation(Translation3::new(0.0, 0.0, 0.1))
    .joint_type(JointType::Rotational{axis: Vector3::y_axis()})
    .into_node();
let l1 = JointBuilder::new()
    .name("joint_pitch1")
    .translation(Translation3::new(0.0, 0.0, 0.5))
    .joint_type(JointType::Rotational{axis: Vector3::y_axis()})
    .into_node();
let l2 = JointBuilder::new()
    .name("hand")
    .translation(Translation3::new(0.0, 0.0, 0.5))
    .joint_type(JointType::Fixed)
    .into_node();

// Sequential joints structure
connect![l0 => l1 => l2];

let mut tree = Chain::from_root(l0);
assert_eq!(tree.dof(), 2);

// Get joint positions
let positions = tree.joint_positions();
assert_eq!(positions.len(), 2);
assert_eq!(positions[0], 0.0);
assert_eq!(positions[1], 0.0);

// Get the initial joint transforms
let transforms = tree.update_transforms();
assert_eq!(transforms.len(), 3);
assert_eq!(transforms[0].translation.vector.z, 0.1);
assert_eq!(transforms[1].translation.vector.z, 0.6);
assert_eq!(transforms[2].translation.vector.z, 1.1);
for t in transforms {
    println!("before: {}", t);
}

// Set joint positions
tree.set_joint_positions(&vec![1.0, 2.0]).unwrap();
let positions = tree.joint_positions();
assert_eq!(positions[0], 1.0);
assert_eq!(positions[1], 2.0);

// Get the result of forward kinematics
let transforms = tree.update_transforms();
assert_eq!(transforms.len(), 3);
for t in transforms {
    println!("after: {}", t);
}

Methods

impl<T: Real> Chain<T>
[src]

pub fn from_root(root_joint: Node<T>) -> Self
[src]

Create Chain from root joint

Examples

use k;

let l0 = k::JointBuilder::new().into_node();
let l1 = k::JointBuilder::new().into_node();
l1.set_parent(&l0);
let tree = k::Chain::<f32>::from_root(l0);

pub fn from_end(end_joint: &Node<T>) -> Chain<T>
[src]

Create Chain from end joint. It has any branches.

Do not discard root joint before create Chain. If you want to get Chain, unwrap() this, it is safe.

Examples

use k::*;

fn create_tree_from_end() -> Chain<f64> {
  let l0 = Node::new(Joint::new("fixed0", JointType::Fixed));
  let l1 = Node::new(Joint::new("fixed1", JointType::Fixed));
  l1.set_parent(&l0);
  Chain::from_end(&l1) // ok, because root is stored in `Chain`
}

let tree = create_tree_from_end(); // no problem

pub fn iter(
    &self
) -> impl Iterator<Item = &Node<T>>
[src]

Iterate for all joint nodes

The order is from parent to children. You can assume that parent is already iterated.

Examples

use k::*;

let l0 = Node::new(Joint::new("fixed0", JointType::Fixed));
let l1 = Node::new(Joint::new("fixed1", JointType::Fixed));
l1.set_parent(&l0);
let tree = Chain::<f64>::from_root(l0);
let names = tree.iter().map(|node| node.joint().name.to_owned()).collect::<Vec<_>>();
assert_eq!(names.len(), 2);
assert_eq!(names[0], "fixed0");
assert_eq!(names[1], "fixed1");

pub fn iter_joints(
    &self
) -> impl Iterator<Item = JointRefGuard<T>>
[src]

Iterate for movable joints

Fixed joints are ignored. If you want to manipulate on Fixed, use iter() instead of iter_joints()

Iterate for links

pub fn dof(&self) -> usize
[src]

Calculate the degree of freedom

Examples

use k::*;
let l0 = JointBuilder::new()
    .joint_type(JointType::Fixed)
    .finalize()
    .into();
let l1 : Node<f64> = JointBuilder::new()
    .joint_type(JointType::Rotational{axis: Vector3::y_axis()})
    .finalize()
    .into();
l1.set_parent(&l0);
let tree = Chain::from_root(l0);
assert_eq!(tree.dof(), 1);

pub fn find(&self, joint_name: &str) -> Option<&Node<T>>
[src]

Find the joint by name

Examples

use k::*;

let l0 = Node::new(JointBuilder::new()
    .name("fixed")
    .finalize());
let l1 = Node::new(JointBuilder::new()
    .name("pitch1")
    .translation(Translation3::new(0.0, 0.1, 0.0))
    .joint_type(JointType::Rotational{axis: Vector3::y_axis()})
    .finalize());
l1.set_parent(&l0);
let tree = Chain::from_root(l0);
let j = tree.find("pitch1").unwrap();
j.set_joint_position(0.5).unwrap();
assert_eq!(j.joint_position().unwrap(), 0.5);

pub fn joint_positions(&self) -> Vec<T>
[src]

Get the positions of the joints

FixedJoint is ignored. the length is the same with dof()

pub fn set_joint_positions(&self, positions_vec: &[T]) -> Result<(), JointError>
[src]

Set the positions of the joints

FixedJoints are ignored. the input number must be equal with dof()

pub fn set_joint_positions_unchecked(&self, positions_vec: &[T])
[src]

Fast, but without check, dangerous set_joint_positions

pub fn update_transforms(&self) -> Vec<Isometry3<T>>
[src]

Update world_transform() of the joints

pub fn update_velocities(&self) -> Vec<Velocity<T>>
[src]

Update world_velocity() of the joints

Update transforms of the links

impl<T> Chain<T> where
    T: Real
[src]

pub fn from_urdf_file<P>(path: P) -> Result<Self, UrdfError> where
    P: AsRef<Path>, 
[src]

Trait Implementations

impl<'a, T> From<&'a Robot> for Chain<T> where
    T: Real
[src]

impl<T> From<Robot> for Chain<T> where
    T: Real
[src]

impl<T: Debug + Real> Debug for Chain<T>
[src]

impl<T: Real> Display for Chain<T>
[src]

Auto Trait Implementations

impl<T> !Send for Chain<T>

impl<T> !Sync for Chain<T>

Blanket Implementations

impl<T> From for T
[src]

impl<T, U> Into for T where
    U: From<T>, 
[src]

impl<T> ToString for T where
    T: Display + ?Sized
[src]

impl<T, U> TryFrom for T where
    T: From<U>, 
[src]

type Error = !

🔬 This is a nightly-only experimental API. (try_from)

The type returned in the event of a conversion error.

impl<T> Borrow for T where
    T: ?Sized
[src]

impl<T> BorrowMut for T where
    T: ?Sized
[src]

impl<T, U> TryInto for T where
    U: TryFrom<T>, 
[src]

type Error = <U as TryFrom<T>>::Error

🔬 This is a nightly-only experimental API. (try_from)

The type returned in the event of a conversion error.

impl<T> Any for T where
    T: 'static + ?Sized
[src]

impl<T> Same for T

type Output = T

Should always be Self

impl<SS, SP> SupersetOf for SP where
    SS: SubsetOf<SP>,