overview-simple.py
Go to the documentation of this file.
1 from __future__ import print_function
2 
3 import pinocchio
4 
5 model = pinocchio.buildSampleModelManipulator()
6 data = model.createData()
7 
8 q = pinocchio.neutral(model)
9 v = pinocchio.utils.zero(model.nv)
10 a = pinocchio.utils.zero(model.nv)
11 
12 tau = pinocchio.rnea(model,data,q,v,a)
13 print('tau = ', tau.T)
Eigen::Matrix< typename LieGroupCollection::Scalar, Eigen::Dynamic, 1, LieGroupCollection::Options > neutral(const LieGroupGenericTpl< LieGroupCollection > &lg)
Visit a LieGroupVariant to get the neutral element of it.
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & 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 accordi...


pinocchio
Author(s):
autogenerated on Fri Jun 23 2023 02:38:32