Jacobian matrix for robotics.
More...
|
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.
|
|
Jacobian matrix for robotics.
◆ JacobianError
Error values for Jacobian calculations.
Enumerator |
---|
SUCCESS | No error.
|
BODY_NOT_IN_TREE | Body index not found in tree.
|
◆ calculate_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_index | Body index of Jacobian |
[in] | body_tree | Body tree with body and joint data |
[in] | cartesian_pva | Cartesian pose, velocity and acceleration data for all bodies |
[out] | jacobian | Jacobian matrix for body |
- Returns
- Jacobian error code
◆ jacobian_derivative()
Compute derivative of Jacobian matrix.
- Parameters
-
hessian | Hessian matrix |
joint_velocity | Joint velocity vector |
dofs | Number 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
-
row | Row index |
col | Column index |
- Returns
- Jacobian index
◆ jacobian_multiply()
Jacobian multiply joint velocity.
- Parameters
-
jacobian | Jacobian matrix |
joint_motion | Joint velocity |
dofs | Number of degrees of freedom (elements in joint velocity vector) |
- Returns
- Cartesian velocity
◆ jacobian_transpose_multiply()
Jacobian transpose multiply cartesian motion.
- Parameters
-
jacobian | Jacobian matrix |
cartesian_motion | Cartesian motion |
dofs | Number of degrees of freedom (elements in joint motion vector) |
- Returns
- Joint motion
◆ jacobian_transpose_multiply_jacobian()
Jacobian transpose multiply jacobian.
\( J^T \cdot \text{diag}(w) J \)
- Parameters
-
jacobian | Jacobian matrix |
cartesian_weights | Weighted 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
-
row | Row index |
col | Column index |
dofs | Number of degrees of freedom (elements in joint velocity vector) |
- Returns
- Array index for joint matrix