inverse-kinematics.py
Go to the documentation of this file.
1 import numpy as np
2 import pinocchio
3 from numpy.linalg import norm, solve
4 
5 model = pinocchio.buildSampleModelManipulator()
6 data = model.createData()
7 
8 JOINT_ID = 6
9 oMdes = pinocchio.SE3(np.eye(3), np.array([1.0, 0.0, 1.0]))
10 
12 eps = 1e-4
13 IT_MAX = 1000
14 DT = 1e-1
15 damp = 1e-12
16 
17 i = 0
18 while True:
19  pinocchio.forwardKinematics(model, data, q)
20  iMd = data.oMi[JOINT_ID].actInv(oMdes)
21  err = pinocchio.log(iMd).vector # in joint frame
22  if norm(err) < eps:
23  success = True
24  break
25  if i >= IT_MAX:
26  success = False
27  break
28  J = pinocchio.computeJointJacobian(model, data, q, JOINT_ID) # in joint frame
29  J = -np.dot(pinocchio.Jlog6(iMd.inverse()), J)
30  v = -J.T.dot(solve(J.dot(J.T) + damp * np.eye(6), err))
31  q = pinocchio.integrate(model, q, v * DT)
32  if not i % 10:
33  print("%d: error = %s" % (i, err.T))
34  i += 1
35 
36 if success:
37  print("Convergence achieved!")
38 else:
39  print(
40  "\n"
41  "Warning: the iterative algorithm has not reached convergence "
42  "to the desired precision"
43  )
44 
45 print(f"\nresult: {q.flatten().tolist()}")
46 print(f"\nfinal error: {err.T}")
pinocchio::SE3Tpl< context::Scalar, context::Options >
pinocchio::forwardKinematics
void forwardKinematics(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)
Update the joint placements, spatial velocities and spatial accelerations according to the current jo...
pinocchio::cholesky::solve
Mat & solve(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Mat > &y)
Return the solution of using the Cholesky decomposition stored in data given the entry ....
pinocchio::integrate
void integrate(const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigIn_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< ConfigOut_t > &qout)
Visit a LieGroupVariant to call its integrate method.
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::Jlog6
Eigen::Matrix< Scalar, 6, 6, Options > Jlog6(const SE3Tpl< Scalar, Options > &M)
Derivative of log6.
Definition: spatial/explog.hpp:679
pinocchio::computeJointJacobian
void computeJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const JointIndex joint_id, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed in the local frame of the joint and store t...


pinocchio
Author(s):
autogenerated on Mon Dec 16 2024 03:41:02