Template Function pinocchio::getJointAccelerationDerivatives(const ModelTpl<Scalar, Options, JointCollectionTpl>&, const DataTpl<Scalar, Options, JointCollectionTpl>&, const Model::JointIndex, const ReferenceFrame, const Eigen::MatrixBase<Matrix6xOut1>&, const Eigen::MatrixBase<Matrix6xOut2>&, const Eigen::MatrixBase<Matrix6xOut3>&, const Eigen::MatrixBase<Matrix6xOut4>&)

Function Documentation

template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl, typename Matrix6xOut1, typename Matrix6xOut2, typename Matrix6xOut3, typename Matrix6xOut4>
inline void pinocchio::getJointAccelerationDerivatives(const ModelTpl<Scalar, Options, JointCollectionTpl> &model, const DataTpl<Scalar, Options, JointCollectionTpl> &data, const Model::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase<Matrix6xOut1> &v_partial_dq, const Eigen::MatrixBase<Matrix6xOut2> &a_partial_dq, const Eigen::MatrixBase<Matrix6xOut3> &a_partial_dv, const Eigen::MatrixBase<Matrix6xOut4> &a_partial_da)

Computes the partial derivaties of the spatial acceleration of a given with respect to the joint configuration, velocity and acceleration. You must first call computForwardKinematicsDerivatives before calling this function. It is important to notice that a direct outcome (for free) of this algo is v_partial_dq and v_partial_dv which is equal to a_partial_da.

Template Parameters:
  • JointCollection – Collection of Joint types.

  • Matrix6xOut1 – Matrix6x containing the partial derivatives of the spatial velocity with respect to the joint configuration vector.

  • Matrix6xOut2 – Matrix6x containing the partial derivatives of the spatial acceleration with respect to the joint configuration vector.

  • Matrix6xOut3 – Matrix6x containing the partial derivatives of the spatial acceleration with respect to the joint velocity vector.

  • Matrix6xOut4 – Matrix6x containing the partial derivatives of the spatial acceleration with respect to the joint acceleration vector.

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

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

  • jointId[in] Index of the joint in model.

  • rf[in] Reference frame in which the Jacobian is expressed.

  • v_partial_dq[out] Partial derivative of the joint spatial velocity w.r.t. \( q \).

  • a_partial_dq[out] Partial derivative of the joint spatial acceleration w.r.t. \( q \).

  • a_partial_dq[out] Partial derivative of the joint spatial acceleration w.r.t. \( \dot{q} \).

  • a_partial_dq[out] Partial derivative of the joint spatial acceleration w.r.t. \( \ddot{q} \).