pin-pink


Namepin-pink JSON
Version 3.1.0 PyPI version JSON
download
home_pageNone
SummaryInverse kinematics for articulated robot models, based on Pinocchio.
upload_time2024-10-28 13:56:16
maintainerNone
docs_urlNone
authorNone
requires_python>=3.8
licenseNone
keywords inverse kinematics pinocchio
VCS
bugtrack_url
requirements No requirements were recorded.
Travis-CI No Travis.
coveralls test coverage No coveralls.
            # Pink

[![Build](https://img.shields.io/github/actions/workflow/status/stephane-caron/pink/ci.yml?branch=main)](https://github.com/stephane-caron/pink/actions)
[![Documentation](https://img.shields.io/github/actions/workflow/status/stephane-caron/pink/docs.yml?branch=main&label=docs)](https://stephane-caron.github.io/pink/)
[![Coverage](https://coveralls.io/repos/github/stephane-caron/pink/badge.svg?branch=main)](https://coveralls.io/github/stephane-caron/pink?branch=main)
[![Conda version](https://anaconda.org/conda-forge/pink/badges/version.svg)](https://anaconda.org/conda-forge/pink)
[![PyPI version](https://img.shields.io/pypi/v/pin-pink)](https://pypi.org/project/pin-pink/)

**P**ython **in**verse **k**inematics for articulated robot models, based on [Pinocchio](https://github.com/stack-of-tasks/pinocchio).

![Banner for Pink v0.5.0](https://user-images.githubusercontent.com/1189580/192318997-ed7574c3-8238-451d-9548-a769d46ec03b.png)

## Installation

For best performance we recommended installing Pink from Conda:

```console
conda install -c conda-forge pink
```

You can also install it from PyPI:

```console
pip install pin-pink
```

## Usage

Pink solves differential inverse kinematics by [weighted tasks](https://scaron.info/robot-locomotion/inverse-kinematics.html). 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](https://scaron.info/robotics/jacobian-of-a-kinematic-task-and-derivatives-on-manifolds.html). 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:

```python
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:

```python
    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:

```python
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:

```python
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`](https://stephane-caron.github.io/pink/inverse-kinematics.html#pink.solve_ik.solve_ik) will take care of both configuration and velocity limits read from the robot model.

## Examples

Illustrated examples showcase how Pink performs on various robot morphologies:

- Arm: [UR5](https://github.com/stephane-caron/pink/tree/main/examples#arm-ur5) and [UR5 with end-effector limits](https://github.com/stephane-caron/pink/tree/main/examples/barriers#arm-ur5)
- Dual arms: [Flying dual-arm UR3](https://github.com/stephane-caron/pink/tree/main/examples#flying-dual-arm-ur3)
- Dual arms: [Yumi with spherical self-collision avoidance](https://github.com/stephane-caron/pink/tree/main/examples/barriers#yumi-end-effector-self-collision-avoidance)
- Dual arms: [Iiwa with whole-body self-collision avoidance](https://github.com/stephane-caron/pink/tree/main/examples/barriers#iiwa-whole-body-collision-avoidance)
- Humanoid: [Draco 3](https://github.com/stephane-caron/pink/tree/main/examples#humanoid-draco-3)
- Mobile base: [Stretch R1](https://github.com/stephane-caron/pink/tree/main/examples#mobile-stretch)
- Quadruped: [Go2 squatting with floating-base limits](https://github.com/stephane-caron/pink/tree/main/examples/barriers#go2-squat)
- Wheeled biped: [Upkie rolling without slipping](https://github.com/stephane-caron/pink/tree/main/examples#wheeled-biped-upkie)

There are also more basic examples to get started:

- [Double pendulum](https://github.com/stephane-caron/pink/blob/main/examples/double_pendulum.py)
- [Loading a custom URDF](https://github.com/stephane-caron/pink/blob/main/examples/load_custom_urdf.py)
- [Visualization in MeshCat](https://github.com/stephane-caron/pink/blob/main/examples/visualize_in_meshcat.py)
- [Visualization in yourdfpy](https://github.com/stephane-caron/pink/blob/main/examples/visualize_in_yourdfpy.py)

Check out the [examples](https://github.com/stephane-caron/pink/tree/main/examples) directory for more.

## Frequently Asked Questions

- [Can I solve **global** inverse kinematics?](https://github.com/stephane-caron/pink/discussions/66#discussioncomment-8224315)
- [Can I make velocities smoother?](https://github.com/stephane-caron/pink/discussions/103)
- [My configuration gets stuck somewhere and does not solve the task, what is going on?](https://github.com/stephane-caron/pink/discussions/66#discussioncomment-8224315)

## 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](https://github.com/stephane-caron/pink/discussions/66). 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](https://github.com/stephane-caron/pink/blob/main/examples/simple_pendulum_configuration_limit.py) example.

## How can I help?

Install the library and use it! Report bugs in the [issue tracker](https://github.com/stephane-caron/pink/issues). If you are a developer with some robotics experience looking to hack on open source, check out the [contribution guidelines](CONTRIBUTING.md).

## Citation

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

```bibtex
@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 and Domrachev, Ivan and Nedelchev, Simeon},
  license = {Apache-2.0},
  url = {https://github.com/stephane-caron/pink},
  version = {3.1.0},
  year = {2024}
}
```

## See also

Software:

- [mink](https://github.com/kevinzakka/mink): differential inverse kinematics in Python, based on the MuJoCo physics engine.
- [Jink.jl](https://github.com/adubredu/Jink.jl): Julia package for differential multi-task inverse kinematics.
- [PlaCo](https://github.com/rhoban/placo): C++ inverse kinematics based on Pinocchio.
- [pymanoid](https://github.com/stephane-caron/pymanoid): precursor to Pink based on OpenRAVE.
- [TSID](https://github.com/stack-of-tasks/tsid): C++ inverse kinematics based on Pinocchio.

Technical notes:

- [Inverse kinematics](https://scaron.info/robotics/inverse-kinematics.html): a general introduction to differential inverse kinematics.
- [Jacobian of a kinematic task and derivatives on manifolds](https://scaron.info/robotics/jacobian-of-a-kinematic-task-and-derivatives-on-manifolds.html).
- [Control Barrier Functions](https://simeon-ned.com/blog/2024/cbf/).

            

Raw data

            {
    "_id": null,
    "home_page": null,
    "name": "pin-pink",
    "maintainer": null,
    "docs_url": null,
    "requires_python": ">=3.8",
    "maintainer_email": "St\u00e9phane Caron <stephane.caron@normalesup.org>",
    "keywords": "inverse, kinematics, pinocchio",
    "author": null,
    "author_email": "St\u00e9phane Caron <stephane.caron@normalesup.org>",
    "download_url": "https://files.pythonhosted.org/packages/7b/af/d86b85ced1cf3ad5be4f5c06bac820405aa58eb2fe1a827ebde87c3ebeff/pin_pink-3.1.0.tar.gz",
    "platform": null,
    "description": "# Pink\n\n[![Build](https://img.shields.io/github/actions/workflow/status/stephane-caron/pink/ci.yml?branch=main)](https://github.com/stephane-caron/pink/actions)\n[![Documentation](https://img.shields.io/github/actions/workflow/status/stephane-caron/pink/docs.yml?branch=main&label=docs)](https://stephane-caron.github.io/pink/)\n[![Coverage](https://coveralls.io/repos/github/stephane-caron/pink/badge.svg?branch=main)](https://coveralls.io/github/stephane-caron/pink?branch=main)\n[![Conda version](https://anaconda.org/conda-forge/pink/badges/version.svg)](https://anaconda.org/conda-forge/pink)\n[![PyPI version](https://img.shields.io/pypi/v/pin-pink)](https://pypi.org/project/pin-pink/)\n\n**P**ython **in**verse **k**inematics for articulated robot models, based on [Pinocchio](https://github.com/stack-of-tasks/pinocchio).\n\n![Banner for Pink v0.5.0](https://user-images.githubusercontent.com/1189580/192318997-ed7574c3-8238-451d-9548-a769d46ec03b.png)\n\n## Installation\n\nFor best performance we recommended installing Pink from Conda:\n\n```console\nconda install -c conda-forge pink\n```\n\nYou can also install it from PyPI:\n\n```console\npip install pin-pink\n```\n\n## Usage\n\nPink solves differential inverse kinematics by [weighted tasks](https://scaron.info/robot-locomotion/inverse-kinematics.html). 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:\n\n$$\ne(q) = p_{foot}^{\\star} - p_{foot}(q)\n$$\n\nIn differential inverse kinematics, we compute a velocity $v \\in \\mathfrak{c}$ that satisfies the first-order differential equation:\n\n$$\nJ_e(q) v = \\dot{e}(q) = -\\alpha e(q)\n$$\n\nwhere $J\\_e(q) := \\frac{\\partial e}{\\partial q}$ is the [task Jacobian](https://scaron.info/robotics/jacobian-of-a-kinematic-task-and-derivatives-on-manifolds.html). 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:\n\n$$\n\\begin{align}\n\\underset{v \\in \\mathfrak{c}}{\\text{minimize}} \\ & \\sum_{\\text{task } e} \\Vert J_e(q) v + \\alpha e(q) \\Vert^2_{W_e} \\\\\n\\text{subject to} \\ & v_{\\text{min}}(q) \\leq v \\leq v_{\\text{max}}(q)\n\\end{align}\n$$\n\nPink provides an API to describe the problem as tasks with targets, and automatically build and solve the underlying quadratic program.\n\n### Task costs\n\nHere 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:\n\n```python\nfrom pink.tasks import FrameTask, PostureTask\n\ntasks = {\n    \"base\": FrameTask(\n        \"base\",\n        position_cost=1.0,              # [cost] / [m]\n        orientation_cost=1.0,           # [cost] / [rad]\n    ),\n    \"left_contact\": FrameTask(\n        \"left_contact\",\n        position_cost=[0.1, 0.0, 0.1],  # [cost] / [m]\n        orientation_cost=0.0,           # [cost] / [rad]\n    ),\n    \"right_contact\": FrameTask(\n        \"right_contact\",\n        position_cost=[0.1, 0.0, 0.1],  # [cost] / [m]\n        orientation_cost=0.0,           # [cost] / [rad]\n    ),\n    \"posture\": PostureTask(\n        cost=1e-3,                      # [cost] / [rad]\n    ),\n}\n```\n\nOrientation (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.\n\n### Task targets\n\nAside 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:\n\n```python\n    tasks[\"posture\"].set_target(\n        [1.0, 0.0, 0.0, 0.0] +           # floating base quaternion\n        [0.0, 0.0, 0.0] +                # floating base position\n        [0.0, 0.2, 0.0, 0.0, -0.2, 0.0]  # joint angles\n    )\n```\n\nBody tasks can be initialized, for example, from the robot's neutral configuration:\n\n```python\nimport pink\nfrom robot_descriptions.loaders.pinocchio import load_robot_description\n\nrobot = load_robot_description(\"upkie_description\")\nconfiguration = pink.Configuration(robot.model, robot.data, robot.q0)\nfor body, task in tasks.items():\n    if type(task) is FrameTask:\n        task.set_target(configuration.get_transform_frame_to_world(body))\n```\n\nA task can be added to the inverse kinematics once both its cost and target (if applicable) are defined.\n\n### Differential inverse kinematics\n\nPink 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:\n\n```python\ndt = 6e-3  # [s]\nfor t in np.arange(0.0, 42.0, dt):\n    velocity = solve_ik(configuration, tasks.values(), dt, solver=\"quadprog\")\n    configuration.integrate_inplace(velocity, dt)\n    time.sleep(dt)\n```\n\nIf 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`](https://stephane-caron.github.io/pink/inverse-kinematics.html#pink.solve_ik.solve_ik) will take care of both configuration and velocity limits read from the robot model.\n\n## Examples\n\nIllustrated examples showcase how Pink performs on various robot morphologies:\n\n- Arm: [UR5](https://github.com/stephane-caron/pink/tree/main/examples#arm-ur5) and [UR5 with end-effector limits](https://github.com/stephane-caron/pink/tree/main/examples/barriers#arm-ur5)\n- Dual arms: [Flying dual-arm UR3](https://github.com/stephane-caron/pink/tree/main/examples#flying-dual-arm-ur3)\n- Dual arms: [Yumi with spherical self-collision avoidance](https://github.com/stephane-caron/pink/tree/main/examples/barriers#yumi-end-effector-self-collision-avoidance)\n- Dual arms: [Iiwa with whole-body self-collision avoidance](https://github.com/stephane-caron/pink/tree/main/examples/barriers#iiwa-whole-body-collision-avoidance)\n- Humanoid: [Draco 3](https://github.com/stephane-caron/pink/tree/main/examples#humanoid-draco-3)\n- Mobile base: [Stretch R1](https://github.com/stephane-caron/pink/tree/main/examples#mobile-stretch)\n- Quadruped: [Go2 squatting with floating-base limits](https://github.com/stephane-caron/pink/tree/main/examples/barriers#go2-squat)\n- Wheeled biped: [Upkie rolling without slipping](https://github.com/stephane-caron/pink/tree/main/examples#wheeled-biped-upkie)\n\nThere are also more basic examples to get started:\n\n- [Double pendulum](https://github.com/stephane-caron/pink/blob/main/examples/double_pendulum.py)\n- [Loading a custom URDF](https://github.com/stephane-caron/pink/blob/main/examples/load_custom_urdf.py)\n- [Visualization in MeshCat](https://github.com/stephane-caron/pink/blob/main/examples/visualize_in_meshcat.py)\n- [Visualization in yourdfpy](https://github.com/stephane-caron/pink/blob/main/examples/visualize_in_yourdfpy.py)\n\nCheck out the [examples](https://github.com/stephane-caron/pink/tree/main/examples) directory for more.\n\n## Frequently Asked Questions\n\n- [Can I solve **global** inverse kinematics?](https://github.com/stephane-caron/pink/discussions/66#discussioncomment-8224315)\n- [Can I make velocities smoother?](https://github.com/stephane-caron/pink/discussions/103)\n- [My configuration gets stuck somewhere and does not solve the task, what is going on?](https://github.com/stephane-caron/pink/discussions/66#discussioncomment-8224315)\n\n## Global inverse kinematics\n\nPink 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](https://github.com/stephane-caron/pink/discussions/66). 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](https://github.com/stephane-caron/pink/blob/main/examples/simple_pendulum_configuration_limit.py) example.\n\n## How can I help?\n\nInstall the library and use it! Report bugs in the [issue tracker](https://github.com/stephane-caron/pink/issues). If you are a developer with some robotics experience looking to hack on open source, check out the [contribution guidelines](CONTRIBUTING.md).\n\n## Citation\n\nIf you use Pink in your scientific works, please cite it *e.g.* as follows:\n\n```bibtex\n@software{pink2024,\n  title = {{Pink: Python inverse kinematics based on Pinocchio}},\n  author = {Caron, St\u00e9phane and De Mont-Marin, Yann and Budhiraja, Rohan and Bang, Seung Hyeon and Domrachev, Ivan and Nedelchev, Simeon},\n  license = {Apache-2.0},\n  url = {https://github.com/stephane-caron/pink},\n  version = {3.1.0},\n  year = {2024}\n}\n```\n\n## See also\n\nSoftware:\n\n- [mink](https://github.com/kevinzakka/mink): differential inverse kinematics in Python, based on the MuJoCo physics engine.\n- [Jink.jl](https://github.com/adubredu/Jink.jl): Julia package for differential multi-task inverse kinematics.\n- [PlaCo](https://github.com/rhoban/placo): C++ inverse kinematics based on Pinocchio.\n- [pymanoid](https://github.com/stephane-caron/pymanoid): precursor to Pink based on OpenRAVE.\n- [TSID](https://github.com/stack-of-tasks/tsid): C++ inverse kinematics based on Pinocchio.\n\nTechnical notes:\n\n- [Inverse kinematics](https://scaron.info/robotics/inverse-kinematics.html): a general introduction to differential inverse kinematics.\n- [Jacobian of a kinematic task and derivatives on manifolds](https://scaron.info/robotics/jacobian-of-a-kinematic-task-and-derivatives-on-manifolds.html).\n- [Control Barrier Functions](https://simeon-ned.com/blog/2024/cbf/).\n",
    "bugtrack_url": null,
    "license": null,
    "summary": "Inverse kinematics for articulated robot models, based on Pinocchio.",
    "version": "3.1.0",
    "project_urls": {
        "Changelog": "https://github.com/stephane-caron/pink/blob/main/CHANGELOG.md",
        "Documentation": "https://stephane-caron.github.io/pink/",
        "Homepage": "https://stephane-caron.github.io/pink/",
        "Source": "https://github.com/stephane-caron/pink",
        "Tracker": "https://github.com/stephane-caron/pink/issues"
    },
    "split_keywords": [
        "inverse",
        " kinematics",
        " pinocchio"
    ],
    "urls": [
        {
            "comment_text": null,
            "digests": {
                "blake2b_256": "8843aa9bdf3db894dcbbf79be6f8a68c6154f4ffa5d301f3bf99a126d0fdd593",
                "md5": "bdccbafc9d9fbe44f36120b314d7e1b2",
                "sha256": "ba879077cc0ed26bc63df477b2da40a40b7d4ada524e2d2e4ed3d434c7bcf15f"
            },
            "downloads": -1,
            "filename": "pin_pink-3.1.0-py3-none-any.whl",
            "has_sig": false,
            "md5_digest": "bdccbafc9d9fbe44f36120b314d7e1b2",
            "packagetype": "bdist_wheel",
            "python_version": "py3",
            "requires_python": ">=3.8",
            "size": 53716,
            "upload_time": "2024-10-28T13:56:14",
            "upload_time_iso_8601": "2024-10-28T13:56:14.232879Z",
            "url": "https://files.pythonhosted.org/packages/88/43/aa9bdf3db894dcbbf79be6f8a68c6154f4ffa5d301f3bf99a126d0fdd593/pin_pink-3.1.0-py3-none-any.whl",
            "yanked": false,
            "yanked_reason": null
        },
        {
            "comment_text": null,
            "digests": {
                "blake2b_256": "7bafd86b85ced1cf3ad5be4f5c06bac820405aa58eb2fe1a827ebde87c3ebeff",
                "md5": "12e0da5fa9d263ff8032b475eaa5b7c0",
                "sha256": "7ce58ee380f6ab0bc037063d0aaac3472a92538be932db137f680a05087330a2"
            },
            "downloads": -1,
            "filename": "pin_pink-3.1.0.tar.gz",
            "has_sig": false,
            "md5_digest": "12e0da5fa9d263ff8032b475eaa5b7c0",
            "packagetype": "sdist",
            "python_version": "source",
            "requires_python": ">=3.8",
            "size": 109556,
            "upload_time": "2024-10-28T13:56:16",
            "upload_time_iso_8601": "2024-10-28T13:56:16.926549Z",
            "url": "https://files.pythonhosted.org/packages/7b/af/d86b85ced1cf3ad5be4f5c06bac820405aa58eb2fe1a827ebde87c3ebeff/pin_pink-3.1.0.tar.gz",
            "yanked": false,
            "yanked_reason": null
        }
    ],
    "upload_time": "2024-10-28 13:56:16",
    "github": true,
    "gitlab": false,
    "bitbucket": false,
    "codeberg": false,
    "github_user": "stephane-caron",
    "github_project": "pink",
    "travis_ci": false,
    "coveralls": false,
    "github_actions": true,
    "tox": true,
    "lcname": "pin-pink"
}
        
Elapsed time: 0.34644s