2#ifndef FSB_KINEMATICS_H
3#define FSB_KINEMATICS_H
7#include "fsb_body_tree.h"
51 const BodyTree& body_tree,
const JointPva& joint_pva,
const CartesianPva& base_pva,
63 const BodyTree& body_tree,
const JointSpacePosition& joint_position,
const JointSpace& joint_offset);
74 const BodyTree& body_tree,
const JointSpacePosition& joint_position_a,
const JointSpacePosition& joint_position_b);
84 const BodyTree& body_tree,
const BodyCartesianPva& body_cartesian,
85 BodyCartesianPva& com_cartesian);
JointSpace joint_difference(const BodyTree &body_tree, const JointSpacePosition &joint_position_a, const JointSpacePosition &joint_position_b)
Get difference between joint positions.
Definition fsb_kinematics.cpp:170
void body_com_kinematics(const BodyTree &body_tree, const BodyCartesianPva &body_cartesian, BodyCartesianPva &com_cartesian)
Compute motion of center of mass for all bodies in tree.
Definition fsb_kinematics.cpp:63
void forward_kinematics(const BodyTree &body_tree, const JointPva &joint_pva, const CartesianPva &base_pva, ForwardKinematicsOption opt, BodyCartesianPva &body_cartesian)
Compute forward kinematics for all bodies in tree.
Definition fsb_kinematics.cpp:38
JointSpacePosition joint_add_offset(const BodyTree &body_tree, const JointSpacePosition &joint_position, const JointSpace &joint_offset)
Add offset to joint position.
Definition fsb_kinematics.cpp:81
ForwardKinematicsOption
Forward kinematics options.
Definition fsb_kinematics.h:25
@ POSE_VELOCITY
Calculate Cartesian pose and velocity from joint position and velocity.
@ POSE
Calculate Cartesian pose from joint position.
@ POSE_VELOCITY_ACCELERATION
Calculate Cartesian pose, velocity and acceleration from joint position, velocity,...