Template Function pinocchio::computeJointJacobian

Function Documentation

template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl, typename ConfigVectorType, typename Matrix6Like>
inline void pinocchio::computeJointJacobian(const ModelTpl<Scalar, Options, JointCollectionTpl> &model, DataTpl<Scalar, Options, JointCollectionTpl> &data, const Eigen::MatrixBase<ConfigVectorType> &q, const JointIndex jointId, const Eigen::MatrixBase<Matrix6Like> &J)

Computes the Jacobian of a specific joint frame expressed in the local frame of the joint and store the result in the input argument J.

Remark

The result of this function is equivalent to call first computeJointJacobians(model,data,q) and then call getJointJacobian(model,data,jointId,LOCAL,J), but forwardKinematics is not fully computed. It is worth to call jacobian if you only need a single Jacobian for a specific joint. Otherwise, for several Jacobians, it is better to call computeJointJacobians(model,data,q) followed by getJointJacobian(model,data,jointId,LOCAL,J) for each Jacobian.

Template Parameters:
  • JointCollection – Collection of Joint types.

  • ConfigVectorType – Type of the joint configuration vector.

  • Matrix6xLike – Type of the matrix containing the joint Jacobian.

Parameters:
  • model[in] The model structure of the rigid body system.

  • data[in] The data structure of the rigid body system.

  • q[in] The joint configuration vector (dim model.nq).

  • jointId[in] The id of the joint refering to model.joints[jointId].

  • J[out] A reference on the Jacobian matrix where the results will be stored in (dim 6 x model.nv). You must fill J with zero elements, e.g. J.setZero().

Returns:

The Jacobian of the specific joint frame expressed in the local frame of the joint (matrix 6 x model.nv).