FancySafeBot 0.0.1
A safe robotics library
Loading...
Searching...
No Matches
Robot Kinematics

Functions to compute robot model kinematics. More...

Enumerations

enum class  fsb::ForwardKinematicsOption : uint8_t { ForwardKinematicsOption::POSE = 0 , ForwardKinematicsOption::POSE_VELOCITY = 1 , ForwardKinematicsOption::POSE_VELOCITY_ACCELERATION = 2 }
 Forward kinematics options. More...
 

Functions

void fsb::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.
 
JointSpacePosition fsb::joint_add_offset (const BodyTree &body_tree, const JointSpacePosition &joint_position, const JointSpace &joint_offset)
 Add offset to joint position.
 
JointSpace fsb::joint_difference (const BodyTree &body_tree, const JointSpacePosition &joint_position_a, const JointSpacePosition &joint_position_b)
 Get difference between joint positions.
 
void fsb::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.
 

Detailed Description

Functions to compute robot model kinematics.

Enumeration Type Documentation

◆ ForwardKinematicsOption

enum class fsb::ForwardKinematicsOption : uint8_t
strong

Forward kinematics options.

Enumerator
POSE 

Calculate Cartesian pose from joint position.

POSE_VELOCITY 

Calculate Cartesian pose and velocity from joint position and velocity.

POSE_VELOCITY_ACCELERATION 

Calculate Cartesian pose, velocity and acceleration from joint position, velocity, and acceleration.

Function Documentation

◆ body_com_kinematics()

void fsb::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.

Parameters
body_treeBody tree with link definitions including center of mass
body_cartesianComputed kinematics of bodies in tree
com_cartesianOutput motion of center of mass for all bodies in tree

◆ forward_kinematics()

void fsb::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.

Parameters
[in]body_treeBody tree with body and joint definitions
[in]joint_pvaJoint position, velocity and acceleration
[in]base_pvaBase pose, velocity and acceleration
[in]optCompute options
[out]body_cartesianOutput Cartesian pose, velocity and acceleration of all bodies

◆ joint_add_offset()

JointSpacePosition fsb::joint_add_offset ( const BodyTree body_tree,
const JointSpacePosition joint_position,
const JointSpace joint_offset 
)

Add offset to joint position.

Parameters
[in]body_treeBody tree with body and joint definitions
[in]joint_positionJoint position
[in]joint_offsetJoint offset
Returns
Joint position with offset added

◆ joint_difference()

JointSpace fsb::joint_difference ( const BodyTree body_tree,
const JointSpacePosition joint_position_a,
const JointSpacePosition joint_position_b 
)

Get difference between joint positions.

Parameters
[in]body_treeBody tree with body and joint definitions
[in]joint_position_aJoint position a
[in]joint_position_bJoint position b
Returns
Joint position difference