Go to the documentation of this file.
    4 import pinocchio 
as pin
 
    5 from test_case 
import PinocchioTestCase 
as TestCase
 
   10         self.
model = pin.buildSampleModelHumanoidRandom()
 
   13         qmax = np.full((self.
model.nq, 1), np.pi)
 
   15         self.
v = np.random.rand(self.
model.nv)
 
   16         self.
a = np.random.rand(self.
model.nv)
 
   19         for _ 
in range(self.
model.njoints):
 
   26         null_fext = pin.StdVec_Force()
 
   27         for k 
in range(model.njoints):
 
   28             null_fext.append(pin.Force.Zero())
 
   33         self.assertApprox(tau_null_fext, tau)
 
   37             null_fext_list.append(f)
 
   39         print(
"size:", len(null_fext_list))
 
   41             self.
model, self.
data, self.
q, self.
v, self.
a, null_fext_list
 
   43         self.assertApprox(tau_null_fext_list, tau)
 
   50         data2 = model.createData()
 
   51         tau_ref = 
pin.rnea(model, data2, self.
q, self.
v, self.
a * 0)
 
   53         self.assertApprox(tau, tau_ref)
 
   60         data2 = model.createData()
 
   61         tau_ref = 
pin.rnea(model, data2, self.
q, self.
v * 0, self.
a * 0)
 
   63         self.assertApprox(tau, tau_ref)
 
   70         data2 = model.createData()
 
   71         tau_ref = 
pin.rnea(model, data2, self.
q, self.
v * 0, self.
a * 0, self.
fext)
 
   73         self.assertApprox(tau, tau_ref)
 
   80         data2 = model.createData()
 
   82             model, data2, self.
q, self.
v, self.
a * 0
 
   83         ) - 
pin.rnea(model, data2, self.
q, self.
v * 0, self.
a * 0)
 
   85         self.assertApprox(tau_coriolis_ref, C.dot(self.
v))
 
   88 if __name__ == 
"__main__":
 
  
def test_static_torque(self)
def test_coriolis_matrix(self)
void randomConfiguration(const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< ConfigOut_t > &qout)
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...
def test_generalized_gravity(self)
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & 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  of the Lagrangian dynamics:
ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > createData(const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel)
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & 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),...
result_of::push_front< V const, T >::type append(T const &t, V const &v)
Append the element T at the front of boost fusion vector V.
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & 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  of the Lagrangian dynamics:
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & computeGeneralizedGravity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the generalized gravity contribution  of the Lagrangian dynamics:
pinocchio
Author(s): 
autogenerated on Wed May 28 2025 02:41:14