Franky 1.0.2
A High-Level Motion API for Franka
|
Franky is a high-level control library for Franka robots offering Python and C++ support. By providing a high-level control interface, Franky eliminates the need for strict real-time programming at 1 kHz, making control from non-real-time environments, such as Python programs, feasible. Instead of relying on low-level control commands, Franky expects high-level position or velocity targets and uses Ruckig to plan time-optimal trajectories in real-time.
Although Python does not provide real-time guarantees, Franky strives to maintain as much real-time control as possible. Motions can be preempted at any moment, prompting Franky to re-plan trajectories on the fly. To handle unforeseen situations—such as unexpected contact with the environment — Franky includes a reaction system that allows to update motion commands dynamically. Furthermore, most non-real-time functionality of libfranka, such as Gripper control is made directly available in Python.
Check out the tutorial and the examples for an introduction. The full documentation can be found at https://timschneider42.github.io/franky/.
pip install
— no ROS at all.Real-time kernel already installed and real-time permissions granted? Just install Franky via
otherwise, follow the setup instructions first.
Now we are already ready to go! Unlock the brakes in the web interface, activate FCI, and start coding:
If you are seeing server version mismatch errors, such as
then your Franka robot is either not on the most recent firmware version or you are using the older Franka Panda model. In any case, it's no big deal; just check here which libfranka version you need and follow our [instructions](installing-frankly) to install the appropriate Franky wheels.
To install Franky, you have to follow three steps:
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:
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 or, if you are using Ubuntu, it can be enabled through Ubuntu Pro.
First, create a group realtime
and add your user (or whoever is running Franky) to this group:
Afterward, add the following limits to the real-time group in /etc/security/limits.conf:
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:
If realtime is not listed in your groups, try rebooting.
To start using Franky with Python and libfranka 0.15.0, just install it via
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, 0.14.2, and 0.15.0. They can be installed via
Franky is based on libfranka, Eigen for transformation calculations and 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 community version for Online Trajectory Generation (OTG).
After installing the dependencies (the exact versions can be found here), you can build and install Franky via
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> franky)
.
If you need only the Python module, you can install Franky via
Make sure that the built library _franky.cpython-3**-****-linux-gnu.so
is in the Python path, e.g. by adjusting PYTHONPATH
accordingly.
To use Franky within Docker we provide a Dockerfile and accompanying docker-compose file.
To use another version of libfranka than the default (0.15.0) add a build argument:
To run the container:
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.
For building Franky and its wheels, we provide another Docker container that can also be launched using docker-compose:
Yes. However, you need to set IGNORE_PREEMPT_RT_PRESENCE=1
during the installation and all subsequent updates of the CUDA drivers on the real-time kernel.
First, make sure that you have rebooted your system after installing the real-time kernel. Then, add IGNORE_PREEMPT_RT_PRESENCE=1
to /etc/environment
, call export IGNORE_PREEMPT_RT_PRESENCE=1
to also set it in the current session and follow the instructions of Nvidia to install CUDA on your system.
If you are on Ubuntu, you can also use this script to install CUDA on your real-time system:
Alternatively, if you are a cowboy and do not care about security, you can also use this one-liner to directly call the script without checking it:
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.
The corresponding program in Python is
Before executing any code, make sure that you have enabled the Franka Control Interface (FCI) in the Franka UI web interface.
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.
franky.Affine
is a python wrapper for Eigen::Affine3d. It is used for Cartesian poses, frames and transformation. franky adds its own constructor, which takes a position and a quaternion as inputs:
In all cases, distances are in [m] and rotations in [rad].
Franky exposes most of the libfanka API for Python. Moreover, we added methods to adapt the dynamics limits of the robot for all motions.
The robot state can be retrieved by accessing the following properties:
state
: Object of type franky.RobotState
, which extends the libfranka franka::RobotState structure by additional state elements.current_cartesian_state
: Object of type franky.CartesianState
, which contains the end-effector pose and velocity obtained from franka::RobotState::O_T_EE and franka::RobotState::O_dP_EE_c.current_joint_state
: Object of type franky.JointState
, which contains the joint positions and velocities obtained from franka::RobotState::q and franka::RobotState::dq.For a full list of state-related features, check the Robot and Model sections of the documentation.
Franky currently supports four different impedance control modes: joint position control, joint velocity control, cartesian position control, and cartesian velocity control. Each of these control modes is invoked by passing the robot an appropriate Motion object.
In the following, we provide a brief example for each motion type implemented by Franky in Python. The C++ interface is generally analogous, though some variable and method names are different because we follow PEP 8 naming conventions in Python and Google naming conventions in C++.
All units are in $m$, $\frac{m}{s}$, $\textit{rad}$, or $\frac{\textit{rad}}{s}$.
Every motion and waypoint type allows to adapt the dynamics (velocity, acceleration and jerk) by setting the respective relative_dynamics_factor
parameter. This parameter can also be set for the robot globally as shown below or in the robot.move
command. Crucially, relative dynamics factors on different layers (robot, move command, and motion) do not override each other but rather get multiplied. Hence, a relative dynamics factor on a motion can only reduce the dynamics of the robot and never increase them.
There is one exception to this rule and that is if any layer sets the relative dynamics factor to RelativeDynamicsFactor.MAX_DYNAMICS
. This will cause the motion to be executed with maximum velocity, acceleration, and jerk limits, independently of the relative dynamics factors of the other layers. This feature should only be used to abruptly stop the robot in case of an unexpected environment contact as executing other motions with it is likely to lead to a discontinuity error and might be dangerous.
The real robot can be moved by applying a motion to the robot using move
:
All motions support callbacks, which will be invoked in every control step at 1kHz. Callbacks can be attached as follows:
Note that in Python, 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 they were queued if they take a long time to execute.
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.
Possible values to measure are
Measure.FORCE_X,
Measure.FORCE_Y,
Measure.FORCE_Z
: Force in X, Y and Z directionMeasure.REL_TIME
: Time in seconds since the current motion startedMeasure.ABS_TIME
: Time in seconds since the initial motion startedThe 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).
With arithmetic comparisons, conditions can be generated.
Conditions support negation, conjunction (and), and disjunction (or):
To check whether a reaction has fired, a callback can be attached:
Similar to the motion callbacks, in Python, reaction callbacks are not executed in real-time but in a regular thread with lower priority to ensure that the control thread does not get blocked. Thus, the callbacks might fire substantially after the reaction has fired, depending on the time it takes to execute them.
In C++ you can additionally use lambdas to define more complex behaviours:
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.
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.
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.
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:
The Python API follows the c++ API closely:
For Franka robots, control happens via the Franka Control Interface (FCI), which has to be enabled through the Franka UI in the robot's web interface. The Franka UI also provides methods for locking and unlocking the brakes, setting the execution mode, and executing the safety self-test. However, sometimes you may want to access these methods programmatically, e.g. for automatically unlocking the brakes before starting a motion, or automatically executing the self-test after 24h of continuous execution.
For that reason, Franky provides a RobotWebSession
class that allows you to access the web interface API of the robot. Note that directly accessing the web interface API is not officially supported and documented by Franka. Hence, use this feature at your own risk.
A typical automated workflow could look like this:
In case you are running the robot for longer than 24h you will have noticed that you have to do a safety self-test every 24h. RobotWebSession
allows to automate this task as well:
robot_web_session.get_system_status()
contains more information than just the time until self-test, such as the current execution mode, whether the brakes are locked, whether the FCI is enabled, and more.
If you want to call other API functions, you can use the RobotWebSession.send_api_request
and RobotWebSession.send_control_api_request
methods. See robot_web_session.py for an example of how to use these methods.
Franky is currently tested against following versions
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.
Franky started originally as a fork of frankx, though both codebase and functionality differ substantially from frankx by now. Aside of bug fixes and general performance improvements, Franky provides the following new features/improvements:
setCollisionBehavior
, setJoinImpedance
, and setCartesianImpedance
).Affine
does not handle elbow positions anymore. Instead, a new class RobotPose
stores both the end-effector pose and optionally the elbow position.MotionData
class does not exist anymore. Instead, reactions and other settings moved to Motion
.If you wish to contribute to this project, you are welcome to create a pull request. Please run the pre-commit hooks before submitting your pull request. To install the pre-commit hooks, run:
pre-commit install
or, alternatively, run `pre-commit run –all-files manually.