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

Jacobian matrix for robotics. More...

Classes

struct  fsb::Jacobian
 Jacobian matrix. More...
 
struct  fsb::JointMatrix
 Square matrix of size nxn for n joints. More...
 
struct  fsb::Hessian
 Hessian tensor. More...
 

Enumerations

enum class  fsb::JacobianError : uint8_t { JacobianError::SUCCESS , JacobianError::BODY_NOT_IN_TREE }
 Error values for Jacobian calculations. More...
 

Functions

size_t fsb::jacobian_index (const size_t row, const size_t col)
 Helper function for indexing jacobian matrix.
 
size_t fsb::joint_matrix_index (const size_t row, const size_t col, const size_t dofs)
 Helper function for indexing joint matrix.
 
MotionVector fsb::jacobian_multiply (const Jacobian &jacobian, const JointSpace &joint_motion, size_t dofs=MaxSize::dofs)
 Jacobian multiply joint velocity.
 
JointSpace fsb::jacobian_transpose_multiply (const Jacobian &jacobian, const MotionVector &cartesian_motion, size_t dofs=MaxSize::dofs)
 Jacobian transpose multiply cartesian motion.
 
JointMatrix fsb::jacobian_transpose_multiply_jacobian (const Jacobian &jacobian, const MotionVector &cartesian_weights, size_t dofs=MaxSize::dofs)
 Jacobian transpose multiply jacobian.
 
Jacobian fsb::jacobian_derivative (const Hessian &hessian, const JointSpace &joint_velocity, size_t dofs=MaxSize::dofs)
 Compute derivative of Jacobian matrix.
 
JacobianError fsb::calculate_jacobian (size_t body_index, const BodyTree &body_tree, const BodyCartesianPva &cartesian_pva, Jacobian &jacobian)
 Determine Jacobian matrix for a single body in tree.
 

Detailed Description

Jacobian matrix for robotics.

Enumeration Type Documentation

◆ JacobianError

enum class fsb::JacobianError : uint8_t
strong

Error values for Jacobian calculations.

Enumerator
SUCCESS 

No error.

BODY_NOT_IN_TREE 

Body index not found in tree.

Function Documentation

◆ calculate_jacobian()

JacobianError fsb::calculate_jacobian ( size_t  body_index,
const BodyTree body_tree,
const BodyCartesianPva cartesian_pva,
Jacobian jacobian 
)

Determine Jacobian matrix for a single body in tree.

Cartesian pose for all bodies should be determined by forward kinematics prior to calling this function.

Parameters
[in]body_indexBody index of Jacobian
[in]body_treeBody tree with body and joint data
[in]cartesian_pvaCartesian pose, velocity and acceleration data for all bodies
[out]jacobianJacobian matrix for body
Returns
Jacobian error code

◆ jacobian_derivative()

Jacobian fsb::jacobian_derivative ( const Hessian hessian,
const JointSpace joint_velocity,
size_t  dofs = MaxSize::dofs 
)

Compute derivative of Jacobian matrix.

Parameters
hessianHessian matrix
joint_velocityJoint velocity vector
dofsNumber of dofs (elements in joint velocity vector)
Returns
Jacobian derivative

◆ jacobian_index()

size_t fsb::jacobian_index ( const size_t  row,
const size_t  col 
)
inline

Helper function for indexing jacobian matrix.

Matrix is ordered column-major with 6 rows

Parameters
rowRow index
colColumn index
Returns
Jacobian index

◆ jacobian_multiply()

MotionVector fsb::jacobian_multiply ( const Jacobian jacobian,
const JointSpace joint_motion,
size_t  dofs = MaxSize::dofs 
)

Jacobian multiply joint velocity.

Parameters
jacobianJacobian matrix
joint_motionJoint velocity
dofsNumber of degrees of freedom (elements in joint velocity vector)
Returns
Cartesian velocity

◆ jacobian_transpose_multiply()

JointSpace fsb::jacobian_transpose_multiply ( const Jacobian jacobian,
const MotionVector cartesian_motion,
size_t  dofs = MaxSize::dofs 
)

Jacobian transpose multiply cartesian motion.

Parameters
jacobianJacobian matrix
cartesian_motionCartesian motion
dofsNumber of degrees of freedom (elements in joint motion vector)
Returns
Joint motion

◆ jacobian_transpose_multiply_jacobian()

JointMatrix fsb::jacobian_transpose_multiply_jacobian ( const Jacobian jacobian,
const MotionVector cartesian_weights,
size_t  dofs = MaxSize::dofs 
)

Jacobian transpose multiply jacobian.

\( J^T \cdot \text{diag}(w) J \)

Parameters
jacobianJacobian matrix
cartesian_weightsWeighted cartesian motion
dofs
Returns

◆ joint_matrix_index()

size_t fsb::joint_matrix_index ( const size_t  row,
const size_t  col,
const size_t  dofs 
)
inline

Helper function for indexing joint matrix.

Matrix is ordered column-major with n rows for n joints

Parameters
rowRow index
colColumn index
dofsNumber of degrees of freedom (elements in joint velocity vector)
Returns
Array index for joint matrix