autodiff-rnea.py
Go to the documentation of this file.
1 import numpy as np
2 import pinocchio as pin
3 import pinocchio.cppad as ADpin
4 from pinocchio.utils import isapprox
5 from pycppad import AD, ADFun, Independent
6 
7 pinmodel = pin.buildSampleModelHumanoidRandom()
8 model = ADpin.Model(pinmodel)
9 data = model.createData()
10 
11 nq = model.nq
12 nv = model.nv
13 
14 q = ADpin.neutral(model)
15 v = np.array([AD(1.0)] * nv)
16 a = np.zeros(nv, dtype=AD)
17 
18 # declare independent variables and starting recording
19 Independent(v)
20 
21 y = ADpin.rnea(model, data, q, v, a)
22 
23 # create f: v -> y and stop tape recording
24 f = ADFun(v, y)
25 
26 # first-order derivates wrt v
27 dv = np.ones(nv)
28 ADdtau_dv = f.Jacobian(dv).reshape(nv, nv)
29 (dtau_dq, dtau_dv, dtau_da) = pin.computeRNEADerivatives(
30  pinmodel, pinmodel.createData(), pin.neutral(pinmodel), np.ones(nv), np.zeros(nv)
31 )
32 isapprox(ADdtau_dv, dtau_dv, 1e-12)
pinocchio.cppad
Definition: bindings/python/pinocchio/cppad/__init__.py:1
pinocchio.utils
Definition: bindings/python/pinocchio/utils.py:1
pinocchio::computeRNEADerivatives
void computeRNEADerivatives(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< ForceTpl< Scalar, Options >> &fext)
Computes the derivatives of the Recursive Newton Euler Algorithms with respect to the joint configura...
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
Author(s):
autogenerated on Wed May 28 2025 02:41:14