Namespaces | Functions
rnea.hpp File Reference
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/multibody/data.hpp"
#include "pinocchio/algorithm/rnea.hxx"
Include dependency graph for rnea.hpp:
This graph shows which files directly or indirectly include this file:

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 ConfigVectorType , typename TangentVectorType >
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & pinocchio::computeCoriolisMatrix (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
 Computes the Coriolis Matrix $ C(q,\dot{q}) $ of the Lagrangian dynamics: More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType >
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & pinocchio::computeGeneralizedGravity (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
 Computes the generalized gravity contribution $ g(q) $ of the Lagrangian dynamics: More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType >
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & pinocchio::computeStaticTorque (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const container::aligned_vector< ForceTpl< Scalar, Options > > &fext)
 Computes the generalized static torque contribution $ g(q) - \sum J(q)^{\top} f_{\text{ext}} $ of the Lagrangian dynamics: More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & pinocchio::getCoriolisMatrix (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
 Retrives the Coriolis Matrix $ C(q,\dot{q}) $ of the Lagrangian dynamics: More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType >
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & pinocchio::nonLinearEffects (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
 Computes the non-linear effects (Corriolis, centrifual and gravitationnal effects), also called the bias terms $ b(q,\dot{q}) $ of the Lagrangian dynamics: More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 >
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & pinocchio::rnea (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)
 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...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename ForceDerived >
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & pinocchio::rnea (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 container::aligned_vector< ForceDerived > &fext)
 The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques according to the current state of the system, the desired joint accelerations and the external forces. More...
 


pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:44:00