Template Function pinocchio::computeFrameJacobian(const ModelTpl<Scalar, Options, JointCollectionTpl>&, DataTpl<Scalar, Options, JointCollectionTpl>&, const Eigen::MatrixBase<ConfigVectorType>&, const FrameIndex, const Eigen::MatrixBase<Matrix6xLike>&)

Function Documentation

template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl, typename ConfigVectorType, typename Matrix6xLike>
inline void pinocchio::computeFrameJacobian(const ModelTpl<Scalar, Options, JointCollectionTpl> &model, DataTpl<Scalar, Options, JointCollectionTpl> &data, const Eigen::MatrixBase<ConfigVectorType> &q, const FrameIndex frameId, const Eigen::MatrixBase<Matrix6xLike> &J)

Computes the Jacobian of a specific Frame expressed in the LOCAL frame coordinate system.

Remark

The result of this function is equivalent to call first computeJointJacobians(model,data,q), then updateFramePlacements(model,data) and then call getJointJacobian(model,data,jointId,LOCAL,J), but forwardKinematics and updateFramePlacements are not fully computed.

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).

  • frameId[in] The id of the Frame refering to model.frames[frameId].

  • 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 Frame expressed in the LOCAL frame coordinate system (matrix 6 x model.nv).