Template Function pinocchio::getPointClassicAccelerationDerivatives(const ModelTpl<Scalar, Options, JointCollectionTpl>&, const DataTpl<Scalar, Options, JointCollectionTpl>&, const Model::JointIndex, const SE3Tpl<Scalar, Options>&, const ReferenceFrame, const Eigen::MatrixBase<Matrix3xOut1>&, const Eigen::MatrixBase<Matrix3xOut2>&, const Eigen::MatrixBase<Matrix3xOut3>&, const Eigen::MatrixBase<Matrix3xOut4>&, const Eigen::MatrixBase<Matrix3xOut5>&)
- Defined in File kinematics-derivatives.hxx 
Function Documentation
- 
template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl, typename Matrix3xOut1, typename Matrix3xOut2, typename Matrix3xOut3, typename Matrix3xOut4, typename Matrix3xOut5>
 void pinocchio::getPointClassicAccelerationDerivatives(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, const Eigen::MatrixBase<Matrix3xOut3> &a_point_partial_dq, const Eigen::MatrixBase<Matrix3xOut4> &a_point_partial_dv, const Eigen::MatrixBase<Matrix3xOut5> &a_point_partial_da)
- Computes the partial derivaties of the classic acceleration of a point given by its placement information w.r.t. to the joint frame. 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_point_partial_dq and v_point_partial_dv.. - 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. 
- Matrix3xOut3 – Matrix3x containing the partial derivatives of the spatial acceleration with respect to the joint configuration vector. 
- Matrix3xOut4 – Matrix3x containing the partial derivatives of the spatial acceleration with respect to the joint velocity vector. 
- Matrix3xOut5 – Matrix3x 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. 
- 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. \( q \). 
- v_point_partial_dv – [out] Partial derivative of the point velociy w.r.t. \( v \). 
- a_point_partial_dq – [out] Partial derivative of the point classic acceleration w.r.t. \( q \). 
- a_point_partial_dv – [out] Partial derivative of the point classic acceleration w.r.t. \( v \). 
- a_point_partial_da – [out] Partial derivative of the point classic acceleration w.r.t. \( \dot{v} \).