#include <omp.h>
#include "pinocchio/multibody/pool/model.hpp"
#include "pinocchio/algorithm/rnea.hpp"
Go to the source code of this file.
|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorPool , typename TangentVectorPool1 , typename TangentVectorPool2 , typename TangentVectorPool3 > |
void | pinocchio::rnea (const int num_threads, ModelPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< TangentVectorPool1 > &v, const Eigen::MatrixBase< TangentVectorPool2 > &a, const Eigen::MatrixBase< TangentVectorPool3 > &tau) |
| The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques according to the current state of the system and the desired joint accelerations. More...
|
|