Template Function pinocchio::getJointVelocityDerivatives
Defined in File kinematics-derivatives.hxx
Function Documentation
-
template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl, typename Matrix6xOut1, typename Matrix6xOut2>
inline void pinocchio::getJointVelocityDerivatives(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> &v_partial_dv) Computes the partial derivaties of the spatial velocity of a given with respect to the joint configuration and velocity. You must first call computForwardKinematicsDerivatives before calling this function.
- Template Parameters:
JointCollection – Collection of Joint types.
Matrix6xOut1 – Matrix6x containing the partial derivatives with respect to the joint configuration vector.
Matrix6xOut2 – Matrix6x containing the partial derivatives with respect to the joint velocity vector.
- Parameters:
model – [in] The model structure of the rigid body system.
data – [in] The data structure of the rigid body system.
rf – [in] Reference frame in which the Jacobian is expressed.
v_partial_dq – [out] Partial derivative of the joint velociy w.r.t. \( q \).
v_partial_dv – [out] Partial derivative of the joint velociy w.r.t. \( \dot{q} \).