Skip to content

Commit

Permalink
Merge pull request #2428 from jcarpent/topic/examples
Browse files Browse the repository at this point in the history
Add inverse-kinematics for translation error only
  • Loading branch information
jcarpent authored Sep 22, 2024
2 parents 500e6a9 + c0284f3 commit 7fd15d0
Show file tree
Hide file tree
Showing 4 changed files with 121 additions and 3 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/).
### Added

- Default visualizer can be changed with `PINOCCHIO_VIEWER` environment variable ([#2419](https://github.com/stack-of-tasks/pinocchio/pull/2419))
- Add more Python and C++ examples related to inverse kinematics with 3d tasks ([#2428](https://github.com/stack-of-tasks/pinocchio/pull/2428))

### Fixed
- Fix linkage of Boost.Serialization on Windows ([#2400](https://github.com/stack-of-tasks/pinocchio/pull/2400))
Expand Down
8 changes: 5 additions & 3 deletions examples/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#
# Copyright (c) 2015-2022 CNRS INRIA
# Copyright (c) 2015-2024 CNRS INRIA
#

# Compute flags outside the macro to avoid recomputing it for each tests
Expand Down Expand Up @@ -46,6 +46,7 @@ function(ADD_PINOCCHIO_CPP_EXAMPLE EXAMPLE)
endfunction()

add_pinocchio_cpp_example(inverse-kinematics)
add_pinocchio_cpp_example(inverse-kinematics-3d)
add_pinocchio_cpp_example(overview-simple)
add_pinocchio_cpp_example(overview-lie)
add_pinocchio_cpp_example(overview-SE3)
Expand All @@ -70,8 +71,9 @@ if(BUILD_WITH_COLLISION_SUPPORT)
endif()

if(BUILD_PYTHON_INTERFACE)
set(${PROJECT_NAME}_PYTHON_EXAMPLES inverse-kinematics overview-simple kinematics-derivatives
forward-dynamics-derivatives inverse-dynamics-derivatives)
set(${PROJECT_NAME}_PYTHON_EXAMPLES
inverse-kinematics inverse-kinematics-3d overview-simple kinematics-derivatives
forward-dynamics-derivatives inverse-dynamics-derivatives)

if(BUILD_WITH_URDF_SUPPORT)
list(
Expand Down
68 changes: 68 additions & 0 deletions examples/inverse-kinematics-3d.cpp
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;
}
47 changes: 47 additions & 0 deletions examples/inverse-kinematics-3d.py
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)

0 comments on commit 7fd15d0

Please sign in to comment.