Namespaces | Functions
frames-derivatives.hpp File Reference
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/multibody/data.hpp"
#include "pinocchio/algorithm/frames-derivatives.hxx"
Include dependency graph for frames-derivatives.hpp:

Go to the source code of this file.

Namespaces

 pinocchio
 Main pinocchio namespace.
 

Functions

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xOut1 , typename Matrix6xOut2 , typename Matrix6xOut3 , typename Matrix6xOut4 >
void pinocchio::getFrameAccelerationDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, 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 derivatives of the frame acceleration quantity with respect to q, v and a. You must first call pinocchio::computeForwardKinematicsDerivatives to compute all the required quantities. 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. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xOut1 , typename Matrix6xOut2 , typename Matrix6xOut3 , typename Matrix6xOut4 , typename Matrix6xOut5 >
void pinocchio::getFrameAccelerationDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &v_partial_dv, const Eigen::MatrixBase< Matrix6xOut3 > &a_partial_dq, const Eigen::MatrixBase< Matrix6xOut4 > &a_partial_dv, const Eigen::MatrixBase< Matrix6xOut5 > &a_partial_da)
 Computes the partial derivatives of the frame acceleration quantity with respect to q, v and a. You must first call pinocchio::computeForwardKinematicsDerivatives to compute all the required quantities. 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. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xOut1 , typename Matrix6xOut2 >
void pinocchio::getFrameVelocityDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &v_partial_dv)
 Computes the partial derivatives of the frame velocity quantity with respect to q and v. You must first call pinocchio::computeForwardKinematicsDerivatives to compute all the required quantities. More...
 


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:05