inverse-dynamics-derivatives.py
Go to the documentation of this file.
1 import numpy as np
2 import pinocchio as pin
3 
4 
12 
13 # Create model and data
14 
15 model = pin.buildSampleModelHumanoidRandom()
16 data = model.createData()
17 
18 # Set bounds (by default they are undefinded for a the Simple Humanoid model)
19 
20 model.lowerPositionLimit = -np.ones((model.nq, 1))
21 model.upperPositionLimit = np.ones((model.nq, 1))
22 
23 q = pin.randomConfiguration(model) # joint configuration
24 v = np.random.rand(model.nv, 1) # joint velocity
25 a = np.random.rand(model.nv, 1) # joint acceleration
26 
27 # Evaluate the derivatives
28 
29 pin.computeRNEADerivatives(model, data, q, v, a)
30 
31 # Retrieve the derivatives in data
32 
33 dtau_dq = data.dtau_dq # Derivatives of the ID w.r.t. the joint config vector
34 dtau_dv = data.dtau_dv # Derivatives of the ID w.r.t. the joint velocity vector
35 dtau_da = data.M # Derivatives of the ID w.r.t. the joint acceleration vector


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