Giter VIP home page Giter VIP logo

pink's Introduction

Pink

Build Documentation Coverage Conda version PyPI version

Python inverse kinematics for articulated robot models, based on Pinocchio.

Banner for Pink v0.5.0

Installation

For best performance we recommended installing Pink from Conda:

conda install -c conda-forge pink

You can also install it from PyPI:

pip install pin-pink

Usage

Pink solves differential inverse kinematics by weighted tasks. A task is defined by a residual function $e(q)$ of the robot configuration $q \in \mathcal{C}$ to be driven to zero. For instance, putting a foot position $p_{foot}(q)$ at a given target $p_{foot}^{\star}$ can be described by the position residual:

$$ e(q) = p_{foot}^{\star} - p_{foot}(q) $$

In differential inverse kinematics, we compute a velocity $v \in \mathfrak{c}$ that satisfies the first-order differential equation:

$$ J_e(q) v = \dot{e}(q) = -\alpha e(q) $$

where $J_e(q) := \frac{\partial e}{\partial q}$ is the task Jacobian. We can define multiple tasks, but some of them will come into conflict if they can't be all fully achieved at the same time. Conflicts are resolved by casting all objectives to a common unit, and weighing these normalized objectives relative to each other. We also include configuration and velocity limits, making our overall optimization problem a quadratic program:

$$ \begin{align} \underset{v \in \mathfrak{c}}{\text{minimize}} \ & \sum_{\text{task } e} \Vert J_e(q) v + \alpha e(q) \Vert^2_{W_e} \\ \text{subject to} \ & v_{\text{min}}(q) \leq v \leq v_{\text{max}}(q) \end{align} $$

Pink provides an API to describe the problem as tasks with targets, and automatically build and solve the underlying quadratic program.

Task costs

Here is the example of a biped robot that controls the position and orientation of its base, left and right contact frames. A fourth "posture" task, giving a preferred angle for each joint, is added for regularization:

from pink.tasks import FrameTask, PostureTask

tasks = {
    "base": FrameTask(
        "base",
        position_cost=1.0,              # [cost] / [m]
        orientation_cost=1.0,           # [cost] / [rad]
    ),
    "left_contact": FrameTask(
        "left_contact",
        position_cost=[0.1, 0.0, 0.1],  # [cost] / [m]
        orientation_cost=0.0,           # [cost] / [rad]
    ),
    "right_contact": FrameTask(
        "right_contact",
        position_cost=[0.1, 0.0, 0.1],  # [cost] / [m]
        orientation_cost=0.0,           # [cost] / [rad]
    ),
    "posture": PostureTask(
        cost=1e-3,                      # [cost] / [rad]
    ),
}

Orientation (similarly position) costs can be scalars or 3D vectors. They specify how much each radian of angular error "costs" in the overall normalized objective. When using 3D vectors, components are weighted anisotropically along each axis of the body frame.

Task targets

Aside from their costs, most tasks take a second set of parameters called target. For example, a frame task aims for a target transform, while a posture task aims for a target configuration vector. Targets are set by the set_target function:

    tasks["posture"].set_target(
        [1.0, 0.0, 0.0, 0.0] +           # floating base quaternion
        [0.0, 0.0, 0.0] +                # floating base position
        [0.0, 0.2, 0.0, 0.0, -0.2, 0.0]  # joint angles
    )

Body tasks can be initialized, for example, from the robot's neutral configuration:

import pink
from robot_descriptions.loaders.pinocchio import load_robot_description

robot = load_robot_description("upkie_description")
configuration = pink.Configuration(robot.model, robot.data, robot.q0)
for body, task in tasks.items():
    if type(task) is FrameTask:
        task.set_target(configuration.get_transform_frame_to_world(body))

A task can be added to the inverse kinematics once both its cost and target (if applicable) are defined.

Differential inverse kinematics

Pink solves differential inverse kinematics, meaning it outputs a velocity that steers the robot towards achieving all tasks at best. If we keep integrating that velocity, and task targets don't change over time, we will converge to a stationary configuration:

dt = 6e-3  # [s]
for t in np.arange(0.0, 42.0, dt):
    velocity = solve_ik(configuration, tasks.values(), dt, solver="quadprog")
    configuration.integrate_inplace(velocity, dt)
    time.sleep(dt)

If task targets are continuously updated, there will be no stationary solution to converge to, but the model will keep on tracking each target at best. Note that solve_ik will take care of both configuration and velocity limits read from the robot model.

Examples

Basic examples to get started:

Pink works with all kinds of robot morphologies:

Check out the examples directory for more code.

Global inverse kinematics

Pink implements differential inverse kinematics, a first-order algorithm that converges to the closest optimum of its cost function. It is a local method that does not solve the more difficult problem of global inverse kinematics. That is, it may converge to a global optimum, or to a local one stuck to some configuration limits. This behavior is illustrated in the simple pendulum with configuration limit example.

How can I help?

Install the library and use it! Report bugs in the issue tracker. If you are a developer with some robotics experience looking to hack on open source, check out the contribution guidelines.

Citation

If you use Pink in your scientific works, please cite it e.g. as follows:

@software{pink2024,
  title = {{Pink: Python inverse kinematics based on Pinocchio}},
  author = {Caron, Stéphane and De Mont-Marin, Yann and Budhiraja, Rohan and Bang, Seung Hyeon},
  license = {Apache-2.0},
  url = {https://github.com/stephane-caron/pink},
  version = {2.1.0},
  year = {2024}
}

See also

Software:

  • Jink.jl: Julia package for differential multi-task inverse kinematics.
  • PlaCo: C++ inverse kinematics based on Pinocchio.
  • pymanoid: precursor to Pink based on OpenRAVE.
  • TSID: C++ inverse kinematics based on Pinocchio.

Technical notes:

pink's People

Contributors

proyan avatar shbang91 avatar stephane-caron avatar ymontmarin avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar

pink's Issues

Adding holonomic constraints

Hello Dr. Caron,

Thank you for maintaining this nice repo.

I have a question regarding how to set a holonomic constraint when solving IK using the API you provided in this repo.
I've looked through the documentation of this repo, but I only found the body and posture task class, so my best guess is I could not solve the IK on the holonomic system given the current APIs.

My problem is: I have a 7-DOF manipulator in which one of the joints is passive(q_1) while satisfying the relation of q_1 = q_2 (one active joint) at the same time, so I would like to move this hard constraint to the cost function (by making it a soft constraint). Is there any task class that I can use to solve this problem?

I would really appreciate you if you could get me any ideas or suggestions.

Best,
Seung Hyeon

pink installation on mac

Hello Stephan,

Thank you for your effort in maintaining this nice repo!

While using pink, I get the following two questions for you.

  1. I've installed pink on my mac which is intel OSX Monterey 12.5.1 and I am using anaconda virtual environment (python version 3.8).
    When I tried to run the upkie_crouching.py example, it kept complaining there is no module named pink.models. So, instead of running the script, I manually tried opening the python interpreter(python version 3.8) in the same anaconda environment and typed the code in upkie_crouching.py line by line, and it successfully imported all the modules. I don't know how this could be possible. Do you have anything in your mind?

  2. Other than the aforementioned software issue, I have another question regarding the inverse kinematics solver interface (API).
    I have a 7-DoF robotic manipulator which has a holonomic constraint (q_1 = q_2) so it has 6 active joints with one passive joint. Given any cartesian tasks, I would like to solve the inverse geometry problem to get the joint positions satisfying the holonomic constraint.
    In this case, I think one way to solve the problem is by setting the holonomic constraint as a task in the cost function and giving the larger task gain compared to the cartesian task.
    Another way to solve the problem is using projected jacobian (J_cartesian_task * N_holonomic_constraint) with N = I - JJ_pseudo_inverse.
    Do you think those two methods sound okay to obtain the solution that I want? If so, can you point out which API in pink I should use to set the holonomic constraint as a cost in the QP (I think I could try the latter one by myself)?

Thank you,
Seung Hyeon

Display a TF tree using pinocchio model

Dear Caron:
I found this repo by using Pinocchio when I tried to learn more about Meshcat, and thanks a lot for your code, I get some inspiration for drawing a TF tree for a robot model.
My understanding of this code in pink

meshcat_shapes.frame(viewer["left_contact_target"], opacity=0.5)

is that we will replace the old object with a new frame.
My question is if we could just add the frame by using addGeometryObject?

Thanks for your help!
heaty

Numerical stability of Draco3 example

@ymontmarin I just tested the new linear holonomic task on the humanoid_draco3.py example, and it seems it has become less numerically stable:

humanoid_draco3_issue.mp4

(The first run uses the latest version from PyPI, the second run is the current master branch.)

I don't think the gains should be reduced for the new task formulation? Or maybe this is because we are now including the free flyer in the task, whereas it was just q_2 = -q_1 before?

Joint limits for planar joints

The omnidirectional three-wheeled robot added by #14 does not work yet because of joint limits for its root planar joint.

This issue will be fixed by #12.

Global inverse kinematics

Dear pink team,

first of all, thanks for the library! I was just experimenting with pink for a variety of 6-DoF robots and I was experiencing an unexpected high number of ik procedures not converging to a solution although it existed. It seems to me around 50% of the runs I was performing got stuck in local minima (position/orientation tradeoff).

In pseudocode, my application looks roughly like this:

q = sample_random_q()
r = create_random_6dof_robot()
goal = r.forward_kinematics(q)
r.reset_to_random_position()

ik = pink_ik(r, goal)  # Basically following the example provided in the readme

I compared the results against my own implementation of an ik solver based on the damped least squares inverse of the frame jacobian. While pink is significantly faster when finding a solution, I only find a solution in ~50% of cases compared to ~90% for my own solver. Playing around with the damping factor didn't really seem to improve the results significantly.

I would love to use pink, it seems to be a fast and nice library for solving the ik with pinocchio-based simulations. However, in order to do so, I would need to have a way to significantly improve the ratio of solved ik problems. Do you have any suggestions on possible adaptions that could help? I would be happy to contribute, but I don't know which approaches would be the most promising here as I have rarely worked with the quadratic programming solvers used here.

Cheers, Jonathan

CVXOPT does not handle infinity

When there is no velocity bound on a joint, Pink currently sets inequality constraints as $-\infty < v_i < \infty$. But with CVXOPT this approach yields ValueError: domain error.

Possible solutions:

  • Trim large values (might not generalize well)
  • Add some post-processing to remove redundant inequalities for CVXOPT specifically
  • Avoid such inequalities altogether

URDF support

Hello,

I've noticed that pink only supports URDF in the robot_description repo. Is there any way I could use my custom URDF?

Thank you,
Seung Hyeon

CoM task

Hi, Stéphane, I am wondering if there is a CoM task for a humanoid robot in current framework.

Need to use pink to solve IK using a LIPM model.

Attribute Error : 'FrameTask' object has no attribute 'frame'

When you run the arm_ur5.py example it gives an error:

Attribute Error : 'FrameTask' object has no attribute 'frame'

end_effector_task.frame is not defined

The class Frame Task has no attribute frame in the examples/arm_ur5.py

The same error is persistent with other arm_ur3.py and other examples

Package name on PyPI

Hello @chenjiandongx, I see that the last release of the pink package on PyPI was from 2018, and that its homepage on GitHub is now a 404 page.

Our project here is also named pink (pin-pink on PyPI). If your project is not active any more, would you be OK with transferring https://pypi.org/project/pink so that we can release to that name?

This would help us reduce friction when users install our project ("I installed pink but it doesn't work!", to which we check "did you pip install pin-pink and not pink", and that usually is the issue...)

Thanks in advance for your consideration,

Configuration is defined only for FrameType::Body, not for other enum values.

Hey Stéphane,
Nice library :)
I tried to use the library for a simple config calculation for a user-defined frame in the end-effector. I used the frametype pinocchio::FrameType::OP_FRAME , but it seems that it is not supported yet (see https://github.com/tasts-robots/pink/blob/master/pink/configuration.py#L161). (The more generic implementation might be with getFrameId and existFrame and so on).

Should be an easy change to make, please let me know if you want me to do it.
Best,
Rohan

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.