bindings_centroidal_dynamics_derivatives.py
Go to the documentation of this file.
1 import unittest
2 
3 import numpy as np
4 import pinocchio as pin
5 from test_case import PinocchioTestCase as TestCase
6 
7 
8 class TestDeriavtives(TestCase):
9  def setUp(self):
10  self.model = pin.buildSampleModelHumanoidRandom()
11  self.data = self.model.createData()
12 
13  qmax = np.full((self.model.nq, 1), np.pi)
14  self.q = pin.randomConfiguration(self.model, -qmax, qmax)
15  self.v = np.random.rand(self.model.nv)
16  self.a = np.random.rand(self.model.nv)
17 
20  self.model, self.data, self.q, self.v, self.a
21  )
22 
23  self.assertTrue(len(res) == 4)
24 
25  data2 = self.model.createData()
27  self.model, data2, self.q, self.v, self.a
28  )
29 
30  self.assertApprox(self.data.hg, data2.hg)
31  self.assertApprox(self.data.dhg, data2.dhg)
32 
33  data3 = self.model.createData()
34  pin.computeRNEADerivatives(self.model, data3, self.q, self.v, self.a)
36 
37  for k in range(4):
38  self.assertApprox(res[k], res2[k])
39 
40 
41 if __name__ == "__main__":
42  unittest.main()
bindings_centroidal_dynamics_derivatives.TestDeriavtives.model
model
Definition: bindings_centroidal_dynamics_derivatives.py:10
bindings_centroidal_dynamics_derivatives.TestDeriavtives.setUp
def setUp(self)
Definition: bindings_centroidal_dynamics_derivatives.py:9
bindings_centroidal_dynamics_derivatives.TestDeriavtives.a
a
Definition: bindings_centroidal_dynamics_derivatives.py:16
bindings_centroidal_dynamics_derivatives.TestDeriavtives.v
v
Definition: bindings_centroidal_dynamics_derivatives.py:15
bindings_centroidal_dynamics_derivatives.TestDeriavtives.test_centroidal_derivatives
def test_centroidal_derivatives(self)
Definition: bindings_centroidal_dynamics_derivatives.py:18
bindings_centroidal_dynamics_derivatives.TestDeriavtives.q
q
Definition: bindings_centroidal_dynamics_derivatives.py:14
pinocchio::randomConfiguration
void randomConfiguration(const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< ConfigOut_t > &qout)
bindings_centroidal_dynamics_derivatives.TestDeriavtives.data
data
Definition: bindings_centroidal_dynamics_derivatives.py:11
pinocchio::createData
ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > createData(const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel)
Definition: constraint-model-visitor.hpp:239
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...
bindings_centroidal_dynamics_derivatives.TestDeriavtives
Definition: bindings_centroidal_dynamics_derivatives.py:8
pinocchio::getCentroidalDynamicsDerivatives
void getCentroidalDynamicsDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Matrix6xLike1 > &dh_dq, const Eigen::MatrixBase< Matrix6xLike1 > &dhdot_dq, const Eigen::MatrixBase< Matrix6xLike2 > &dhdot_dv, const Eigen::MatrixBase< Matrix6xLike3 > &dhdot_da)
Retrive the analytical derivatives of the centroidal dynamics from the RNEA derivatives....
pinocchio::computeCentroidalMomentumTimeVariation
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & computeCentroidalMomentumTimeVariation(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)
Computes the Centroidal momemtum and its time derivatives, a.k.a. the total momenta of the system and...
pinocchio::computeCentroidalDynamicsDerivatives
void computeCentroidalDynamicsDerivatives(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 Eigen::MatrixBase< Matrix6xLike0 > &dh_dq, const Eigen::MatrixBase< Matrix6xLike1 > &dhdot_dq, const Eigen::MatrixBase< Matrix6xLike2 > &dhdot_dv, const Eigen::MatrixBase< Matrix6xLike3 > &dhdot_da)
Computes the analytical derivatives of the centroidal dynamics with respect to the joint configuratio...


pinocchio
Author(s):
autogenerated on Wed May 28 2025 02:41:14