-
Notifications
You must be signed in to change notification settings - Fork 406
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #2428 from jcarpent/topic/examples
Add inverse-kinematics for translation error only
- Loading branch information
Showing
4 changed files
with
121 additions
and
3 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,68 @@ | ||
#include <iostream> | ||
|
||
#include "pinocchio/multibody/sample-models.hpp" | ||
#include "pinocchio/spatial/explog.hpp" | ||
#include "pinocchio/algorithm/kinematics.hpp" | ||
#include "pinocchio/algorithm/jacobian.hpp" | ||
#include "pinocchio/algorithm/joint-configuration.hpp" | ||
|
||
int main(int /* argc */, char ** /* argv */) | ||
{ | ||
pinocchio::Model model; | ||
pinocchio::buildModels::manipulator(model); | ||
pinocchio::Data data(model); | ||
|
||
const int JOINT_ID = 6; | ||
const pinocchio::SE3 oMdes(Eigen::Matrix3d::Identity(), Eigen::Vector3d(1., 0., 1.)); | ||
|
||
Eigen::VectorXd q = pinocchio::neutral(model); | ||
const double eps = 1e-4; | ||
const int IT_MAX = 1000; | ||
const double DT = 1e-1; | ||
const double damp = 1e-12; | ||
|
||
pinocchio::Data::Matrix6x joint_jacobian(6, model.nv); | ||
joint_jacobian.setZero(); | ||
|
||
bool success = false; | ||
Eigen::Vector3d err; | ||
Eigen::VectorXd v(model.nv); | ||
for (int i = 0;; i++) | ||
{ | ||
pinocchio::forwardKinematics(model, data, q); | ||
const pinocchio::SE3 iMd = data.oMi[JOINT_ID].actInv(oMdes); | ||
err = iMd.translation(); // in joint frame | ||
if (err.norm() < eps) | ||
{ | ||
success = true; | ||
break; | ||
} | ||
if (i >= IT_MAX) | ||
{ | ||
success = false; | ||
break; | ||
} | ||
pinocchio::computeJointJacobian( | ||
model, data, q, JOINT_ID, joint_jacobian); // joint_jacobian expressed in the joint frame | ||
const auto J = -joint_jacobian.topRows<3>(); // Jacobian associated with the error | ||
const Eigen::Matrix3d JJt = J * J.transpose() + damp * Eigen::Matrix3d::Identity(); | ||
v.noalias() = -J.transpose() * JJt.ldlt().solve(err); | ||
q = pinocchio::integrate(model, q, v * DT); | ||
if (!(i % 10)) | ||
std::cout << i << ": error = " << err.transpose() << std::endl; | ||
} | ||
|
||
if (success) | ||
{ | ||
std::cout << "Convergence achieved!" << std::endl; | ||
} | ||
else | ||
{ | ||
std::cout | ||
<< "\nWarning: the iterative algorithm has not reached convergence to the desired precision" | ||
<< std::endl; | ||
} | ||
|
||
std::cout << "\nresult: " << q.transpose() << std::endl; | ||
std::cout << "\nfinal error: " << err.transpose() << std::endl; | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,47 @@ | ||
from __future__ import print_function | ||
|
||
import numpy as np | ||
from numpy.linalg import norm, solve | ||
|
||
import pinocchio | ||
|
||
model = pinocchio.buildSampleModelManipulator() | ||
data = model.createData() | ||
|
||
JOINT_ID = 6 | ||
oMdes = pinocchio.SE3(np.eye(3), np.array([1.0, 0.0, 1.0])) | ||
|
||
q = pinocchio.neutral(model) | ||
eps = 1e-4 | ||
IT_MAX = 1000 | ||
DT = 1e-1 | ||
damp = 1e-12 | ||
|
||
it = 0 | ||
while True: | ||
pinocchio.forwardKinematics(model, data, q) | ||
iMd = data.oMi[JOINT_ID].actInv(oMdes) | ||
err = iMd.translation | ||
if norm(err) < eps: | ||
success = True | ||
break | ||
if it >= IT_MAX: | ||
success = False | ||
break | ||
J = pinocchio.computeJointJacobian(model, data, q, JOINT_ID) # in joint frame | ||
J = -J[:3, :] # linear part of the Jacobian | ||
v = -J.T.dot(solve(J.dot(J.T) + damp * np.eye(3), err)) | ||
q = pinocchio.integrate(model, q, v * DT) | ||
if not it % 10: | ||
print("%d: error = %s" % (it, err.T)) | ||
it += 1 | ||
|
||
if success: | ||
print("Convergence achieved!") | ||
else: | ||
print( | ||
"\nWarning: the iterative algorithm has not reached convergence to the desired precision" | ||
) | ||
|
||
print("\nresult: %s" % q.flatten().tolist()) | ||
print("\nfinal error: %s" % err.T) |