overview-simple.py
Go to the documentation of this file.
1 import pinocchio
2 
3 model = pinocchio.buildSampleModelManipulator()
4 data = model.createData()
5 
6 q = pinocchio.neutral(model)
7 v = pinocchio.utils.zero(model.nv)
8 a = pinocchio.utils.zero(model.nv)
9 
10 tau = pinocchio.rnea(model, data, q, v, a)
11 print("tau = ", tau.T)
pinocchio::rnea
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::neutral
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.
pinocchio.utils.zero
def zero(n)
Definition: bindings/python/pinocchio/utils.py:37


pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:32