dcrba.py
Go to the documentation of this file.
1 #
2 # Copyright (c) 2016 CNRS
3 #
4 
5 from __future__ import print_function
6 
7 import pinocchio as pin
8 from pinocchio.robot_wrapper import RobotWrapper
9 from pinocchio.utils import *
10 from numpy.linalg import norm
11 import lambdas
12 from lambdas import Mcross, ancestors, parent, iv, td, quad, adj, adjdual
13 
14 
15 def hessian(robot, q, crossterms=False):
16  """
17  Compute the Hessian tensor of all the robot joints.
18  If crossterms, then also compute the Si x Si terms,
19  that are not part of the true Hessian but enters in some computations like VRNEA.
20  """
22  H = np.zeros([6, robot.model.nv, robot.model.nv])
23  pin.computeJointJacobians(robot.model, robot.data, q)
24  J = robot.data.J
25  skiplast = -1 if not crossterms else None
26  for joint_i in range(1, robot.model.njoints):
27  for joint_j in ancestors(joint_i)[:skiplast]: # j is a child of i
28  for i in iv(joint_i):
29  for j in iv(joint_j):
30  Si = J[:, i]
31  Sj = J[:, j]
32  H[:, i, j] = np.asarray(Mcross(Sj, Si))[:, 0]
33  return H
34 
35 
36 # CRBA ====> Mp[i,j] += Si.transpose()*Yk*Sj
37 # D-CRBA ==> TSi Y Sj + Si Y TSj - Si YSdx Sj + Si SdxY Sj
38 # Term a = term d && term b = term c --- or are null
39 # -> term a is null if j<=diff
40 # -> term d is null if diff>k
41 # -> then a-d is nonzero only when k>=diff>j
42 # Due to simplification, terms cancel to the following:
43 # if i<d (always true) M[i,j,d] = Si.T Yd TjSd (= -Si.T Yd Sd x Sj)
44 # if j<d (possibly false) M[i,j,d] += TdSi.T Yd Sd (= +Si.T Sdx Yd Sj)
45 # where Yd is the composite inertia of the minimal subtree rooted either at j or d.
46 
47 
48 class DCRBA:
49  """
50  Compute the derivative (tangent application) of the mass matrix M wrt q,
51  which is a NVxNVxNV tensor.
52  """
53 
54  def __init__(self, robot):
55  self.robot = robot
57 
58  def pre(self, q):
59  robot = self.robot
60  self.H = hessian(robot, q)
61  self.J = robot.data.J.copy()
62  pin.crba(robot.model, robot.data, q)
63  self.Y = [
64  (robot.data.oMi[i] * robot.data.Ycrb[i]).matrix()
65  for i in range(0, robot.model.njoints)
66  ]
67 
68  self.dM = np.zeros(
69  [
70  robot.model.nv,
71  ]
72  * 3
73  )
74 
75  def __call__(self):
76  robot = self.robot
77  J = self.J
78  Y = self.Y
79  dM = self.dM
80  H = self.H
81 
82  for j in range(robot.model.njoints - 1, 0, -1):
83  for joint_diff in range(
84  1, robot.model.njoints
85  ): # diff should be a descendant or ancestor of j
86  if j not in ancestors(joint_diff) and joint_diff not in ancestors(j):
87  continue
88 
89  for i in ancestors(min(parent(joint_diff), j)):
90  i0, i1 = iv(i)[0], iv(i)[-1] + 1
91  j0, j1 = iv(j)[0], iv(j)[-1] + 1
92 
93  Si = J[:, i0:i1]
94  Sj = J[:, j0:j1]
95 
96  for d in iv(joint_diff):
97  T_iSd = np.array(H[:, d, i0:i1]) # this is 0 if d<=i (<=j)
98  T_jSd = np.array(H[:, d, j0:j1]) # this is 0 is d<=j
99 
100  """
101  assert( norm(T_iSd)<1e-6 or not joint_diff<i ) # d<i => TiSd=0
102  assert( norm(T_jSd)<1e-6 or not joint_diff<j ) # d<j => TjSd=0
103  assert( norm(T_jSd)<1e-6 or not norm(T_iSd)<1e-6 ) # TiSd=0 => TjSd=0
104  assert( norm(T_iSd)>1e-6 )
105  """
106 
107  Yd = Y[max(j, joint_diff)]
108 
109  dM[i0:i1, j0:j1, d] = T_iSd.T * Yd * Sj
110  if j < joint_diff:
111  dM[i0:i1, j0:j1, d] += Si.T * Yd * T_jSd
112 
113  # Make dM triangular by copying strict-upper triangle to lower one.
114  if i != j:
115  dM[j0:j1, i0:i1, d] = dM[i0:i1, j0:j1, d].T
116  else:
117  dM[j0:j1, i0:i1, d] += np.triu(dM[i0:i1, j0:j1, d], 1).T
118 
119  return dM
120 
121 
122 # -----------------------------------------------------------------------------------
123 # -----------------------------------------------------------------------------------
124 # -----------------------------------------------------------------------------------
125 class VRNEA:
126  """
127  Compute the C tensor so that nle(q,vq) = vq C vq.
128  Noting Cv = C*vq for an arbitrary robot velocity vq:
129  Since Mdot = (Cv+Cv')/2, then C = dCv/dvq and dM/dq = (Cv+Cv')
130 
131  Q is index by i,j,k i.e. tau_k = v.T*Q[:,:,k]*v
132  At level k, Qk is a lower triangular matrix (same shape as H) where:
133  * rows i s.t. i>k are equals to Sk.T*Ycrb_i*S_ixS_j (j the col index),
134  * rows i s.t. i<=k are equals to Sk.T*Ycrb_k*S_ixS_j (j the col index)
135  To avoid the call to Ycrb_i>k, the first par is set up while computing Q_k
136  """
137 
138  def __init__(self, robot):
139  self.robot = robot
140  lambdas.setRobotArgs(robot)
141  self.YJ = zero([6, robot.model.nv])
142  self.Q = np.zeros(
143  [
144  robot.model.nv,
145  ]
146  * 3
147  )
148 
149  def __call__(self, q):
150  robot = self.robot
151  H = hessian(robot, q, crossterms=True)
152  J = robot.data.J
153  YJ = self.YJ
154  Q = self.Q
155 
156  # The terms in SxS YS corresponds to f = vxYv
157  # The terms in S YSxS corresponds to a = vxv (==> f = Yvxv)
158  for k in range(robot.model.njoints - 1, 0, -1):
159  k0, k1 = iv(k)[0], iv(k)[-1] + 1
160  Yk = (robot.data.oMi[k] * robot.data.Ycrb[k]).matrix()
161  Sk = J[:, k0:k1]
162  for j in ancestors(k): # Fill YJ = [ ... Yk*Sj ... ]_j
163  j0, j1 = iv(j)[0], iv(j)[-1] + 1
164  YJ[:, j0:j1] = Yk * J[:, j0:j1]
165 
166  # Fill the diagonal of the current level of Q = Q[k,:k,:k]
167  for i in ancestors(k):
168  i0, i1 = iv(i)[0], iv(i)[-1] + 1
169  Si = J[:, i0:i1]
170 
171  Q[k0:k1, i0:i1, i0:i1] = -td(
172  H[:, k0:k1, i0:i1], YJ[:, i0:i1], [0, 0]
173  ) # = (Si x Sk)' * Yk Si
174 
175  # Fill the nondiag of the current level Q[k,:k,:k]
176  for j in ancestors(i)[:-1]:
177  j0, j1 = iv(j)[0], iv(j)[-1] + 1
178  Sj = J[:, j0:j1]
179 
180  # = Sk' * Yk * Si x Sj
181  Q[k0:k1, i0:i1, j0:j1] = td(
182  YJ[:, k0:k1], H[:, i0:i1, j0:j1], [0, 0]
183  )
184  # = (Si x Sk)' * Yk Sj
185  Q[k0:k1, i0:i1, j0:j1] -= td(
186  H[:, k0:k1, i0:i1], YJ[:, j0:j1], [0, 0]
187  )
188  # = (Sj x Sk)' * Yk Si
189  Q[k0:k1, j0:j1, i0:i1] = -td(
190  H[:, k0:k1, j0:j1], YJ[:, i0:i1], [0, 0]
191  )
192 
193  # Fill the border elements of levels below k Q[kk,k,:] and Q[kk,:,k] with kk<k
194  for kk in ancestors(k)[:-1]:
195  kk0, kk1 = iv(kk)[0], iv(kk)[-1] + 1
196  Skk = J[:, kk0:kk1]
197 
198  for j in ancestors(k):
199  j0, j1 = iv(j)[0], iv(j)[-1] + 1
200  Sj = J[:, j0:j1]
201 
202  # = Skk' Yk Sk x Sj = (Yk Skk)' Sk x Sj
203  if k != j:
204  Q[kk0:kk1, k0:k1, j0:j1] = td(
205  YJ[:, kk0:kk1], H[:, k0:k1, j0:j1], [0, 0]
206  )
207  # = (Sk x Skk)' Yk Sj
208  Q[kk0:kk1, k0:k1, j0:j1] += td(
209  H[:, k0:k1, kk0:kk1].T, YJ[:, j0:j1], [2, 0]
210  )
211  # = (Sj x Skk)' Yk Sk
212  # Switch because j can be > or < than kk
213  if j < kk:
214  Q[kk0:kk1, j0:j1, k0:k1] = -Q[j0:j1, kk0:kk1, k0:k1].transpose(
215  1, 0, 2
216  )
217  elif j >= kk:
218  Q[kk0:kk1, j0:j1, k0:k1] = td(
219  H[:, j0:j1, kk0:kk1].T, YJ[:, k0:k1], [2, 0]
220  )
221 
222  return Q
223 
224 
225 # -----------------------------------------------------------------------------------
226 # -----------------------------------------------------------------------------------
227 # -----------------------------------------------------------------------------------
228 class Coriolis:
229  def __init__(self, robot):
230  self.robot = robot
231  lambdas.setRobotArgs(robot)
232  NV = robot.model.nv
233  NJ = robot.model.njoints
234  self.C = zero([NV, NV])
235  self.YS = zero([6, NV])
236  self.Sxv = zero([6, NV])
237 
238  def __call__(self, q, vq):
239  robot = self.robot
240  NV = robot.model.nv
241  NJ = robot.model.njoints
242  C = self.C
243  YS = self.YS
244  Sxv = self.Sxv
245  H = hessian(robot, q)
246 
247  pin.computeAllTerms(robot.model, robot.data, q, vq)
248  J = robot.data.J
249  oMi = robot.data.oMi
250  v = [(oMi[i] * robot.data.v[i]).vector for i in range(NJ)]
251  Y = [(oMi[i] * robot.data.Ycrb[i]).matrix() for i in range(NJ)]
252 
253  # --- Precomputations
254  # Centroidal matrix
255  for j in range(NJ):
256  j0, j1 = iv(j)[0], iv(j)[-1] + 1
257  YS[:, j0:j1] = Y[j] * J[:, j0:j1]
258 
259  # velocity-jacobian cross products.
260  for j in range(NJ):
261  j0, j1 = iv(j)[0], iv(j)[-1] + 1
262  vj = v[j]
263  Sxv[:, j0:j1] = adj(vj) * J[:, j0:j1]
264 
265  # --- Main loop
266  for i in range(NJ - 1, 0, -1):
267  i0, i1 = iv(i)[0], iv(i)[-1] + 1
268  Yi = Y[i]
269  Si = J[:, i0:i1]
270  vp = v[robot.model.parents[i]]
271 
272  SxvY = Sxv[:, i0:i1].T * Yi
273  for j in ancestors(i):
274  j0, j1 = iv(j)[0], iv(j)[-1] + 1
275  Sj = J[:, j0:j1]
276 
277  # COR ===> Si' Yi Sj x vj
278  C[i0:i1, j0:j1] = YS[:, i0:i1].T * Sxv[:, j0:j1]
279  # CEN ===> Si' vi x Yi Sj = - (Si x vi)' Yi Sj
280  C[i0:i1, j0:j1] -= SxvY * Sj
281 
282  vxYS = adjdual(v[i]) * Yi * Si
283  YSxv = Yi * Sxv[:, i0:i1]
284  Yv = Yi * vp
285  for ii in ancestors(i)[:-1]:
286  ii0, ii1 = iv(ii)[0], iv(ii)[-1] + 1
287  Sii = J[:, ii0:ii1]
288  # COR ===> Sii' Yi Si x vi
289  C[ii0:ii1, i0:i1] = Sii.T * YSxv
290  # CEN ===> Sii' vi x Yi Si = (Sii x vi)' Yi Si
291  C[ii0:ii1, i0:i1] += Sii.T * vxYS
292  # CEN ===> Sii' Si x Yi vi = (Sii x Si)' Yi vi
293  C[ii0:ii1, i0:i1] += np.array(
294  td(H[:, i0:i1, ii0:ii1], Yv, [0, 0])[:, :, 0]
295  )
296 
297  return C
298 
299 
300 # --- DRNEA -------------------------------------------------------------------------
301 # --- DRNEA -------------------------------------------------------------------------
302 # --- DRNEA -------------------------------------------------------------------------
303 
304 from lambdas import MCross, FCross
305 
306 
307 class DRNEA:
308  def __init__(self, robot):
309  self.robot = robot
310  lambdas.setRobotArgs(robot)
311 
312  def __call__(self, q, vq, aq):
313  robot = self.robot
314  pin.rnea(robot.model, robot.data, q, vq, aq)
315  NJ = robot.model.njoints
316  NV = robot.model.nv
317  J = robot.data.J
318  oMi = robot.data.oMi
319  v = [(oMi[i] * robot.data.v[i]).vector for i in range(NJ)]
320  a = [(oMi[i] * robot.data.a_gf[i]).vector for i in range(NJ)]
321  f = [(oMi[i] * robot.data.f[i]).vector for i in range(NJ)]
322  Y = [(oMi[i] * robot.model.inertias[i]).matrix() for i in range(NJ)]
323  Ycrb = [(oMi[i] * robot.data.Ycrb[i]).matrix() for i in range(NJ)]
324 
325  Tkf = [zero([6, NV]) for i in range(NJ)]
326  Yvx = [zero([6, 6]) for i in range(NJ)]
327  adjf = lambda f: -np.bmat(
328  [[zero([3, 3]), skew(f[:3])], [skew(f[:3]), skew(f[3:])]]
329  )
330 
331  R = self.R = zero([NV, NV])
332 
333  for i in reversed(
334  range(1, NJ)
335  ): # i is the torque index : dtau_i = R[i,:] dq
336  i0, i1 = iv(i)[0], iv(i)[-1] + 1
337  Yi = Y[i]
338  Yci = Ycrb[i]
339  Si = J[:, i0:i1]
340  vi = v[i]
341  ai = a[i]
342  fi = f[i]
343  aqi = aq[i0:i1]
344  vqi = vq[i0:i1]
345  dvi = Si * vqi
346  li = parent(i)
347 
348  Yvx[i] += Y[i] * adj(v[i])
349  Yvx[i] -= adjf(Y[i] * v[i])
350  Yvx[i] -= adjdual(v[i]) * Yi
351 
352  Yvx[li] += Yvx[i]
353 
354  for k in ancestors(i): # k is the derivative index: dtau = R[:,k] dq_k
355  k0, k1 = iv(k)[0], iv(k)[-1] + 1
356  Sk = J[:, k0:k1]
357  lk = parent(k)
358 
359  # Si' Yi Tk ai = Si' Yi ( Sk x (ai-alk) + (vi-vlk) x (Sk x vlk) )
360  # Tk Si' Yi ai = Si' Yi ( - Sk x a[lk] + (vi-vlk) x (Sk x vlk) )
361  Tkf = Yci * (-MCross(Sk, a[lk]) + MCross(MCross(Sk, v[lk]), v[lk]))
362 
363  # Tk Si' fs = Tk Si' Ycrb[i] ai + Si' Ys (vs-vi) x (Sk x vlk)
364  # = "" + Si' Ys vs x (Sk x vlk) - Si' Ys vi x (Sk x vlk)
365  Tkf += Yvx[i] * MCross(Sk, v[lk])
366 
367  R[i0:i1, k0:k1] = Si.T * Tkf
368  if i == k:
369  for kk in ancestors(k)[:-1]:
370  kk0, kk1 = iv(kk)[0], iv(kk)[-1] + 1
371  Skk = J[:, kk0:kk1]
372  R[kk0:kk1, k0:k1] = Skk.T * FCross(Sk, f[i])
373  R[kk0:kk1, k0:k1] += Skk.T * Tkf
374 
375  self.a = a
376  self.v = v
377  self.f = f
378  self.Y = Y
379  self.Ycrb = Ycrb
380  self.Yvx = Yvx
381 
382  return R
383 
384 
385 # -----------------------------------------------------------------------------------
386 # -----------------------------------------------------------------------------------
387 # -----------------------------------------------------------------------------------
388 # --- UNIT TEST ---
389 if __name__ == "__main__":
390  np.random.seed(0)
391 
392  robot = RobotWrapper(
393  "/home/nmansard/src/pinocchio/pinocchio/models/romeo/urdf/romeo.urdf",
394  [
395  "/home/nmansard/src/pinocchio/pinocchio/models/romeo/",
396  ],
397  pin.JointModelFreeFlyer(),
398  )
399  q = rand(robot.model.nq)
400  q[3:7] /= norm(q[3:7])
401  vq = rand(robot.model.nv)
402 
403  # --- HESSIAN ---
404  # --- HESSIAN ---
405  # --- HESSIAN ---
406  H = hessian(robot, q)
407 
408  # Compute the Hessian matrix H using RNEA, so that acor = v*H*v
409  vq1 = vq * 0
410  Htrue = np.zeros([6, robot.model.nv, robot.model.nv])
411  for joint_i in range(1, robot.model.njoints):
412  for joint_j in ancestors(joint_i)[:-1]:
413  for i in iv(joint_i):
414  for j in iv(joint_j):
415  vq1 *= 0
416  vq1[i] = vq1[j] = 1.0
417  pin.computeAllTerms(robot.model, robot.data, q, vq1)
418  Htrue[:, i, j] = (
419  robot.data.oMi[joint_i] * robot.data.a[joint_i]
420  ).vector.T
421 
422  print("Check hessian = \t\t", norm(H - Htrue))
423 
424  # --- dCRBA ---
425  # --- dCRBA ---
426  # --- dCRBA ---
427 
428  dcrba = DCRBA(robot)
429  dcrba.pre(q)
430  Mp = dcrba()
431 
432  # --- Validate dM/dq by finite diff
433  dM = np.zeros(
434  [
435  robot.model.nv,
436  ]
437  * 3
438  )
439  eps = 1e-6
440  dq = zero(robot.model.nv)
441 
442  for diff in range(robot.model.nv):
443  dM[:, :, diff] = -pin.crba(robot.model, robot.data, q)
444 
445  dq *= 0
446  dq[diff] = eps
447  qdq = pin.integrate(robot.model, q, dq)
448 
449  dM[:, :, diff] += pin.crba(robot.model, robot.data, qdq)
450 
451  dM /= eps
452 
453  print(
454  "Check dCRBA = \t\t\t",
455  max([norm(Mp[:, :, diff] - dM[:, :, diff]) for diff in range(robot.model.nv)]),
456  )
457 
458  # --- vRNEA ---
459  # --- vRNEA ---
460  # --- vRNEA ---
461 
462  vrnea = VRNEA(robot)
463  Q = vrnea(q)
464 
465  # --- Compute C from rnea, for future check
466  robot.model.gravity = pin.Motion.Zero()
467  rnea0 = lambda q, vq: pin.nle(robot.model, robot.data, q, vq)
468  vq1 = vq * 0
469  C = np.zeros(
470  [
471  robot.model.nv,
472  ]
473  * 3
474  )
475  for i in range(robot.model.nv):
476  vq1 *= 0
477  vq1[i] = 1
478  C[:, i, i] = rnea0(q, vq1).T
479 
480  for i in range(robot.model.nv):
481  for j in range(robot.model.nv):
482  if i == j:
483  continue
484  vq1 *= 0
485  vq1[i] = vq1[j] = 1.0
486  C[:, i, j] = (rnea0(q, vq1).T - C[:, i, i] - C[:, j, j]) / 2
487 
488  print("Check d/dv rnea = \t\t", norm(quad(Q, vq) - rnea0(q, vq)))
489  print("Check C = Q+Q.T = \t\t", norm((Q + Q.transpose(0, 2, 1)) / 2 - C))
490  print("Check dM = C+C.T /2 \t\t", norm(Mp - (C + C.transpose(1, 0, 2))))
491  print(
492  "Check dM = Q+Q.T+Q.T+Q.T /2 \t",
493  norm(
494  Mp
495  - (Q + Q.transpose(0, 2, 1) + Q.transpose(1, 0, 2) + Q.transpose(2, 0, 1))
496  / 2
497  ),
498  )
499 
500  # --- CORIOLIS
501  # --- CORIOLIS
502  # --- CORIOLIS
503  coriolis = Coriolis(robot)
504  C = coriolis(q, vq)
505  print("Check coriolis \t\t\t", norm(C * vq - rnea0(q, vq)))
506 
507  # --- DRNEA
508  # --- DRNEA
509  # --- DRNEA
510  drnea = DRNEA(robot)
511  aq = rand(robot.model.nv)
512  R = drnea(q, vq, aq)
513 
514  NV = robot.model.nv
515  Rd = zero([NV, NV])
516  eps = 1e-8
517  r0 = pin.rnea(robot.model, robot.data, q, vq, aq).copy()
518  for i in range(NV):
519  dq = zero(NV)
520  dq[i] = eps
521  qdq = pin.integrate(robot.model, q, dq)
522  Rd[:, i] = (pin.rnea(robot.model, robot.data, qdq, vq, aq) - r0) / eps
523  print("Check drnea \t\t\t", norm(Rd - R))
dcrba.VRNEA.YJ
YJ
Definition: dcrba.py:141
dcrba.Coriolis.__call__
def __call__(self, q, vq)
Definition: dcrba.py:238
dcrba.Coriolis.YS
YS
Definition: dcrba.py:235
pinocchio.robot_wrapper.RobotWrapper
Definition: robot_wrapper.py:12
lambdas.parent
parent
Definition: lambdas.py:20
lambdas.adjdual
adjdual
Definition: lambdas.py:82
dcrba.coriolis
coriolis
Definition: dcrba.py:503
dcrba.DCRBA.Y
Y
Definition: dcrba.py:63
lambdas.ancestors
tuple ancestors
Definition: lambdas.py:27
dcrba.DCRBA
Definition: dcrba.py:48
dcrba.VRNEA.__init__
def __init__(self, robot)
Definition: dcrba.py:138
dcrba.Coriolis
Definition: dcrba.py:228
dcrba.DRNEA.Ycrb
Ycrb
Definition: dcrba.py:379
dcrba.DRNEA.v
v
Definition: dcrba.py:376
dcrba.DRNEA.__call__
def __call__(self, q, vq, aq)
Definition: dcrba.py:312
dcrba.DCRBA.robot
robot
Definition: dcrba.py:55
dcrba.Coriolis.robot
robot
Definition: dcrba.py:230
dcrba.DCRBA.__init__
def __init__(self, robot)
Definition: dcrba.py:54
dcrba.DRNEA.Yvx
Yvx
Definition: dcrba.py:380
pinocchio::cholesky::min
JointCollectionTpl const DataTpl< Scalar, Options, JointCollectionTpl > const Eigen::MatrixBase< Mat > & min
Definition: cholesky.hpp:91
dcrba.DRNEA.robot
robot
Definition: dcrba.py:309
dcrba.VRNEA.__call__
def __call__(self, q)
Definition: dcrba.py:149
dcrba.DRNEA.Y
Y
Definition: dcrba.py:378
dcrba.Coriolis.C
C
Definition: dcrba.py:234
dcrba.VRNEA
Definition: dcrba.py:125
dcrba.VRNEA.robot
robot
Definition: dcrba.py:139
dcrba.hessian
def hessian(robot, q, crossterms=False)
Definition: dcrba.py:15
dcrba.DCRBA.__call__
def __call__(self)
Definition: dcrba.py:75
dcrba
Definition: dcrba.py:1
dcrba.Coriolis.Sxv
Sxv
Definition: dcrba.py:236
pinocchio.utils
Definition: bindings/python/pinocchio/utils.py:1
dcrba.DRNEA.f
f
Definition: dcrba.py:377
dcrba.DCRBA.dM
dM
Definition: dcrba.py:68
lambdas.MCross
MCross
Definition: lambdas.py:75
lambdas.adj
adj
Definition: lambdas.py:79
pinocchio::python::skew
Eigen::Matrix< typename Vector3::Scalar, 3, 3, Vector3::Options > skew(const Vector3 &v)
Definition: expose-skew.cpp:19
pinocchio.robot_wrapper
Definition: robot_wrapper.py:1
dcrba.vrnea
vrnea
Definition: dcrba.py:462
dcrba.DCRBA.J
J
Definition: dcrba.py:61
dcrba.VRNEA.Q
Q
Definition: dcrba.py:142
dcrba.rnea0
rnea0
Definition: dcrba.py:467
lambdas.Mcross
Mcross
Definition: lambdas.py:69
dcrba.drnea
drnea
Definition: dcrba.py:510
dcrba.DRNEA.__init__
def __init__(self, robot)
Definition: dcrba.py:308
dcrba.Coriolis.__init__
def __init__(self, robot)
Definition: dcrba.py:229
lambdas.iv
iv
Definition: lambdas.py:21
pinocchio::copy
void copy(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &origin, DataTpl< Scalar, Options, JointCollectionTpl > &dest, KinematicLevel kinematic_level)
Copy part of the data from origin to dest. Template parameter can be used to select at which differen...
Definition: copy.hpp:42
dcrba.DRNEA
Definition: dcrba.py:307
dcrba.DCRBA.pre
def pre(self, q)
Definition: dcrba.py:58
lambdas.setRobotArgs
def setRobotArgs(robot)
Definition: lambdas.py:59
lambdas.quad
quad
Definition: lambdas.py:88
lambdas.td
td
Definition: lambdas.py:87
dcrba.DRNEA.a
a
Definition: dcrba.py:375
pinocchio.utils.rand
def rand(n)
Definition: bindings/python/pinocchio/utils.py:42
pinocchio.utils.zero
def zero(n)
Definition: bindings/python/pinocchio/utils.py:38
dcrba.DRNEA.R
R
Definition: dcrba.py:331
CppAD::max
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
Definition: autodiff/cppad.hpp:180
lambdas.FCross
FCross
Definition: lambdas.py:76
dcrba.DCRBA.H
H
Definition: dcrba.py:60


pinocchio
Author(s):
autogenerated on Sat Jun 1 2024 02:40:34