Template Function pinocchio::getPointVelocityDerivatives
Defined in File kinematics-derivatives.hxx
Function Documentation
-
template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl, typename Matrix3xOut1, typename Matrix3xOut2>
void pinocchio::getPointVelocityDerivatives(const ModelTpl<Scalar, Options, JointCollectionTpl> &model, const DataTpl<Scalar, Options, JointCollectionTpl> &data, const Model::JointIndex joint_id, const SE3Tpl<Scalar, Options> &placement, const ReferenceFrame rf, const Eigen::MatrixBase<Matrix3xOut1> &v_point_partial_dq, const Eigen::MatrixBase<Matrix3xOut2> &v_point_partial_dv) Computes the partial derivatives of the velocity of a point given by its placement information w.r.t. the joint frame. You must first call computForwardKinematicsDerivatives before calling this function.
- Template Parameters:
JointCollection – Collection of Joint types.
Matrix3xOut1 – Matrix3x containing the partial derivatives of the spatial velocity with respect to the joint configuration vector.
Matrix3xOut2 – Matrix3x containing the partial derivatives of the spatial velocity 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.
joint_id – [in] Index of the joint in model.
placement – [in] Relative placement of the point w.r.t. the joint frame.
rf – [in] Reference frame in which the Jacobian is expressed (either LOCAL or LOCAL_WORLD_ALIGNED).
v_point_partial_dq – [out] Partial derivative of the point velocity w.r.t.
.v_point_partial_dv – [out] Partial derivative of the point velociy w.r.t.
.