4 #ifndef __pinocchio_algorithm_rnea_second_order_derivatives_hpp__ 5 #define __pinocchio_algorithm_rnea_second_order_derivatives_hpp__ 7 #include "pinocchio/container/aligned-vector.hpp" 8 #include "pinocchio/multibody/data.hpp" 9 #include "pinocchio/multibody/model.hpp" 71 template <
typename,
int>
class JointCollectionTpl,
72 typename ConfigVectorType,
typename TangentVectorType1,
73 typename TangentVectorType2,
typename Tensor1,
74 typename Tensor2,
typename Tensor3,
typename Tensor4>
76 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
77 DataTpl<Scalar, Options, JointCollectionTpl> &
data,
78 const Eigen::MatrixBase<ConfigVectorType> &
q,
79 const Eigen::MatrixBase<TangentVectorType1> &
v,
80 const Eigen::MatrixBase<TangentVectorType2> &
a,
81 const Tensor1 &d2tau_dqdq,
const Tensor2 &d2tau_dvdv,
82 const Tensor3 &dtau_dqdv,
const Tensor4 &dtau_dadq);
123 template <
typename,
int>
class JointCollectionTpl,
124 typename ConfigVectorType,
typename TangentVectorType1,
125 typename TangentVectorType2>
129 const Eigen::MatrixBase<ConfigVectorType> &
q,
130 const Eigen::MatrixBase<TangentVectorType1> &
v,
131 const Eigen::MatrixBase<TangentVectorType2> &
a) {
144 #include "pinocchio/algorithm/rnea-second-order-derivatives.hxx" 146 #endif // ifndef __pinocchio_algorithm_rnea_second_order_derivatives_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Tensor3x d2tau_dqdq
SO Partial derivative of the joint torque vector with respect to the joint configuration.
Tensor3x d2tau_dqdv
SO Cross-Partial derivative of the joint torque vector with respect to the joint configuration/veloci...
Main pinocchio namespace.
void ComputeRNEASecondOrderDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, const Tensor1 &d2tau_dqdq, const Tensor2 &d2tau_dvdv, const Tensor3 &dtau_dqdv, const Tensor4 &dtau_dadq)
Computes the Second-Order partial derivatives of the Recursive Newton Euler Algorithm w...
void setZero(std::vector< MatType, Eigen::aligned_allocator< MatType > > &Ms)
JointCollectionTpl & model
Tensor3x d2tau_dvdv
SO Partial derivative of the joint torque vector with respect to the joint velocity.
Tensor3x d2tau_dadq
SO Cross-Partial derivative of the joint torque vector with respect to the joint acceleration/configu...