franky-panda


Namefranky-panda JSON
Version 0.9.1 PyPI version JSON
download
home_pagehttps://github.com/TimSchneider42/franky
SummaryHigh-Level Motion Library for the Franka Panda Robot (fork of frankx)
upload_time2024-06-04 21:19:25
maintainerNone
docs_urlNone
authorTim Schneider
requires_python>=3.6
licenseLGPL
keywords robot robotics trajectory-generation motion-control
VCS
bugtrack_url
requirements No requirements were recorded.
Travis-CI No Travis.
coveralls test coverage No coveralls.
            <div align="center">
  <img width="340" src="https://raw.githubusercontent.com/timschneider42/franky/master/doc/logo.svg?sanitize=true">
  <h3 align="center">
    High-Level Motion Library for the Franka Emika Robot
  </h3>
</div>
<p align="center">
  <a href="https://github.com/timschneider42/franky/actions">
    <img src="https://github.com/timschneider42/franky/workflows/CI/badge.svg" alt="CI">
  </a>

  <a href="https://github.com/timschneider42/franky/actions">
    <img src="https://github.com/timschneider42/franky/workflows/Publish/badge.svg" alt="Publish">
  </a>

  <a href="https://github.com/timschneider42/franky/issues">
    <img src="https://img.shields.io/github/issues/timschneider42/franky.svg" alt="Issues">
  </a>

  <a href="https://github.com/timschneider42/franky/releases">
    <img src="https://img.shields.io/github/v/release/timschneider42/franky.svg?include_prereleases&sort=semver" alt="Releases">
  </a>

  <a href="https://github.com/timschneider42/franky/blob/master/LICENSE">
    <img src="https://img.shields.io/badge/license-LGPL-green.svg" alt="LGPL">
  </a>
</p>


Franky is a high-level motion library (both C++ and Python) for the Franka Emika robot.
It adds a Python wrapper around [libfranka](https://frankaemika.github.io/docs/libfranka.html), while replacing necessary real-time programming with higher-level motion commands.
As franky focuses on making real-time trajectory generation easy, it allows the robot to react to unforeseen events.


## Differences to frankx
Franky is a fork of [frankx](https://github.com/pantor/frankx), though both codebase and functionality differ substantially from frankx by now.
In particular, franky provides the following new features/improvements:
* [Motions can be updated asynchronously.](#real-time-motion)
* [Reactions allow for the registration of callbacks instead of just printing to stdout when fired.](#real-time-reactions)
* [The robot state is also available during control.](#robot-state)
* A larger part of the libfranka API is exposed to python (e.g.,`setCollisionBehavior`, `setJoinImpedance`, and `setCartesianImpedance`).
* Cartesian motion generation handles boundaries in Euler angles properly.
* [There is a new joint motion type that supports waypoints.](#motion-types)
* [The signature of `Affine` changed.](#geometry) `Affine` does not handle elbow positions anymore. Instead, a new class `RobotPose` stores both the end-effector pose and optionally the elbow position.
* The `MotionData` class does not exist anymore. Instead, reactions and other settings moved to `Motion`.
* [The `Measure` class allows for arithmetic operations.](#real-time-reactions)
* Exceptions caused by libfranka are raised properly instead of being printed to stdout.
* [We provide wheels for both Franka Research 3 and the older Franka Panda](#installation)

## Setup
To install franky, you have to follow three steps:
1. Ensure that you are using a realtime kernel
2. Ensure that the executing user has permission to run real-time applications
3. Install franky via pip or build it from the sources

### Installing a real-time kernel

In order for franky to function properly, it requires the underlying OS to use a realtime kernel. 
Otherwise, you might see `communication_constrains_violation` errors.

To check whether your system is currently using a real-time kernel, type `uname -a`.
You should see something like this:
```bash
$ uname -a
Linux [PCNAME] 5.15.0-1056-realtime #63-Ubuntu SMP PREEMPT_RT ...
```
If it does not say PREEMPT_RT, you are not currently running a real-time kernel.

There are multiple ways of installing a real-time kernel. You can [build it from source](https://frankaemika.github.io/docs/installation_linux.html#setting-up-the-real-time-kernel) or, if you are using Ubuntu, it can be [enabled through Ubuntu Pro](https://ubuntu.com/real-time).

### Allowing the executing user to run real-time applications

First, create a group `realtime` and add your user (or whoever is running franky) to this group:
```bash
sudo addgroup realtime
sudo usermod -a -G realtime $(whoami)
```

Afterward, add the following limits to the real-time group in /etc/security/limits.conf:
```
@realtime soft rtprio 99
@realtime soft priority 99
@realtime soft memlock 102400
@realtime hard rtprio 99
@realtime hard priority 99
@realtime hard memlock 102400
```
Log out and log in again to let the changes take effect.

To verify that the changes were applied, check if your user is in the `realtime` group:
```bash
$ groups
... realtime
```
If realtime is not listed in your groups, try rebooting.

### Installing franky
To start using franky with Python and libfranka *0.13.3*, just install it via
```bash
pip install franky-panda
```
We also provide wheels for libfranka versions *0.7.1*, *0.8.0*, *0.9.2*, *0.10.0*, *0.11.0*, *0.12.1*, *0.13.3*. 
They can be installed via
```bash
VERSION=0-9-2
wget https://github.com/TimSchneider42/franky/releases/latest/download/libfranka_${VERSION}_wheels.zip
unzip libfranka_${VERSION}_wheels.zip
pip install --no-index --find-links=./dist franky-panda
```

Franky is based on [libfranka](https://github.com/frankaemika/libfranka), [Eigen](https://eigen.tuxfamily.org) for transformation calculations and [pybind11](https://github.com/pybind/pybind11) for the Python bindings.
As the Franka is sensitive to acceleration discontinuities, it requires jerk-constrained motion generation, for which franky uses the [Ruckig](https://ruckig.com) community version for Online Trajectory Generation (OTG).

After installing the dependencies (the exact versions can be found [here](#development)), you can build and install franky via
```bash
git clone --recurse-submodules git@github.com:timschneider42/franky.git
cd franky
mkdir -p build
cd build
cmake -DCMAKE_BUILD_TYPE=Release ..
make
make install
```

To use franky, you can also include it as a subproject in your parent CMake via `add_subdirectory(franky)` and then `target_link_libraries(<target> libfranky)`. 

If you need only the Python module, you can install franky via
```bash
pip install .
```
Make sure that the built library `_franky.cpython-3**-****-linux-gnu.so` is in the Python path, e.g. by adjusting `PYTHONPATH` accordingly.


#### Using Docker

To use franky within Docker we provide a [Dockerfile](docker/run/Dockerfile) and accompanying [docker-compose](docker-compose.yml) file.

```bash
git clone https://github.com/timschneider42/franky.git
cd franky/
docker compose build franky-run
```

To use another version of libfranka than the default (v0.13.3) add a build argument:
```bash
docker compose build franky-run --build-arg LIBFRANKA_VERSION=0.9.2
```

To run the container:
```bash
docker compose run franky-run bash
```
The container requires access to the host machines network *and* elevated user rights to allow the docker user to set RT capabilities of the processes run from within it.


#### Building franky with Docker

For building franky and its wheels, we provide another Docker container that can also be launched using docker-compose:

```bash
docker compose build franky-build
docker compose run --rm franky-build run-tests  # To run the tests
docker compose run --rm franky-build build-wheels  # To build wheels for all supported python versions
```


## Tutorial

Franky comes with both a C++ and Python API that differ only regarding real-time capability. We will introduce both languages next to each other. In your C++ project, just include `include <franky.hpp>` and link the library. For Python, just `import franky`. As a first example, only four lines of code are needed for simple robotic motions.

```c++
#include <franky.hpp>
using namespace franky;

// Connect to the robot with the FCI IP address
Robot robot("172.16.0.2");

// Reduce velocity and acceleration of the robot
robot.setDynamicRel(0.05);

// Move the end-effector 20cm in positive x-direction
auto motion = CartesianMotion(RobotPose(Affine({0.2, 0.0, 0.0}), 0.0), ReferenceType::Relative);

// Finally move the robot
robot.move(motion);
```

The corresponding program in Python is
```python
from franky import Affine, CartesianMotion, Robot, ReferenceType

robot = Robot("172.16.0.2")
robot.relative_dynamics_factor = 0.05

motion = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
robot.move(motion)
```

Furthermore, we will introduce methods for geometric calculations, for moving the robot according to different motion types, how to implement real-time reactions and changing waypoints in real time as well as controlling the gripper.


### Geometry

`franky.Affine` is a python wrapper for [Eigen::Affine3d](https://eigen.tuxfamily.org/dox/group__TutorialGeometry.html). 
It is used for Cartesian poses, frames and transformation. 
franky adds its own constructor, which takes a position and a quaternion as inputs:
```python
import math
from scipy.spatial.transform import Rotation
from franky import Affine

z_translation = Affine([0.0, 0.0, 0.5])

quat = Rotation.from_euler("xyz", [0, 0, math.pi / 2]).as_quat()
z_rotation = Affine([0.0, 0.0, 0.0], quat)

combined_transformation = z_translation * z_rotation
```

In all cases, distances are in [m] and rotations in [rad].

### Robot

We wrapped most of the libfanka API (including the RobotState or ErrorMessage) for Python. 
Moreover, we added methods to adapt the dynamics of the robot for all motions. 
The `rel` name denotes that this a factor of the maximum constraints of the robot.
```python
from franky import Robot

robot = Robot("172.16.0.2")

# Recover from errors
robot.recover_from_errors()

# Set velocity, acceleration and jerk to 5% of the maximum
robot.relative_dynamics_factor = 0.05

# Alternatively, you can define each constraint individually
robot.velocity_rel = 0.2
robot.acceleration_rel = 0.1
robot.jerk_rel = 0.01

# Get the current pose
current_pose = robot.current_pose
```


### Robot State

The robot state can be retrieved by calling the following methods:

* `state`: Object of type `franky.RobotState`, which is a wrapper of the libfranka [franka::RobotState](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html) structure.

* `current_cartesian_state`: Object of type `franky.CartesianState`, which contains the end-effector pose and velocity obtained from [franka::RobotState::O_T_EE](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#a193781d47722b32925e0ea7ac415f442) and [franka::RobotState::O_dP_EE_c](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#a4be112bd1a9a7d777a67aea4a18a8dcc).

* `current_joint_position`: Object of type `franky.JointState`, which contains the joint positions and velocities obtained from [franka::RobotState::q](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#ade3335d1ac2f6c44741a916d565f7091) and [franka::RobotState::dq](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#a706045af1b176049e9e56df755325bd2).

```python
robot = Robot("172.16.0.2")

# Get the current state as raw `franky.RobotState`
state = robot.state

# Get the robot's cartesian state
cartesian_state = robot.current_cartesian_state
robot_pose = cartesian_state.pose  # Contains end-effector pose and elbow position
ee_pose = robot_pose.end_effector_pose
elbow_pos = robot_pose.elbow_position
robot_velocity = cartesian_state.velocity  # Contains end-effector twist and elbow velocity
ee_twist = robot_velocity.end_effector_twist
elbow_vel = robot_velocity.elbow_velocity

# Get the robot's joint state
joint_state = robot.current_joint_state
joint_pos = joint_state.position
joint_vel = joint_state.velocity
```


### Motion Types

Franky defines a number of different motion types. 
In python, you can use them as follows:
```python
import math
from scipy.spatial.transform import Rotation
from franky import JointWaypointMotion, JointWaypoint, JointPositionStopMotion, CartesianMotion, \
    CartesianWaypointMotion, CartesianWaypoint, Affine, Twist, RobotPose, ReferenceType, CartesianPoseStopMotion, \
    CartesianState, JointState

# A point-to-point motion in the joint space
m1 = JointWaypointMotion([JointWaypoint([-0.3, 0.1, 0.3, -1.4, 0.1, 1.8, 0.7])])

# A motion in joint space with multiple waypoints
m2 = JointWaypointMotion([
    JointWaypoint([-0.3, 0.1, 0.3, -1.4, 0.1, 1.8, 0.7]),
    JointWaypoint([0.0, 0.3, 0.3, -1.5, -0.2, 1.5, 0.8]),
    JointWaypoint([0.1, 0.4, 0.3, -1.4, -0.3, 1.7, 0.9])
])

# Intermediate waypoints also permit to specify target velocities. The default target velocity is 0, meaning that the
# robot will stop at every waypoint.
m3 = JointWaypointMotion([
    JointWaypoint([-0.3, 0.1, 0.3, -1.4, 0.1, 1.8, 0.7]),
    JointWaypoint(
        JointState(
            position=[0.0, 0.3, 0.3, -1.5, -0.2, 1.5, 0.8],
            velocity=[0.1, 0.0, 0.0, 0.0, -0.0, 0.0, 0.0])),
    JointWaypoint([0.1, 0.4, 0.3, -1.4, -0.3, 1.7, 0.9])
])

# Stop the robot
m4 = JointPositionStopMotion()

# A linear motion in cartesian space
quat = Rotation.from_euler("xyz", [0, 0, math.pi / 2]).as_quat()
m5 = CartesianMotion(Affine([0.4, -0.2, 0.3], quat))
m6 = CartesianMotion(RobotPose(Affine([0.4, -0.2, 0.3], quat), elbow_position=0.3))  # With target elbow angle

# A linear motion in cartesian space relative to the initial position
# (Note that this motion is relative both in position and orientation. Hence, when the robot's end-effector is oriented
# differently, it will move in a different direction)
m7 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)

# Generalization of CartesianMotion that allows for multiple waypoints
m8 = CartesianWaypointMotion([
    CartesianWaypoint(RobotPose(Affine([0.4, -0.2, 0.3], quat), elbow_position=0.3)),
    # The following waypoint is relative to the prior one and 50% slower
    CartesianWaypoint(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative, RelativeDynamicsFactor(0.5, 1.0, 1.0))
])

# Cartesian waypoints also permit to specify target velocities
m9 = CartesianWaypointMotion([
    CartesianWaypoint(Affine([0.5, -0.2, 0.3], quat)),
    CartesianWaypoint(
        CartesianState(
            pose=Affine([0.4, -0.1, 0.3], quat),
            velocity=Twist([-0.01, 0.01, 0.0]))),
    CartesianWaypoint(Affine([0.3, 0.0, 0.3], quat))
])

# Stop the robot. The difference of JointPositionStopMotion to CartesianPoseStopMotion is that JointPositionStopMotion
# stops the robot in joint position control mode while CartesianPoseStopMotion stops it in cartesian pose control mode.
# The difference becomes relevant when asynchronous move commands are being sent (see below).
m10 = CartesianPoseStopMotion()
```

Every motion and waypoint type allows to adapt the dynamics (velocity, acceleration and jerk) by setting the respective `relative_dynamics_factor` parameter.

The real robot can be moved by applying a motion to the robot using `move`:
```python
robot.move(m1)
robot.move(m2)
```


### Real-Time Reactions

By adding reactions to the motion data, the robot can react to unforeseen events. 
In the Python API, you can define conditions by using a comparison between a robot's value and a given threshold. 
If the threshold is exceeded, the reaction fires. 
```python
from franky import CartesianMotion, Affine, ReferenceType, Measure, Reaction

motion = CartesianMotion(Affine([0.0, 0.0, 0.1]), ReferenceType.Relative)  # Move down 10cm

reaction_motion = CartesianMotion(Affine([0.0, 0.0, 0.01]), ReferenceType.Relative)  # Move up for 1cm

# Trigger reaction if the Z force is greater than 30N
reaction = Reaction(Measure.FORCE_Z > 30.0, reaction_motion)
motion.add_reaction(reaction)

robot.move(motion)
```

Possible values to measure are
* `Measure.FORCE_X,` `Measure.FORCE_Y,` `Measure.FORCE_Z`: Force in X, Y and Z direction
* `Measure.REL_TIME`: Time in seconds since the current motion started
* `Measure.ABS_TIME`: Time in seconds since the initial motion started

The difference between `Measure.REL_TIME` and `Measure.ABS_TIME` is that `Measure.REL_TIME` is reset to zero whenever a new motion starts (either by calling `Robot.move` or as a result of a triggered `Reaction`).
`Measure.ABS_TIME`, on the other hand, is only reset to zero when a motion terminates regularly without being interrupted and the robot stops moving.
Hence, `Measure.ABS_TIME` measures the total time in which the robot has moved without interruption.

`Measure` values support all classical arithmetic operations, like addition, subtraction, multiplication, division, and exponentiation (both as base and exponent).
```python
normal_force = (Measure.FORCE_X ** 2 + Measure.FORCE_Y ** 2 + Measure.FORCE_Z ** 2) ** 0.5
```

With arithmetic comparisons, conditions can be generated.
```python
normal_force_within_bounds = normal_force < 30.0
time_up = Measure.ABS_TIME > 10.0
```

Conditions support negation, conjunction (and), and disjunction (or):
```python
abort = ~normal_force_within_bounds | time_up
fast_abort = ~normal_force_within_bounds | time_up
```

To check whether a reaction has fired, a callback can be attached:
```python
from franky import RobotState

def reaction_callback(robot_state: RobotState, rel_time: float, abs_time: float):
    print(f"Reaction fired at {abs_time}.")

reaction.register_callback(reaction_callback)
```

Note that these callbacks are not executed in the control thread since they would otherwise block it.
Instead, they are put in a queue and executed by another thread.
While this scheme ensures that the control thread can always run, it cannot prevent that the queue grows indefinitely when the callbacks take more time to execute than it takes for new callbacks to be queued.
Hence, callbacks might be executed significantly after their respective reaction has fired if they are triggered in rapid succession or take a long time to execute.

In C++ you can additionally use lambdas to define more complex behaviours:
```c++
auto motion = CartesianMotion(RobotPose(Affine({0.0, 0.0, 0.2}), 0.0), ReferenceType::Relative);

// Stop motion if force is over 10N
auto stop_motion = StopMotion<franka::CartesianPose>()

motion
  .addReaction(
    Reaction(
      Measure::ForceZ() > 10.0,  // [N],
      stop_motion))
  .addReaction(
    Reaction(
      Condition(
        [](const franka::RobotState& state, double rel_time, double abs_time) {
          // Lambda condition
          return state.current_errors.self_collision_avoidance_violation;
        }),
      [](const franka::RobotState& state, double rel_time, double abs_time) {
        // Lambda reaction motion generator
        // (we are just returning a stop motion, but there could be arbitrary 
        // logic here for generating reaction motions)
        return StopMotion<franka::CartesianPose>();
      })
    ));

robot.move(motion)
```


### Real-Time Motion

By setting the `asynchronous` parameter of `Robot.move` to `True`, the function does not block until the motion finishes.
Instead, it returns immediately and, thus, allows the main thread to set new motions asynchronously. 
```python
import time
from franky import Affine, CartesianMotion, Robot, ReferenceType

robot = Robot("172.16.0.2")
robot.relative_dynamics_factor = 0.05

motion1 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
robot.move(motion1, asynchronous=True)

time.sleep(0.5)
motion2 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
robot.move(motion2, asynchronous=True)
```

By calling `Robot.join_motion` the main thread can be synchronized with the motion thread, as it will block until the robot finishes its motion.
```python
robot.join_motion()
```

Note that when exceptions occur during the asynchronous execution of a motion, they will not be thrown immediately.
Instead, the control thread stores the exception and terminates.
The next time `Robot.join_motion` or `Robot.move` are called, they will throw the stored exception in the main thread.
Hence, after an asynchronous motion has finished, make sure to call `Robot.join_motion` to ensure being notified of any exceptions that occurred during the motion.


### Gripper

In the `franky::Gripper` class, the default gripper force and gripper speed can be set. 
Then, additionally to the libfranka commands, the following helper methods can be used:

```c++
#include <franky.hpp>
#include <chrono>
#include <future>

auto gripper = franky::Gripper("172.16.0.2");

double speed = 0.02; // [m/s]
double force = 20.0; // [N]

// Move the fingers to a specific width (5cm)
bool success = gripper.move(0.05, speed);

// Grasp an object of unknown width
success &= gripper.grasp(0.0, speed, force, epsilon_outer=1.0);

// Get the width of the grasped object
double width = gripper.width();

// Release the object
gripper.open(speed);

// There are also asynchronous versions of the methods
std::future<bool> success_future = gripper.moveAsync(0.05, speed);

// Wait for 1s
if (!success_future.wait_for(std::chrono::seconds(1)) == std::future_status::ready) {
  // Get the result
  std::cout << "Success: " << success_future.get() << std::endl;
} else {
  gripper.stop();
  success_future.wait();
  std::cout << "Gripper motion timed out." << std::endl;
}
```

The Python API follows the c++ API closely:
```python
import franky

gripper = franky.Gripper("172.16.0.2")

speed = 0.02  # [m/s]
force = 20.0  # [N]

# Move the fingers to a specific width (5cm)
success = gripper.move(0.05, speed)

# Grasp an object of unknown width
success &= gripper.grasp(0.0, speed, force, epsilon_outer=1.0)

# Get the width of the grasped object
width = gripper.width

# Release the object
gripper.open(speed)

# There are also asynchronous versions of the methods
success_future = gripper.move_async(0.05, speed)

# Wait for 1s
if success_future.wait(1):
    print(f"Success: {success_future.get()}")
else:
    gripper.stop()
    success_future.wait()
    print("Gripper motion timed out.")
```

## Documentation

An auto-generated documentation can be found at [https://timschneider42.github.io/franky/](https://timschneider42.github.io/franky/).
Moreover, there are multiple examples for both C++ and Python in the [examples](https://github.com/TimSchneider42/franky/tree/master/examples) directory. 


## Development

Franky is written in C++17 and Python3.7. It is currently tested against following versions

- Libfranka v0.7.1, v0.8.0, v0.9.2, v0.10.0, v0.11.0, v0.12.1, v0.13.3
- Eigen v3.4.0
- Pybind11 v2.11.1
- Python 3.7, 3.8, 3.9, 3.10, 3.11, 3.12
- Catch2 v2.13.8 (for testing only)

## License

For non-commercial applications, this software is licensed under the LGPL v3.0. 
If you want to use franky within commercial applications or under a different license, please contact us for individual agreements.

            

Raw data

            {
    "_id": null,
    "home_page": "https://github.com/TimSchneider42/franky",
    "name": "franky-panda",
    "maintainer": null,
    "docs_url": null,
    "requires_python": ">=3.6",
    "maintainer_email": null,
    "keywords": "robot, robotics, trajectory-generation, motion-control",
    "author": "Tim Schneider",
    "author_email": "tim@robot-learning.de",
    "download_url": null,
    "platform": null,
    "description": "<div align=\"center\">\n  <img width=\"340\" src=\"https://raw.githubusercontent.com/timschneider42/franky/master/doc/logo.svg?sanitize=true\">\n  <h3 align=\"center\">\n    High-Level Motion Library for the Franka Emika Robot\n  </h3>\n</div>\n<p align=\"center\">\n  <a href=\"https://github.com/timschneider42/franky/actions\">\n    <img src=\"https://github.com/timschneider42/franky/workflows/CI/badge.svg\" alt=\"CI\">\n  </a>\n\n  <a href=\"https://github.com/timschneider42/franky/actions\">\n    <img src=\"https://github.com/timschneider42/franky/workflows/Publish/badge.svg\" alt=\"Publish\">\n  </a>\n\n  <a href=\"https://github.com/timschneider42/franky/issues\">\n    <img src=\"https://img.shields.io/github/issues/timschneider42/franky.svg\" alt=\"Issues\">\n  </a>\n\n  <a href=\"https://github.com/timschneider42/franky/releases\">\n    <img src=\"https://img.shields.io/github/v/release/timschneider42/franky.svg?include_prereleases&sort=semver\" alt=\"Releases\">\n  </a>\n\n  <a href=\"https://github.com/timschneider42/franky/blob/master/LICENSE\">\n    <img src=\"https://img.shields.io/badge/license-LGPL-green.svg\" alt=\"LGPL\">\n  </a>\n</p>\n\n\nFranky is a high-level motion library (both C++ and Python) for the Franka Emika robot.\nIt adds a Python wrapper around [libfranka](https://frankaemika.github.io/docs/libfranka.html), while replacing necessary real-time programming with higher-level motion commands.\nAs franky focuses on making real-time trajectory generation easy, it allows the robot to react to unforeseen events.\n\n\n## Differences to frankx\nFranky is a fork of [frankx](https://github.com/pantor/frankx), though both codebase and functionality differ substantially from frankx by now.\nIn particular, franky provides the following new features/improvements:\n* [Motions can be updated asynchronously.](#real-time-motion)\n* [Reactions allow for the registration of callbacks instead of just printing to stdout when fired.](#real-time-reactions)\n* [The robot state is also available during control.](#robot-state)\n* A larger part of the libfranka API is exposed to python (e.g.,`setCollisionBehavior`, `setJoinImpedance`, and `setCartesianImpedance`).\n* Cartesian motion generation handles boundaries in Euler angles properly.\n* [There is a new joint motion type that supports waypoints.](#motion-types)\n* [The signature of `Affine` changed.](#geometry) `Affine` does not handle elbow positions anymore. Instead, a new class `RobotPose` stores both the end-effector pose and optionally the elbow position.\n* The `MotionData` class does not exist anymore. Instead, reactions and other settings moved to `Motion`.\n* [The `Measure` class allows for arithmetic operations.](#real-time-reactions)\n* Exceptions caused by libfranka are raised properly instead of being printed to stdout.\n* [We provide wheels for both Franka Research 3 and the older Franka Panda](#installation)\n\n## Setup\nTo install franky, you have to follow three steps:\n1. Ensure that you are using a realtime kernel\n2. Ensure that the executing user has permission to run real-time applications\n3. Install franky via pip or build it from the sources\n\n### Installing a real-time kernel\n\nIn order for franky to function properly, it requires the underlying OS to use a realtime kernel. \nOtherwise, you might see `communication_constrains_violation` errors.\n\nTo check whether your system is currently using a real-time kernel, type `uname -a`.\nYou should see something like this:\n```bash\n$ uname -a\nLinux [PCNAME] 5.15.0-1056-realtime #63-Ubuntu SMP PREEMPT_RT ...\n```\nIf it does not say PREEMPT_RT, you are not currently running a real-time kernel.\n\nThere are multiple ways of installing a real-time kernel. You can [build it from source](https://frankaemika.github.io/docs/installation_linux.html#setting-up-the-real-time-kernel) or, if you are using Ubuntu, it can be [enabled through Ubuntu Pro](https://ubuntu.com/real-time).\n\n### Allowing the executing user to run real-time applications\n\nFirst, create a group `realtime` and add your user (or whoever is running franky) to this group:\n```bash\nsudo addgroup realtime\nsudo usermod -a -G realtime $(whoami)\n```\n\nAfterward, add the following limits to the real-time group in /etc/security/limits.conf:\n```\n@realtime soft rtprio 99\n@realtime soft priority 99\n@realtime soft memlock 102400\n@realtime hard rtprio 99\n@realtime hard priority 99\n@realtime hard memlock 102400\n```\nLog out and log in again to let the changes take effect.\n\nTo verify that the changes were applied, check if your user is in the `realtime` group:\n```bash\n$ groups\n... realtime\n```\nIf realtime is not listed in your groups, try rebooting.\n\n### Installing franky\nTo start using franky with Python and libfranka *0.13.3*, just install it via\n```bash\npip install franky-panda\n```\nWe also provide wheels for libfranka versions *0.7.1*, *0.8.0*, *0.9.2*, *0.10.0*, *0.11.0*, *0.12.1*, *0.13.3*. \nThey can be installed via\n```bash\nVERSION=0-9-2\nwget https://github.com/TimSchneider42/franky/releases/latest/download/libfranka_${VERSION}_wheels.zip\nunzip libfranka_${VERSION}_wheels.zip\npip install --no-index --find-links=./dist franky-panda\n```\n\nFranky is based on [libfranka](https://github.com/frankaemika/libfranka), [Eigen](https://eigen.tuxfamily.org) for transformation calculations and [pybind11](https://github.com/pybind/pybind11) for the Python bindings.\nAs the Franka is sensitive to acceleration discontinuities, it requires jerk-constrained motion generation, for which franky uses the [Ruckig](https://ruckig.com) community version for Online Trajectory Generation (OTG).\n\nAfter installing the dependencies (the exact versions can be found [here](#development)), you can build and install franky via\n```bash\ngit clone --recurse-submodules git@github.com:timschneider42/franky.git\ncd franky\nmkdir -p build\ncd build\ncmake -DCMAKE_BUILD_TYPE=Release ..\nmake\nmake install\n```\n\nTo use franky, you can also include it as a subproject in your parent CMake via `add_subdirectory(franky)` and then `target_link_libraries(<target> libfranky)`. \n\nIf you need only the Python module, you can install franky via\n```bash\npip install .\n```\nMake sure that the built library `_franky.cpython-3**-****-linux-gnu.so` is in the Python path, e.g. by adjusting `PYTHONPATH` accordingly.\n\n\n#### Using Docker\n\nTo use franky within Docker we provide a [Dockerfile](docker/run/Dockerfile) and accompanying [docker-compose](docker-compose.yml) file.\n\n```bash\ngit clone https://github.com/timschneider42/franky.git\ncd franky/\ndocker compose build franky-run\n```\n\nTo use another version of libfranka than the default (v0.13.3) add a build argument:\n```bash\ndocker compose build franky-run --build-arg LIBFRANKA_VERSION=0.9.2\n```\n\nTo run the container:\n```bash\ndocker compose run franky-run bash\n```\nThe container requires access to the host machines network *and* elevated user rights to allow the docker user to set RT capabilities of the processes run from within it.\n\n\n#### Building franky with Docker\n\nFor building franky and its wheels, we provide another Docker container that can also be launched using docker-compose:\n\n```bash\ndocker compose build franky-build\ndocker compose run --rm franky-build run-tests  # To run the tests\ndocker compose run --rm franky-build build-wheels  # To build wheels for all supported python versions\n```\n\n\n## Tutorial\n\nFranky comes with both a C++ and Python API that differ only regarding real-time capability. We will introduce both languages next to each other. In your C++ project, just include `include <franky.hpp>` and link the library. For Python, just `import franky`. As a first example, only four lines of code are needed for simple robotic motions.\n\n```c++\n#include <franky.hpp>\nusing namespace franky;\n\n// Connect to the robot with the FCI IP address\nRobot robot(\"172.16.0.2\");\n\n// Reduce velocity and acceleration of the robot\nrobot.setDynamicRel(0.05);\n\n// Move the end-effector 20cm in positive x-direction\nauto motion = CartesianMotion(RobotPose(Affine({0.2, 0.0, 0.0}), 0.0), ReferenceType::Relative);\n\n// Finally move the robot\nrobot.move(motion);\n```\n\nThe corresponding program in Python is\n```python\nfrom franky import Affine, CartesianMotion, Robot, ReferenceType\n\nrobot = Robot(\"172.16.0.2\")\nrobot.relative_dynamics_factor = 0.05\n\nmotion = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)\nrobot.move(motion)\n```\n\nFurthermore, we will introduce methods for geometric calculations, for moving the robot according to different motion types, how to implement real-time reactions and changing waypoints in real time as well as controlling the gripper.\n\n\n### Geometry\n\n`franky.Affine` is a python wrapper for [Eigen::Affine3d](https://eigen.tuxfamily.org/dox/group__TutorialGeometry.html). \nIt is used for Cartesian poses, frames and transformation. \nfranky adds its own constructor, which takes a position and a quaternion as inputs:\n```python\nimport math\nfrom scipy.spatial.transform import Rotation\nfrom franky import Affine\n\nz_translation = Affine([0.0, 0.0, 0.5])\n\nquat = Rotation.from_euler(\"xyz\", [0, 0, math.pi / 2]).as_quat()\nz_rotation = Affine([0.0, 0.0, 0.0], quat)\n\ncombined_transformation = z_translation * z_rotation\n```\n\nIn all cases, distances are in [m] and rotations in [rad].\n\n### Robot\n\nWe wrapped most of the libfanka API (including the RobotState or ErrorMessage) for Python. \nMoreover, we added methods to adapt the dynamics of the robot for all motions. \nThe `rel` name denotes that this a factor of the maximum constraints of the robot.\n```python\nfrom franky import Robot\n\nrobot = Robot(\"172.16.0.2\")\n\n# Recover from errors\nrobot.recover_from_errors()\n\n# Set velocity, acceleration and jerk to 5% of the maximum\nrobot.relative_dynamics_factor = 0.05\n\n# Alternatively, you can define each constraint individually\nrobot.velocity_rel = 0.2\nrobot.acceleration_rel = 0.1\nrobot.jerk_rel = 0.01\n\n# Get the current pose\ncurrent_pose = robot.current_pose\n```\n\n\n### Robot State\n\nThe robot state can be retrieved by calling the following methods:\n\n* `state`: Object of type `franky.RobotState`, which is a wrapper of the libfranka [franka::RobotState](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html) structure.\n\n* `current_cartesian_state`: Object of type `franky.CartesianState`, which contains the end-effector pose and velocity obtained from [franka::RobotState::O_T_EE](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#a193781d47722b32925e0ea7ac415f442) and [franka::RobotState::O_dP_EE_c](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#a4be112bd1a9a7d777a67aea4a18a8dcc).\n\n* `current_joint_position`: Object of type `franky.JointState`, which contains the joint positions and velocities obtained from [franka::RobotState::q](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#ade3335d1ac2f6c44741a916d565f7091) and [franka::RobotState::dq](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#a706045af1b176049e9e56df755325bd2).\n\n```python\nrobot = Robot(\"172.16.0.2\")\n\n# Get the current state as raw `franky.RobotState`\nstate = robot.state\n\n# Get the robot's cartesian state\ncartesian_state = robot.current_cartesian_state\nrobot_pose = cartesian_state.pose  # Contains end-effector pose and elbow position\nee_pose = robot_pose.end_effector_pose\nelbow_pos = robot_pose.elbow_position\nrobot_velocity = cartesian_state.velocity  # Contains end-effector twist and elbow velocity\nee_twist = robot_velocity.end_effector_twist\nelbow_vel = robot_velocity.elbow_velocity\n\n# Get the robot's joint state\njoint_state = robot.current_joint_state\njoint_pos = joint_state.position\njoint_vel = joint_state.velocity\n```\n\n\n### Motion Types\n\nFranky defines a number of different motion types. \nIn python, you can use them as follows:\n```python\nimport math\nfrom scipy.spatial.transform import Rotation\nfrom franky import JointWaypointMotion, JointWaypoint, JointPositionStopMotion, CartesianMotion, \\\n    CartesianWaypointMotion, CartesianWaypoint, Affine, Twist, RobotPose, ReferenceType, CartesianPoseStopMotion, \\\n    CartesianState, JointState\n\n# A point-to-point motion in the joint space\nm1 = JointWaypointMotion([JointWaypoint([-0.3, 0.1, 0.3, -1.4, 0.1, 1.8, 0.7])])\n\n# A motion in joint space with multiple waypoints\nm2 = JointWaypointMotion([\n    JointWaypoint([-0.3, 0.1, 0.3, -1.4, 0.1, 1.8, 0.7]),\n    JointWaypoint([0.0, 0.3, 0.3, -1.5, -0.2, 1.5, 0.8]),\n    JointWaypoint([0.1, 0.4, 0.3, -1.4, -0.3, 1.7, 0.9])\n])\n\n# Intermediate waypoints also permit to specify target velocities. The default target velocity is 0, meaning that the\n# robot will stop at every waypoint.\nm3 = JointWaypointMotion([\n    JointWaypoint([-0.3, 0.1, 0.3, -1.4, 0.1, 1.8, 0.7]),\n    JointWaypoint(\n        JointState(\n            position=[0.0, 0.3, 0.3, -1.5, -0.2, 1.5, 0.8],\n            velocity=[0.1, 0.0, 0.0, 0.0, -0.0, 0.0, 0.0])),\n    JointWaypoint([0.1, 0.4, 0.3, -1.4, -0.3, 1.7, 0.9])\n])\n\n# Stop the robot\nm4 = JointPositionStopMotion()\n\n# A linear motion in cartesian space\nquat = Rotation.from_euler(\"xyz\", [0, 0, math.pi / 2]).as_quat()\nm5 = CartesianMotion(Affine([0.4, -0.2, 0.3], quat))\nm6 = CartesianMotion(RobotPose(Affine([0.4, -0.2, 0.3], quat), elbow_position=0.3))  # With target elbow angle\n\n# A linear motion in cartesian space relative to the initial position\n# (Note that this motion is relative both in position and orientation. Hence, when the robot's end-effector is oriented\n# differently, it will move in a different direction)\nm7 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)\n\n# Generalization of CartesianMotion that allows for multiple waypoints\nm8 = CartesianWaypointMotion([\n    CartesianWaypoint(RobotPose(Affine([0.4, -0.2, 0.3], quat), elbow_position=0.3)),\n    # The following waypoint is relative to the prior one and 50% slower\n    CartesianWaypoint(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative, RelativeDynamicsFactor(0.5, 1.0, 1.0))\n])\n\n# Cartesian waypoints also permit to specify target velocities\nm9 = CartesianWaypointMotion([\n    CartesianWaypoint(Affine([0.5, -0.2, 0.3], quat)),\n    CartesianWaypoint(\n        CartesianState(\n            pose=Affine([0.4, -0.1, 0.3], quat),\n            velocity=Twist([-0.01, 0.01, 0.0]))),\n    CartesianWaypoint(Affine([0.3, 0.0, 0.3], quat))\n])\n\n# Stop the robot. The difference of JointPositionStopMotion to CartesianPoseStopMotion is that JointPositionStopMotion\n# stops the robot in joint position control mode while CartesianPoseStopMotion stops it in cartesian pose control mode.\n# The difference becomes relevant when asynchronous move commands are being sent (see below).\nm10 = CartesianPoseStopMotion()\n```\n\nEvery motion and waypoint type allows to adapt the dynamics (velocity, acceleration and jerk) by setting the respective `relative_dynamics_factor` parameter.\n\nThe real robot can be moved by applying a motion to the robot using `move`:\n```python\nrobot.move(m1)\nrobot.move(m2)\n```\n\n\n### Real-Time Reactions\n\nBy adding reactions to the motion data, the robot can react to unforeseen events. \nIn the Python API, you can define conditions by using a comparison between a robot's value and a given threshold. \nIf the threshold is exceeded, the reaction fires. \n```python\nfrom franky import CartesianMotion, Affine, ReferenceType, Measure, Reaction\n\nmotion = CartesianMotion(Affine([0.0, 0.0, 0.1]), ReferenceType.Relative)  # Move down 10cm\n\nreaction_motion = CartesianMotion(Affine([0.0, 0.0, 0.01]), ReferenceType.Relative)  # Move up for 1cm\n\n# Trigger reaction if the Z force is greater than 30N\nreaction = Reaction(Measure.FORCE_Z > 30.0, reaction_motion)\nmotion.add_reaction(reaction)\n\nrobot.move(motion)\n```\n\nPossible values to measure are\n* `Measure.FORCE_X,` `Measure.FORCE_Y,` `Measure.FORCE_Z`: Force in X, Y and Z direction\n* `Measure.REL_TIME`: Time in seconds since the current motion started\n* `Measure.ABS_TIME`: Time in seconds since the initial motion started\n\nThe difference between `Measure.REL_TIME` and `Measure.ABS_TIME` is that `Measure.REL_TIME` is reset to zero whenever a new motion starts (either by calling `Robot.move` or as a result of a triggered `Reaction`).\n`Measure.ABS_TIME`, on the other hand, is only reset to zero when a motion terminates regularly without being interrupted and the robot stops moving.\nHence, `Measure.ABS_TIME` measures the total time in which the robot has moved without interruption.\n\n`Measure` values support all classical arithmetic operations, like addition, subtraction, multiplication, division, and exponentiation (both as base and exponent).\n```python\nnormal_force = (Measure.FORCE_X ** 2 + Measure.FORCE_Y ** 2 + Measure.FORCE_Z ** 2) ** 0.5\n```\n\nWith arithmetic comparisons, conditions can be generated.\n```python\nnormal_force_within_bounds = normal_force < 30.0\ntime_up = Measure.ABS_TIME > 10.0\n```\n\nConditions support negation, conjunction (and), and disjunction (or):\n```python\nabort = ~normal_force_within_bounds | time_up\nfast_abort = ~normal_force_within_bounds | time_up\n```\n\nTo check whether a reaction has fired, a callback can be attached:\n```python\nfrom franky import RobotState\n\ndef reaction_callback(robot_state: RobotState, rel_time: float, abs_time: float):\n    print(f\"Reaction fired at {abs_time}.\")\n\nreaction.register_callback(reaction_callback)\n```\n\nNote that these callbacks are not executed in the control thread since they would otherwise block it.\nInstead, they are put in a queue and executed by another thread.\nWhile this scheme ensures that the control thread can always run, it cannot prevent that the queue grows indefinitely when the callbacks take more time to execute than it takes for new callbacks to be queued.\nHence, callbacks might be executed significantly after their respective reaction has fired if they are triggered in rapid succession or take a long time to execute.\n\nIn C++ you can additionally use lambdas to define more complex behaviours:\n```c++\nauto motion = CartesianMotion(RobotPose(Affine({0.0, 0.0, 0.2}), 0.0), ReferenceType::Relative);\n\n// Stop motion if force is over 10N\nauto stop_motion = StopMotion<franka::CartesianPose>()\n\nmotion\n  .addReaction(\n    Reaction(\n      Measure::ForceZ() > 10.0,  // [N],\n      stop_motion))\n  .addReaction(\n    Reaction(\n      Condition(\n        [](const franka::RobotState& state, double rel_time, double abs_time) {\n          // Lambda condition\n          return state.current_errors.self_collision_avoidance_violation;\n        }),\n      [](const franka::RobotState& state, double rel_time, double abs_time) {\n        // Lambda reaction motion generator\n        // (we are just returning a stop motion, but there could be arbitrary \n        // logic here for generating reaction motions)\n        return StopMotion<franka::CartesianPose>();\n      })\n    ));\n\nrobot.move(motion)\n```\n\n\n### Real-Time Motion\n\nBy setting the `asynchronous` parameter of `Robot.move` to `True`, the function does not block until the motion finishes.\nInstead, it returns immediately and, thus, allows the main thread to set new motions asynchronously. \n```python\nimport time\nfrom franky import Affine, CartesianMotion, Robot, ReferenceType\n\nrobot = Robot(\"172.16.0.2\")\nrobot.relative_dynamics_factor = 0.05\n\nmotion1 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)\nrobot.move(motion1, asynchronous=True)\n\ntime.sleep(0.5)\nmotion2 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)\nrobot.move(motion2, asynchronous=True)\n```\n\nBy calling `Robot.join_motion` the main thread can be synchronized with the motion thread, as it will block until the robot finishes its motion.\n```python\nrobot.join_motion()\n```\n\nNote that when exceptions occur during the asynchronous execution of a motion, they will not be thrown immediately.\nInstead, the control thread stores the exception and terminates.\nThe next time `Robot.join_motion` or `Robot.move` are called, they will throw the stored exception in the main thread.\nHence, after an asynchronous motion has finished, make sure to call `Robot.join_motion` to ensure being notified of any exceptions that occurred during the motion.\n\n\n### Gripper\n\nIn the `franky::Gripper` class, the default gripper force and gripper speed can be set. \nThen, additionally to the libfranka commands, the following helper methods can be used:\n\n```c++\n#include <franky.hpp>\n#include <chrono>\n#include <future>\n\nauto gripper = franky::Gripper(\"172.16.0.2\");\n\ndouble speed = 0.02; // [m/s]\ndouble force = 20.0; // [N]\n\n// Move the fingers to a specific width (5cm)\nbool success = gripper.move(0.05, speed);\n\n// Grasp an object of unknown width\nsuccess &= gripper.grasp(0.0, speed, force, epsilon_outer=1.0);\n\n// Get the width of the grasped object\ndouble width = gripper.width();\n\n// Release the object\ngripper.open(speed);\n\n// There are also asynchronous versions of the methods\nstd::future<bool> success_future = gripper.moveAsync(0.05, speed);\n\n// Wait for 1s\nif (!success_future.wait_for(std::chrono::seconds(1)) == std::future_status::ready) {\n  // Get the result\n  std::cout << \"Success: \" << success_future.get() << std::endl;\n} else {\n  gripper.stop();\n  success_future.wait();\n  std::cout << \"Gripper motion timed out.\" << std::endl;\n}\n```\n\nThe Python API follows the c++ API closely:\n```python\nimport franky\n\ngripper = franky.Gripper(\"172.16.0.2\")\n\nspeed = 0.02  # [m/s]\nforce = 20.0  # [N]\n\n# Move the fingers to a specific width (5cm)\nsuccess = gripper.move(0.05, speed)\n\n# Grasp an object of unknown width\nsuccess &= gripper.grasp(0.0, speed, force, epsilon_outer=1.0)\n\n# Get the width of the grasped object\nwidth = gripper.width\n\n# Release the object\ngripper.open(speed)\n\n# There are also asynchronous versions of the methods\nsuccess_future = gripper.move_async(0.05, speed)\n\n# Wait for 1s\nif success_future.wait(1):\n    print(f\"Success: {success_future.get()}\")\nelse:\n    gripper.stop()\n    success_future.wait()\n    print(\"Gripper motion timed out.\")\n```\n\n## Documentation\n\nAn auto-generated documentation can be found at [https://timschneider42.github.io/franky/](https://timschneider42.github.io/franky/).\nMoreover, there are multiple examples for both C++ and Python in the [examples](https://github.com/TimSchneider42/franky/tree/master/examples) directory. \n\n\n## Development\n\nFranky is written in C++17 and Python3.7. It is currently tested against following versions\n\n- Libfranka v0.7.1, v0.8.0, v0.9.2, v0.10.0, v0.11.0, v0.12.1, v0.13.3\n- Eigen v3.4.0\n- Pybind11 v2.11.1\n- Python 3.7, 3.8, 3.9, 3.10, 3.11, 3.12\n- Catch2 v2.13.8 (for testing only)\n\n## License\n\nFor non-commercial applications, this software is licensed under the LGPL v3.0. \nIf you want to use franky within commercial applications or under a different license, please contact us for individual agreements.\n",
    "bugtrack_url": null,
    "license": "LGPL",
    "summary": "High-Level Motion Library for the Franka Panda Robot (fork of frankx)",
    "version": "0.9.1",
    "project_urls": {
        "Homepage": "https://github.com/TimSchneider42/franky"
    },
    "split_keywords": [
        "robot",
        " robotics",
        " trajectory-generation",
        " motion-control"
    ],
    "urls": [
        {
            "comment_text": "",
            "digests": {
                "blake2b_256": "708e3e67e80acc1ecba57ecc1da13899abf1037f3b5257b74ffd91516fde4f97",
                "md5": "b5177eb4398e4b5cf607878cbfc0c3ff",
                "sha256": "820b10417f5126c66f950b47ad6fa49db858134ec46d14d639d542d3fd9ff580"
            },
            "downloads": -1,
            "filename": "franky_panda-0.9.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl",
            "has_sig": false,
            "md5_digest": "b5177eb4398e4b5cf607878cbfc0c3ff",
            "packagetype": "bdist_wheel",
            "python_version": "cp310",
            "requires_python": ">=3.6",
            "size": 1927141,
            "upload_time": "2024-06-04T21:19:25",
            "upload_time_iso_8601": "2024-06-04T21:19:25.339481Z",
            "url": "https://files.pythonhosted.org/packages/70/8e/3e67e80acc1ecba57ecc1da13899abf1037f3b5257b74ffd91516fde4f97/franky_panda-0.9.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl",
            "yanked": false,
            "yanked_reason": null
        },
        {
            "comment_text": "",
            "digests": {
                "blake2b_256": "944be4f547b49b729bab30fa5d1b2449e209bd431bd866f962370074629a4c80",
                "md5": "54b68fb382bd419a425aff683e999fa6",
                "sha256": "7cf89f1d6fa3c42af57da7c2b0d25140d0ba8e9e6b37975fadd6fe5580767ecd"
            },
            "downloads": -1,
            "filename": "franky_panda-0.9.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl",
            "has_sig": false,
            "md5_digest": "54b68fb382bd419a425aff683e999fa6",
            "packagetype": "bdist_wheel",
            "python_version": "cp311",
            "requires_python": ">=3.6",
            "size": 1929043,
            "upload_time": "2024-06-04T21:19:27",
            "upload_time_iso_8601": "2024-06-04T21:19:27.364381Z",
            "url": "https://files.pythonhosted.org/packages/94/4b/e4f547b49b729bab30fa5d1b2449e209bd431bd866f962370074629a4c80/franky_panda-0.9.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl",
            "yanked": false,
            "yanked_reason": null
        },
        {
            "comment_text": "",
            "digests": {
                "blake2b_256": "7146956b4a94bee99f257dca04b73b266cf36a3844902c7d56daa46323515b53",
                "md5": "e8e169ce7e70c2e78765ca61bce6a435",
                "sha256": "6c9f73faf8dbba0408c9087535256a254f27b0116013fb223bb6fa4c1c6cc322"
            },
            "downloads": -1,
            "filename": "franky_panda-0.9.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl",
            "has_sig": false,
            "md5_digest": "e8e169ce7e70c2e78765ca61bce6a435",
            "packagetype": "bdist_wheel",
            "python_version": "cp312",
            "requires_python": ">=3.6",
            "size": 1927507,
            "upload_time": "2024-06-04T21:19:29",
            "upload_time_iso_8601": "2024-06-04T21:19:29.225784Z",
            "url": "https://files.pythonhosted.org/packages/71/46/956b4a94bee99f257dca04b73b266cf36a3844902c7d56daa46323515b53/franky_panda-0.9.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl",
            "yanked": false,
            "yanked_reason": null
        },
        {
            "comment_text": "",
            "digests": {
                "blake2b_256": "9353ac541f8a565bc5b9fca75b9c5ff199a9d3aa80aa86ca985d37f2c98e5b20",
                "md5": "807f69fd5191f03362c5afccac5a4dce",
                "sha256": "5eca2023dbbd900fd90cde0fbc6c9002665d007279d8e9555aca6328955b3c30"
            },
            "downloads": -1,
            "filename": "franky_panda-0.9.1-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl",
            "has_sig": false,
            "md5_digest": "807f69fd5191f03362c5afccac5a4dce",
            "packagetype": "bdist_wheel",
            "python_version": "cp37",
            "requires_python": ">=3.6",
            "size": 1935781,
            "upload_time": "2024-06-04T21:19:31",
            "upload_time_iso_8601": "2024-06-04T21:19:31.094946Z",
            "url": "https://files.pythonhosted.org/packages/93/53/ac541f8a565bc5b9fca75b9c5ff199a9d3aa80aa86ca985d37f2c98e5b20/franky_panda-0.9.1-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl",
            "yanked": false,
            "yanked_reason": null
        },
        {
            "comment_text": "",
            "digests": {
                "blake2b_256": "e23a0411678c7569687c85f11cf50fe37b4d54b1e3bfce51840535e7626147da",
                "md5": "4a0b997417099d126404118056376af7",
                "sha256": "a3512894ae2900d8894f3e910b3f3e63cb1704d0f3102d5bc4ae119e9d200d11"
            },
            "downloads": -1,
            "filename": "franky_panda-0.9.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl",
            "has_sig": false,
            "md5_digest": "4a0b997417099d126404118056376af7",
            "packagetype": "bdist_wheel",
            "python_version": "cp38",
            "requires_python": ">=3.6",
            "size": 1927965,
            "upload_time": "2024-06-04T21:19:33",
            "upload_time_iso_8601": "2024-06-04T21:19:33.582782Z",
            "url": "https://files.pythonhosted.org/packages/e2/3a/0411678c7569687c85f11cf50fe37b4d54b1e3bfce51840535e7626147da/franky_panda-0.9.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl",
            "yanked": false,
            "yanked_reason": null
        },
        {
            "comment_text": "",
            "digests": {
                "blake2b_256": "4ae1dabbb512db45104293d9c35c307deb81db80a010cc22be0ed738a9d11bde",
                "md5": "27d2fef32e566a05e285dc3b131e7585",
                "sha256": "374ffe2535a32597ec001f90f7b17a890015fa30008395a545ffbcf25bef6465"
            },
            "downloads": -1,
            "filename": "franky_panda-0.9.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl",
            "has_sig": false,
            "md5_digest": "27d2fef32e566a05e285dc3b131e7585",
            "packagetype": "bdist_wheel",
            "python_version": "cp39",
            "requires_python": ">=3.6",
            "size": 1927180,
            "upload_time": "2024-06-04T21:19:36",
            "upload_time_iso_8601": "2024-06-04T21:19:36.034389Z",
            "url": "https://files.pythonhosted.org/packages/4a/e1/dabbb512db45104293d9c35c307deb81db80a010cc22be0ed738a9d11bde/franky_panda-0.9.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl",
            "yanked": false,
            "yanked_reason": null
        }
    ],
    "upload_time": "2024-06-04 21:19:25",
    "github": true,
    "gitlab": false,
    "bitbucket": false,
    "codeberg": false,
    "github_user": "TimSchneider42",
    "github_project": "franky",
    "travis_ci": false,
    "coveralls": false,
    "github_actions": true,
    "lcname": "franky-panda"
}
        
Elapsed time: 0.28311s