inverse-kinematics.cpp
Go to the documentation of this file.
1 #include "pinocchio/parsers/sample-models.hpp"
2 #include "pinocchio/spatial/explog.hpp"
3 #include "pinocchio/algorithm/kinematics.hpp"
4 #include "pinocchio/algorithm/jacobian.hpp"
5 #include "pinocchio/algorithm/joint-configuration.hpp"
6 
7 int main(int /* argc */, char ** /* argv */)
8 {
11  pinocchio::Data data(model);
12 
13  const int JOINT_ID = 6;
14  const pinocchio::SE3 oMdes(Eigen::Matrix3d::Identity(), Eigen::Vector3d(1., 0., 1.));
15 
17  const double eps = 1e-4;
18  const int IT_MAX = 1000;
19  const double DT = 1e-1;
20  const double damp = 1e-6;
21 
23  J.setZero();
24 
25  bool success = false;
26  typedef Eigen::Matrix<double, 6, 1> Vector6d;
27  Vector6d err;
28  Eigen::VectorXd v(model.nv);
29  for (int i=0;;i++)
30  {
31  pinocchio::forwardKinematics(model,data,q);
32  const pinocchio::SE3 dMi = oMdes.actInv(data.oMi[JOINT_ID]);
33  err = pinocchio::log6(dMi).toVector();
34  if(err.norm() < eps)
35  {
36  success = true;
37  break;
38  }
39  if (i >= IT_MAX)
40  {
41  success = false;
42  break;
43  }
44  pinocchio::computeJointJacobian(model,data,q,JOINT_ID,J);
46  JJt.noalias() = J * J.transpose();
47  JJt.diagonal().array() += damp;
48  v.noalias() = - J.transpose() * JJt.ldlt().solve(err);
49  q = pinocchio::integrate(model,q,v*DT);
50  if(!(i%10))
51  std::cout << i << ": error = " << err.transpose() << std::endl;
52  }
53 
54  if(success)
55  std::cout << "Convergence achieved!" << std::endl;
56  else
57  std::cout << "\nWarning: the iterative algorithm has not reached convergence to the desired precision" << std::endl;
58 
59  std::cout << "\nresult: " << q.transpose() << std::endl;
60  std::cout << "\nfinal error: " << err.transpose() << std::endl;
61 }
q
void integrate(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< ReturnType > &qout)
Integrate a configuration vector for the specified model for a tangent vector during one unit time...
int eps
Definition: dcrba.py:384
v
MotionTpl< Scalar, Options > log6(const SE3Tpl< Scalar, Options > &M)
Log: SE3 -> se3.
data
int main(int, char **)
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Update the joint placements according to the current joint configuration.
SE3GroupAction< D >::ReturnType actInv(const D &d) const
by = aXb.actInv(ay)
Definition: se3-base.hpp:97
int DT
Definition: dpendulum.py:13
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
Return the neutral configuration element related to the model configuration space.
ToVectorConstReturnType toVector() const
Definition: motion-base.hpp:37
int nv
Dimension of the velocity vector space.
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
void computeJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const JointIndex jointId, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed in the local frame of the joint and store t...
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
Definition: conversions.cpp:14
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
void manipulator(ModelTpl< Scalar, Options, JointCollectionTpl > &model)
Create a 6-DOF kinematic chain shoulder-elbow-wrist.


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:03