franky-control 1.0.2__cp38-cp38-manylinux_2_28_x86_64.whl

This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
@@ -0,0 +1,869 @@
1
+ Metadata-Version: 2.1
2
+ Name: franky-control
3
+ Version: 1.0.2
4
+ Summary: High-level control library for Franka robots.
5
+ Home-page: https://github.com/TimSchneider42/franky
6
+ Author: Tim Schneider
7
+ Author-email: tim@robot-learning.de
8
+ License: LGPL-3.0-or-later
9
+ Keywords: robot,robotics,trajectory-generation,motion-control
10
+ Classifier: Development Status :: 4 - Beta
11
+ Classifier: Intended Audience :: Science/Research
12
+ Classifier: Topic :: Scientific/Engineering
13
+ Classifier: Programming Language :: C++
14
+ Requires-Python: >=3.7
15
+ Description-Content-Type: text/markdown
16
+ License-File: LICENSE
17
+ Requires-Dist: numpy
18
+
19
+ <div align="center">
20
+ <img width="340" src="https://raw.githubusercontent.com/timschneider42/franky/master/doc/logo.svg?sanitize=true">
21
+ <h3 align="center">
22
+ High-Level Control Library for Franka Robots with Python and C++ Support
23
+ </h3>
24
+ </div>
25
+ <p align="center">
26
+ <a href="https://github.com/timschneider42/franky/actions">
27
+ <img src="https://github.com/timschneider42/franky/workflows/CI/badge.svg" alt="CI">
28
+ </a>
29
+
30
+ <a href="https://github.com/timschneider42/franky/actions">
31
+ <img src="https://github.com/timschneider42/franky/workflows/Publish/badge.svg" alt="Publish">
32
+ </a>
33
+
34
+ <a href="https://github.com/timschneider42/franky/issues">
35
+ <img src="https://img.shields.io/github/issues/timschneider42/franky.svg" alt="Issues">
36
+ </a>
37
+
38
+ <a href="https://github.com/timschneider42/franky/releases">
39
+ <img src="https://img.shields.io/github/v/release/timschneider42/franky.svg?include_prereleases&sort=semver" alt="Releases">
40
+ </a>
41
+
42
+ <a href="https://github.com/timschneider42/franky/blob/master/LICENSE">
43
+ <img src="https://img.shields.io/badge/license-LGPL-green.svg" alt="LGPL">
44
+ </a>
45
+ </p>
46
+
47
+ Franky is a high-level control library for Franka robots offering Python and C++ support.
48
+ By providing a high-level control interface, Franky eliminates the need for strict real-time programming at 1 kHz,
49
+ making control from non-real-time environments, such as Python programs, feasible.
50
+ Instead of relying on low-level control commands, Franky expects high-level position or velocity targets and
51
+ uses [Ruckig](https://github.com/pantor/ruckig) to plan time-optimal trajectories in real-time.
52
+
53
+ Although Python does not provide real-time guarantees, Franky strives to maintain as much real-time control as possible.
54
+ Motions can be preempted at any moment, prompting Franky to re-plan trajectories on the fly.
55
+ To handle unforeseen situations—such as unexpected contact with the environment — Franky includes a reaction system that
56
+ allows to update motion commands dynamically.
57
+ Furthermore, most non-real-time functionality of [libfranka](https://frankaemika.github.io/docs/libfranka.html), such as
58
+ Gripper control is made directly available in Python.
59
+
60
+ Check out the [tutorial](#-tutorial) and the [examples](https://github.com/TimSchneider42/franky/tree/master/examples)
61
+ for an introduction.
62
+ The full documentation can be found
63
+ at [https://timschneider42.github.io/franky/](https://timschneider42.github.io/franky/).
64
+
65
+ ## 🚀 Features
66
+
67
+ - **Control your Franka robot directly from Python in just a few lines!**
68
+ No more endless hours setting up ROS, juggling packages, or untangling dependencies. Just `pip install` — no ROS at all.
69
+
70
+ - **[Four control modes](#motion-types)**: [Cartesian position](#cartesian-position-control), [Cartesian velocity](#cartesian-velocity-control), [Joint position](#joint-position-control), [Joint velocity](#joint-velocity-control)
71
+ Franky uses [Ruckig](https://github.com/pantor/ruckig) to generate smooth, time-optimal trajectories while respecting velocity, acceleration, and jerk limits.
72
+
73
+ - **[Real-time control from Python and C++](#real-time-motions)**
74
+ Need to change the target while the robot’s moving? No problem. Franky re-plans trajectories on the fly so that you can preempt motions anytime.
75
+
76
+ - **[Reactive behavior](#-real-time-reactions)**
77
+ Robots don’t always go according to plan. Franky lets you define reactions to unexpected events—like contact with the environment — so you can change course in real-time.
78
+
79
+ - **[Motion and reaction callbacks](#motion-callbacks)**
80
+ Want to monitor what’s happening under the hood? Add callbacks to your motions and reactions. They won’t block the control thread and are super handy for debugging or logging.
81
+
82
+ - **Things are moving too fast? [Tune the robot's dynamics to your needs](#-robot)**
83
+ Adjust max velocity, acceleration, and jerk to match your setup or task. Fine control for smooth, safe operation.
84
+
85
+ - **Full Python access to the libfranka API**
86
+ Want to tweak impedance, read the robot state, set force thresholds, or mess with the Jacobian? Go for it. If libfranka supports it, chances are Franky does, too.
87
+
88
+ ## 📖 Python Quickstart Guide
89
+
90
+ Real-time kernel already installed and real-time permissions granted? Just install Franky via
91
+
92
+ ```bash
93
+ pip install franky-control
94
+ ```
95
+
96
+ otherwise, follow the [setup instructions](#setup) first.
97
+
98
+ Now we are already ready to go!
99
+ Unlock the brakes in the web interface, activate FCI, and start coding:
100
+ ```python
101
+ from franky import *
102
+
103
+ robot = Robot("172.16.0.2") # Replace this with your robot's IP
104
+
105
+ # Let's start slow (this lets the robot use a maximum of 5% of its velocity, acceleration, and jerk limits)
106
+ robot.relative_dynamics_factor = 0.05
107
+
108
+ # Move the robot 20cm along the relative X-axis of its end-effector
109
+ motion = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
110
+ robot.move(motion)
111
+ ```
112
+
113
+ If you are seeing server version mismatch errors, such as
114
+ ```
115
+ franky.IncompatibleVersionException: libfranka: Incompatible library version (server version: 5, library version: 9)
116
+ ```
117
+ then your Franka robot is either not on the most recent firmware version or you are using the older Franka Panda model.
118
+ In any case, it's no big deal; just check [here](https://frankaemika.github.io/docs/compatibility.html) which libfranka version you need and follow our [instructions](installing-frankly) to install the appropriate Franky wheels.
119
+
120
+ ## <a id="setup" /> ⚙️ Setup
121
+
122
+ To install Franky, you have to follow three steps:
123
+
124
+ 1. Ensure that you are using a realtime kernel
125
+ 2. Ensure that the executing user has permission to run real-time applications
126
+ 3. Install Franky via pip or build it from source
127
+
128
+ ### Installing a real-time kernel
129
+
130
+ In order for Franky to function properly, it requires the underlying OS to use a realtime kernel.
131
+ Otherwise, you might see `communication_constrains_violation` errors.
132
+
133
+ To check whether your system is currently using a real-time kernel, type `uname -a`.
134
+ You should see something like this:
135
+
136
+ ```
137
+ $ uname -a
138
+ Linux [PCNAME] 5.15.0-1056-realtime #63-Ubuntu SMP PREEMPT_RT ...
139
+ ```
140
+
141
+ If it does not say PREEMPT_RT, you are not currently running a real-time kernel.
142
+
143
+ There are multiple ways of installing a real-time kernel.
144
+ You
145
+ can [build it from source](https://frankaemika.github.io/docs/installation_linux.html#setting-up-the-real-time-kernel)
146
+ or, if you are using Ubuntu, it can be [enabled through Ubuntu Pro](https://ubuntu.com/real-time).
147
+
148
+ ### Allowing the executing user to run real-time applications
149
+
150
+ First, create a group `realtime` and add your user (or whoever is running Franky) to this group:
151
+
152
+ ```bash
153
+ sudo addgroup realtime
154
+ sudo usermod -a -G realtime $(whoami)
155
+ ```
156
+
157
+ Afterward, add the following limits to the real-time group in /etc/security/limits.conf:
158
+
159
+ ```
160
+ @realtime soft rtprio 99
161
+ @realtime soft priority 99
162
+ @realtime soft memlock 102400
163
+ @realtime hard rtprio 99
164
+ @realtime hard priority 99
165
+ @realtime hard memlock 102400
166
+ ```
167
+
168
+ Log out and log in again to let the changes take effect.
169
+
170
+ To verify that the changes were applied, check if your user is in the `realtime` group:
171
+
172
+ ```bash
173
+ $ groups
174
+ ... realtime
175
+ ```
176
+
177
+ If realtime is not listed in your groups, try rebooting.
178
+
179
+ ### Installing Franky
180
+
181
+ To start using Franky with Python and libfranka *0.15.0*, just install it via
182
+
183
+ ```bash
184
+ pip install franky-control
185
+ ```
186
+
187
+ 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*,
188
+ *0.14.2*, and *0.15.0*.
189
+ They can be installed via
190
+
191
+ ```bash
192
+ VERSION=0-9-2
193
+ wget https://github.com/TimSchneider42/franky/releases/latest/download/libfranka_${VERSION}_wheels.zip
194
+ unzip libfranka_${VERSION}_wheels.zip
195
+ pip install numpy
196
+ pip install --no-index --find-links=./dist franky-control
197
+ ```
198
+
199
+ Franky is based on [libfranka](https://github.com/frankaemika/libfranka), [Eigen](https://eigen.tuxfamily.org) for
200
+ transformation calculations and [pybind11](https://github.com/pybind/pybind11) for the Python bindings.
201
+ As the Franka is sensitive to acceleration discontinuities, it requires jerk-constrained motion generation, for which
202
+ Franky uses the [Ruckig](https://ruckig.com) community version for Online Trajectory Generation (OTG).
203
+
204
+ After installing the dependencies (the exact versions can be found [here](#-development)), you can build and install
205
+ Franky via
206
+
207
+ ```bash
208
+ git clone --recurse-submodules git@github.com:timschneider42/franky.git
209
+ cd franky
210
+ mkdir -p build
211
+ cd build
212
+ cmake -DCMAKE_BUILD_TYPE=Release ..
213
+ make
214
+ make install
215
+ ```
216
+
217
+ To use Franky, you can also include it as a subproject in your parent CMake via `add_subdirectory(franky)` and then
218
+ `target_link_libraries(<target> franky)`.
219
+
220
+ If you need only the Python module, you can install Franky via
221
+
222
+ ```bash
223
+ pip install .
224
+ ```
225
+
226
+ Make sure that the built library `_franky.cpython-3**-****-linux-gnu.so` is in the Python path, e.g. by adjusting
227
+ `PYTHONPATH` accordingly.
228
+
229
+ #### Using Docker
230
+
231
+ To use Franky within Docker we provide a [Dockerfile](docker/run/Dockerfile) and
232
+ accompanying [docker-compose](docker-compose.yml) file.
233
+
234
+ ```bash
235
+ git clone --recurse-submodules https://github.com/timschneider42/franky.git
236
+ cd franky/
237
+ docker compose build franky-run
238
+ ```
239
+
240
+ To use another version of libfranka than the default (0.15.0) add a build argument:
241
+
242
+ ```bash
243
+ docker compose build franky-run --build-arg LIBFRANKA_VERSION=0.9.2
244
+ ```
245
+
246
+ To run the container:
247
+
248
+ ```bash
249
+ docker compose run franky-run bash
250
+ ```
251
+
252
+ The container requires access to the host machines network *and* elevated user rights to allow the docker user to set RT
253
+ capabilities of the processes run from within it.
254
+
255
+ #### Building Franky with Docker
256
+
257
+ For building Franky and its wheels, we provide another Docker container that can also be launched using docker-compose:
258
+
259
+ ```bash
260
+ docker compose build franky-build
261
+ docker compose run --rm franky-build run-tests # To run the tests
262
+ docker compose run --rm franky-build build-wheels # To build wheels for all supported python versions
263
+ ```
264
+
265
+ ## 📚 Tutorial
266
+
267
+ Franky comes with both a C++ and Python API that differ only regarding real-time capability.
268
+ We will introduce both languages next to each other.
269
+ In your C++ project, just include `include <franky.hpp>` and link the library.
270
+ For Python, just `import franky`.
271
+ As a first example, only four lines of code are needed for simple robotic motions.
272
+
273
+ ```c++
274
+ #include <franky.hpp>
275
+ using namespace franky;
276
+
277
+ // Connect to the robot with the FCI IP address
278
+ Robot robot("172.16.0.2");
279
+
280
+ // Reduce velocity and acceleration of the robot
281
+ robot.setRelativeDynamicsFactor(0.05);
282
+
283
+ // Move the end-effector 20cm in positive x-direction
284
+ auto motion = std::make_shared<CartesianMotion>(RobotPose(Affine({0.2, 0.0, 0.0}), 0.0), ReferenceType::Relative);
285
+
286
+ // Finally move the robot
287
+ robot.move(motion);
288
+ ```
289
+
290
+ The corresponding program in Python is
291
+
292
+ ```python
293
+ from franky import Affine, CartesianMotion, Robot, ReferenceType
294
+
295
+ robot = Robot("172.16.0.2")
296
+ robot.relative_dynamics_factor = 0.05
297
+
298
+ motion = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
299
+ robot.move(motion)
300
+ ```
301
+
302
+ Furthermore, we will introduce methods for geometric calculations, for moving the robot according to different motion
303
+ types, how to implement real-time reactions and changing waypoints in real time as well as controlling the gripper.
304
+
305
+ ### 🧮 Geometry
306
+
307
+ `franky.Affine` is a python wrapper for [Eigen::Affine3d](https://eigen.tuxfamily.org/dox/group__TutorialGeometry.html).
308
+ It is used for Cartesian poses, frames and transformation.
309
+ franky adds its own constructor, which takes a position and a quaternion as inputs:
310
+
311
+ ```python
312
+ import math
313
+ from scipy.spatial.transform import Rotation
314
+ from franky import Affine
315
+
316
+ z_translation = Affine([0.0, 0.0, 0.5])
317
+
318
+ quat = Rotation.from_euler("xyz", [0, 0, math.pi / 2]).as_quat()
319
+ z_rotation = Affine([0.0, 0.0, 0.0], quat)
320
+
321
+ combined_transformation = z_translation * z_rotation
322
+ ```
323
+
324
+ In all cases, distances are in [m] and rotations in [rad].
325
+
326
+ ### 🤖 Robot
327
+
328
+ Franky exposes most of the libfanka API for Python.
329
+ Moreover, we added methods to adapt the dynamics limits of the robot for all motions.
330
+
331
+ ```python
332
+ from franky import *
333
+
334
+ robot = Robot("172.16.0.2")
335
+
336
+ # Recover from errors
337
+ robot.recover_from_errors()
338
+
339
+ # Set velocity, acceleration and jerk to 5% of the maximum
340
+ robot.relative_dynamics_factor = 0.05
341
+
342
+ # Alternatively, you can define each constraint individually
343
+ robot.relative_dynamics_factor = RelativeDynamicsFactor(velocity=0.1, acceleration=0.05, jerk=0.1)
344
+
345
+ # Or, for more finegrained access, set individual limits
346
+ robot.translation_velocity_limit.set(3.0)
347
+ robot.rotation_velocity_limit.set(2.5)
348
+ robot.elbow_velocity_limit.set(2.62)
349
+ robot.translation_acceleration_limit.set(9.0)
350
+ robot.rotation_acceleration_limit.set(17.0)
351
+ robot.elbow_acceleration_limit.set(10.0)
352
+ robot.translation_jerk_limit.set(4500.0)
353
+ robot.rotation_jerk_limit.set(8500.0)
354
+ robot.elbow_jerk_limit.set(5000.0)
355
+ robot.joint_velocity_limit.set([2.62, 2.62, 2.62, 2.62, 5.26, 4.18, 5.26])
356
+ robot.joint_acceleration_limit.set([10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0])
357
+ robot.joint_jerk_limit.set([5000.0, 5000.0, 5000.0, 5000.0, 5000.0, 5000.0, 5000.0])
358
+ # By default, these limits are set to their respective maxima (the values shown here)
359
+
360
+ # Get the max of each limit (as provided by Franka) with the max function, e.g.:
361
+ print(robot.joint_jerk_limit.max)
362
+ ```
363
+
364
+ #### Robot State
365
+
366
+ The robot state can be retrieved by accessing the following properties:
367
+
368
+ * `state`: Object of type `franky.RobotState`, which extends the
369
+ libfranka [franka::RobotState](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html) structure by
370
+ additional state elements.
371
+ * `current_cartesian_state`: Object of type `franky.CartesianState`, which contains the end-effector pose and velocity
372
+ obtained
373
+ from [franka::RobotState::O_T_EE](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#a193781d47722b32925e0ea7ac415f442)
374
+ and [franka::RobotState::O_dP_EE_c](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#a4be112bd1a9a7d777a67aea4a18a8dcc).
375
+ * `current_joint_position`: Object of type `franky.JointState`, which contains the joint positions and velocities
376
+ obtained
377
+ from [franka::RobotState::q](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#ade3335d1ac2f6c44741a916d565f7091)
378
+ and [franka::RobotState::dq](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#a706045af1b176049e9e56df755325bd2).
379
+
380
+ ```python
381
+ from franky import *
382
+
383
+ robot = Robot("172.16.0.2")
384
+
385
+ # Get the current state as `franky.RobotState`. See the documentation for a list of fields.
386
+ state = robot.state
387
+
388
+ # Get the robot's cartesian state
389
+ cartesian_state = robot.current_cartesian_state
390
+ robot_pose = cartesian_state.pose # Contains end-effector pose and elbow position
391
+ ee_pose = robot_pose.end_effector_pose
392
+ elbow_pos = robot_pose.elbow_state
393
+ robot_velocity = cartesian_state.velocity # Contains end-effector twist and elbow velocity
394
+ ee_twist = robot_velocity.end_effector_twist
395
+ elbow_vel = robot_velocity.elbow_velocity
396
+
397
+ # Get the robot's joint state
398
+ joint_state = robot.current_joint_state
399
+ joint_pos = joint_state.position
400
+ joint_vel = joint_state.velocity
401
+
402
+ # Use the robot model to compute kinematics
403
+ q = [-0.3, 0.1, 0.3, -1.4, 0.1, 1.8, 0.7]
404
+ f_t_ee = Affine()
405
+ ee_t_k = Affine()
406
+ ee_pose_kin = robot.model.pose(Frame.EndEffector, q, f_t_ee, ee_t_k)
407
+
408
+ # Get the jacobian of the current robot state
409
+ jacobian = robot.model.body_jacobian(Frame.EndEffector, state)
410
+
411
+ # Alternatively, just get the URDF as string and do the kinematics computation yourself (only for libfranka >= 0.15.0)
412
+ urdf_model = robot.model_urdf
413
+ ```
414
+
415
+ For a full list of state-related features, check
416
+ the [Robot](https://timschneider42.github.io/franky/classfranky_1_1_robot.html)
417
+ and [Model](https://timschneider42.github.io/franky/classfranky_1_1_model.html) sections of the documentation.
418
+
419
+ ### <a id="motion-types" /> 🏃‍♂️ Motion Types
420
+
421
+ Franky currently supports four different impedance control modes: **joint position control**, **joint velocity control
422
+ **, **cartesian position control**, and **cartesian velocity control**.
423
+ Each of these control modes is invoked by passing the robot an appropriate _Motion_ object.
424
+
425
+ In the following, we provide a brief example for each motion type implemented by Franky in Python.
426
+ The C++ interface is generally analogous, though some variable and method names are different because we
427
+ follow [PEP 8](https://peps.python.org/pep-0008/) naming conventions in Python
428
+ and [Google naming conventions](https://google.github.io/styleguide/cppguide.html) in C++.
429
+
430
+ All units are in $m$, $\frac{m}{s}$, $\textit{rad}$, or $\frac{\textit{rad}}{s}$.
431
+
432
+ #### Joint Position Control
433
+
434
+ ```python
435
+ from franky import *
436
+
437
+ # A point-to-point motion in the joint space
438
+ m_jp1 = JointMotion([-0.3, 0.1, 0.3, -1.4, 0.1, 1.8, 0.7])
439
+
440
+ # A motion in joint space with multiple waypoints
441
+ m_jp2 = JointWaypointMotion([
442
+ JointWaypoint([-0.3, 0.1, 0.3, -1.4, 0.1, 1.8, 0.7]),
443
+ JointWaypoint([0.0, 0.3, 0.3, -1.5, -0.2, 1.5, 0.8]),
444
+ JointWaypoint([0.1, 0.4, 0.3, -1.4, -0.3, 1.7, 0.9])
445
+ ])
446
+
447
+ # Intermediate waypoints also permit to specify target velocities. The default target velocity is 0, meaning that the
448
+ # robot will stop at every waypoint.
449
+ m_jp3 = JointWaypointMotion([
450
+ JointWaypoint([-0.3, 0.1, 0.3, -1.4, 0.1, 1.8, 0.7]),
451
+ JointWaypoint(
452
+ JointState(
453
+ position=[0.0, 0.3, 0.3, -1.5, -0.2, 1.5, 0.8],
454
+ velocity=[0.1, 0.0, 0.0, 0.0, -0.0, 0.0, 0.0])),
455
+ JointWaypoint([0.1, 0.4, 0.3, -1.4, -0.3, 1.7, 0.9])
456
+ ])
457
+
458
+ # Stop the robot in joint position control mode. The difference of JointStopMotion to other stop motions such as
459
+ # CartesianStopMotion is that # JointStopMotion # stops the robot in joint position control mode while
460
+ # CartesianStopMotion stops it in cartesian pose control mode. The difference becomes relevant when asynchronous move
461
+ # commands are being sent or reactions are being used(see below).
462
+ m_jp4 = JointStopMotion()
463
+ ```
464
+
465
+ #### Joint Velocity Control
466
+
467
+ ```python
468
+ from franky import *
469
+
470
+ # Accelerate to the given joint velocity and hold it. After 1000ms stop the robot again.
471
+ m_jv1 = JointVelocityMotion([0.1, 0.3, -0.1, 0.0, 0.1, -0.2, 0.4], duration=Duration(1000))
472
+
473
+ # Joint velocity motions also support waypoints. Unlike in joint position control, a joint velocity waypoint is a
474
+ # target velocity to be reached. This particular example first accelerates the joints, holds the velocity for 1s, then
475
+ # reverses direction for 2s, reverses direction again for 1s, and finally stops. It is important not to forget to stop
476
+ # the robot at the end of such a sequence, as it will otherwise throw an error.
477
+ m_jv2 = JointVelocityWaypointMotion([
478
+ JointVelocityWaypoint([0.1, 0.3, -0.1, 0.0, 0.1, -0.2, 0.4], hold_target_duration=Duration(1000)),
479
+ JointVelocityWaypoint([-0.1, -0.3, 0.1, -0.0, -0.1, 0.2, -0.4], hold_target_duration=Duration(2000)),
480
+ JointVelocityWaypoint([0.1, 0.3, -0.1, 0.0, 0.1, -0.2, 0.4], hold_target_duration=Duration(1000)),
481
+ JointVelocityWaypoint([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]),
482
+ ])
483
+
484
+ # Stop the robot in joint velocity control mode.
485
+ m_jv3 = JointVelocityStopMotion()
486
+ ```
487
+
488
+ #### Cartesian Position Control
489
+
490
+ ```python
491
+ import math
492
+ from scipy.spatial.transform import Rotation
493
+ from franky import *
494
+
495
+ # Move to the given target pose
496
+ quat = Rotation.from_euler("xyz", [0, 0, math.pi / 2]).as_quat()
497
+ m_cp1 = CartesianMotion(Affine([0.4, -0.2, 0.3], quat))
498
+
499
+ # With target elbow angle (otherwise, the Franka firmware will choose by itself)
500
+ m_cp2 = CartesianMotion(RobotPose(Affine([0.4, -0.2, 0.3], quat), elbow_state=ElbowState(0.3)))
501
+
502
+ # A linear motion in cartesian space relative to the initial position
503
+ # (Note that this motion is relative both in position and orientation. Hence, when the robot's end-effector is oriented
504
+ # differently, it will move in a different direction)
505
+ m_cp3 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
506
+
507
+ # Generalization of CartesianMotion that allows for multiple waypoints
508
+ m_cp4 = CartesianWaypointMotion([
509
+ CartesianWaypoint(RobotPose(Affine([0.4, -0.2, 0.3], quat), elbow_state=ElbowState(0.3))),
510
+ # The following waypoint is relative to the prior one and 50% slower
511
+ CartesianWaypoint(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative, RelativeDynamicsFactor(0.5, 1.0, 1.0))
512
+ ])
513
+
514
+ # Cartesian waypoints also permit to specify target velocities
515
+ m_cp5 = CartesianWaypointMotion([
516
+ CartesianWaypoint(Affine([0.5, -0.2, 0.3], quat)),
517
+ CartesianWaypoint(
518
+ CartesianState(
519
+ pose=Affine([0.4, -0.1, 0.3], quat),
520
+ velocity=Twist([-0.01, 0.01, 0.0]))),
521
+ CartesianWaypoint(Affine([0.3, 0.0, 0.3], quat))
522
+ ])
523
+
524
+ # Stop the robot in cartesian position control mode.
525
+ m_cp6 = CartesianStopMotion()
526
+ ```
527
+
528
+ #### Cartesian Velocity Control
529
+
530
+ ```python
531
+ from franky import *
532
+
533
+ # A cartesian velocity motion with linear (first argument) and angular (second argument) components
534
+ m_cv1 = CartesianVelocityMotion(Twist([0.2, -0.1, 0.1], [0.1, -0.1, 0.2]))
535
+
536
+ # With target elbow velocity
537
+ m_cv2 = CartesianVelocityMotion(RobotVelocity(Twist([0.2, -0.1, 0.1], [0.1, -0.1, 0.2]), elbow_velocity=-0.2))
538
+
539
+ # Cartesian velocity motions also support multiple waypoints. Unlike in cartesian position control, a cartesian velocity
540
+ # waypoint is a target velocity to be reached. This particular example first accelerates the end-effector, holds the
541
+ # velocity for 1s, then # reverses direction for 2s, reverses direction again for 1s, and finally stops. It is important
542
+ # not to forget to stop # the robot at the end of such a sequence, as it will otherwise throw an error.
543
+ m_cv4 = CartesianVelocityWaypointMotion([
544
+ CartesianVelocityWaypoint(Twist([0.2, -0.1, 0.1], [0.1, -0.1, 0.2]), hold_target_duration=Duration(1000)),
545
+ CartesianVelocityWaypoint(Twist([-0.2, 0.1, -0.1], [-0.1, 0.1, -0.2]), hold_target_duration=Duration(2000)),
546
+ CartesianVelocityWaypoint(Twist([0.2, -0.1, 0.1], [0.1, -0.1, 0.2]), hold_target_duration=Duration(1000)),
547
+ CartesianVelocityWaypoint(Twist()),
548
+ ])
549
+
550
+ # Stop the robot in cartesian velocity control mode.
551
+ m_cv6 = CartesianVelocityStopMotion()
552
+ ```
553
+
554
+ #### Relative Dynamics Factors
555
+
556
+ Every motion and waypoint type allows to adapt the dynamics (velocity, acceleration and jerk) by setting the respective
557
+ `relative_dynamics_factor` parameter.
558
+ This parameter can also be set for the robot globally as shown below or in the `robot.move` command.
559
+ Crucially, relative dynamics factors on different layers (robot, move command, and motion) do not override each other
560
+ but rather get multiplied.
561
+ Hence, a relative dynamics factor on a motion can only reduce the dynamics of the robot and never increase them.
562
+
563
+ There is one exception to this rule and that is if any layer sets the relative dynamics factor to
564
+ `RelativeDynamicsFactor.MAX_DYNAMICS`.
565
+ This will cause the motion to be executed with maximum velocity, acceleration, and jerk limits, independently of the
566
+ relative dynamics factors of the other layers.
567
+ This feature should only be used to abruptly stop the robot in case of an unexpected environment contact as executing
568
+ other motions with it is likely to lead to a discontinuity error and might be dangerous.
569
+
570
+ #### Executing Motions
571
+
572
+ The real robot can be moved by applying a motion to the robot using `move`:
573
+
574
+ ```python
575
+ # Before moving the robot, set an appropriate dynamics factor. We start small:
576
+ robot.relative_dynamics_factor = 0.05
577
+ # or alternatively, to control the scaling of velocity, acceleration, and jerk limits separately:
578
+ robot.relative_dynamics_factor = RelativeDynamicsFactor(0.05, 0.1, 0.15)
579
+ # If these values are set too high, you will see discontinuity errors
580
+
581
+ robot.move(m_jp1)
582
+
583
+ # We can also set a relative dynamics factor in the move command. It will be multiplied with the other relative
584
+ # dynamics factors (robot and motion if present).
585
+ robot.move(m_jp2, relative_dynamics_factor=0.8)
586
+ ```
587
+
588
+ #### Motion Callbacks
589
+
590
+ All motions support callbacks, which will be invoked in every control step at 1kHz.
591
+ Callbacks can be attached as follows:
592
+
593
+ ```python
594
+ def cb(
595
+ robot_state: RobotState,
596
+ time_step: Duration,
597
+ rel_time: Duration,
598
+ abs_time: Duration,
599
+ control_signal: JointPositions):
600
+ print(f"At time {abs_time}, the target joint positions were {control_signal.q}")
601
+
602
+
603
+ m_jp1.register_callback(cb)
604
+ robot.move(m_jp1)
605
+ ```
606
+
607
+ Note that in Python, these callbacks are not executed in the control thread since they would otherwise block it.
608
+ Instead, they are put in a queue and executed by another thread.
609
+ While this scheme ensures that the control thread can always run, it cannot prevent that the queue grows indefinitely
610
+ when the callbacks take more time to execute than it takes for new callbacks to be queued.
611
+ Hence, callbacks might be executed significantly after they were queued if they take a long time to execute.
612
+
613
+ ### ⚡ Real-Time Reactions
614
+
615
+ By adding reactions to the motion data, the robot can react to unforeseen events.
616
+ In the Python API, you can define conditions by using a comparison between a robot's value and a given threshold.
617
+ If the threshold is exceeded, the reaction fires.
618
+
619
+ ```python
620
+ from franky import CartesianMotion, Affine, ReferenceType, Measure, Reaction
621
+
622
+ motion = CartesianMotion(Affine([0.0, 0.0, 0.1]), ReferenceType.Relative) # Move down 10cm
623
+
624
+ # It is important that the reaction motion uses the same control mode as the original motion. Hence, we cannot register
625
+ # a JointMotion as a reaction motion to a CartesianMotion.
626
+ reaction_motion = CartesianMotion(Affine([0.0, 0.0, 0.01]), ReferenceType.Relative) # Move up for 1cm
627
+
628
+ # Trigger reaction if the Z force is greater than 30N
629
+ reaction = Reaction(Measure.FORCE_Z > 30.0, reaction_motion)
630
+ motion.add_reaction(reaction)
631
+
632
+ robot.move(motion)
633
+ ```
634
+
635
+ Possible values to measure are
636
+
637
+ * `Measure.FORCE_X,` `Measure.FORCE_Y,` `Measure.FORCE_Z`: Force in X, Y and Z direction
638
+ * `Measure.REL_TIME`: Time in seconds since the current motion started
639
+ * `Measure.ABS_TIME`: Time in seconds since the initial motion started
640
+
641
+ The difference between `Measure.REL_TIME` and `Measure.ABS_TIME` is that `Measure.REL_TIME` is reset to zero whenever a
642
+ new motion starts (either by calling `Robot.move` or as a result of a triggered `Reaction`).
643
+ `Measure.ABS_TIME`, on the other hand, is only reset to zero when a motion terminates regularly without being
644
+ interrupted and the robot stops moving.
645
+ Hence, `Measure.ABS_TIME` measures the total time in which the robot has moved without interruption.
646
+
647
+ `Measure` values support all classical arithmetic operations, like addition, subtraction, multiplication, division, and
648
+ exponentiation (both as base and exponent).
649
+
650
+ ```python
651
+ normal_force = (Measure.FORCE_X ** 2 + Measure.FORCE_Y ** 2 + Measure.FORCE_Z ** 2) ** 0.5
652
+ ```
653
+
654
+ With arithmetic comparisons, conditions can be generated.
655
+
656
+ ```python
657
+ normal_force_within_bounds = normal_force < 30.0
658
+ time_up = Measure.ABS_TIME > 10.0
659
+ ```
660
+
661
+ Conditions support negation, conjunction (and), and disjunction (or):
662
+
663
+ ```python
664
+ abort = ~normal_force_within_bounds | time_up
665
+ fast_abort = ~normal_force_within_bounds | time_up
666
+ ```
667
+
668
+ To check whether a reaction has fired, a callback can be attached:
669
+
670
+ ```python
671
+ from franky import RobotState
672
+
673
+
674
+ def reaction_callback(robot_state: RobotState, rel_time: float, abs_time: float):
675
+ print(f"Reaction fired at {abs_time}.")
676
+
677
+
678
+ reaction.register_callback(reaction_callback)
679
+ ```
680
+
681
+ Similar to the motion callbacks, in Python, reaction callbacks are not executed in real-time but in a regular thread
682
+ with lower priority to ensure that the control thread does not get blocked.
683
+ Thus, the callbacks might fire substantially after the reaction has fired, depending on the time it takes to execute
684
+ them.
685
+
686
+ In C++ you can additionally use lambdas to define more complex behaviours:
687
+
688
+ ```c++
689
+ auto motion = CartesianMotion(RobotPose(Affine({0.0, 0.0, 0.2}), 0.0), ReferenceType::Relative);
690
+
691
+ // Stop motion if force is over 10N
692
+ auto stop_motion = StopMotion<franka::CartesianPose>()
693
+
694
+ motion
695
+ .addReaction(
696
+ Reaction(
697
+ Measure::ForceZ() > 10.0, // [N],
698
+ stop_motion))
699
+ .addReaction(
700
+ Reaction(
701
+ Condition(
702
+ [](const franka::RobotState& state, double rel_time, double abs_time) {
703
+ // Lambda condition
704
+ return state.current_errors.self_collision_avoidance_violation;
705
+ }),
706
+ [](const franka::RobotState& state, double rel_time, double abs_time) {
707
+ // Lambda reaction motion generator
708
+ // (we are just returning a stop motion, but there could be arbitrary
709
+ // logic here for generating reaction motions)
710
+ return StopMotion<franka::CartesianPose>();
711
+ })
712
+ ));
713
+
714
+ robot.move(motion)
715
+ ```
716
+
717
+ ### <a id="real-time-motions" /> ⏱️ Real-Time Motions
718
+
719
+ By setting the `asynchronous` parameter of `Robot.move` to `True`, the function does not block until the motion
720
+ finishes.
721
+ Instead, it returns immediately and, thus, allows the main thread to set new motions asynchronously.
722
+
723
+ ```python
724
+ import time
725
+ from franky import Affine, CartesianMotion, Robot, ReferenceType
726
+
727
+ robot = Robot("172.16.0.2")
728
+ robot.relative_dynamics_factor = 0.05
729
+
730
+ motion1 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
731
+ robot.move(motion1, asynchronous=True)
732
+
733
+ time.sleep(0.5)
734
+ # Note that similar to reactions, when preempting active motions with new motions, the control mode cannot change.
735
+ # Hence, we cannot use, e.g., a JointMotion here.
736
+ motion2 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
737
+ robot.move(motion2, asynchronous=True)
738
+ ```
739
+
740
+ By calling `Robot.join_motion` the main thread can be synchronized with the motion thread, as it will block until the
741
+ robot finishes its motion.
742
+
743
+ ```python
744
+ robot.join_motion()
745
+ ```
746
+
747
+ Note that when exceptions occur during the asynchronous execution of a motion, they will not be thrown immediately.
748
+ Instead, the control thread stores the exception and terminates.
749
+ The next time `Robot.join_motion` or `Robot.move` are called, they will throw the stored exception in the main thread.
750
+ Hence, after an asynchronous motion has finished, make sure to call `Robot.join_motion` to ensure being notified of any
751
+ exceptions that occurred during the motion.
752
+
753
+ ### Gripper
754
+
755
+ In the `franky::Gripper` class, the default gripper force and gripper speed can be set.
756
+ Then, additionally to the libfranka commands, the following helper methods can be used:
757
+
758
+ ```c++
759
+ #include <franky.hpp>
760
+ #include <chrono>
761
+ #include <future>
762
+
763
+ auto gripper = franky::Gripper("172.16.0.2");
764
+
765
+ double speed = 0.02; // [m/s]
766
+ double force = 20.0; // [N]
767
+
768
+ // Move the fingers to a specific width (5cm)
769
+ bool success = gripper.move(0.05, speed);
770
+
771
+ // Grasp an object of unknown width
772
+ success &= gripper.grasp(0.0, speed, force, epsilon_outer=1.0);
773
+
774
+ // Get the width of the grasped object
775
+ double width = gripper.width();
776
+
777
+ // Release the object
778
+ gripper.open(speed);
779
+
780
+ // There are also asynchronous versions of the methods
781
+ std::future<bool> success_future = gripper.moveAsync(0.05, speed);
782
+
783
+ // Wait for 1s
784
+ if (!success_future.wait_for(std::chrono::seconds(1)) == std::future_status::ready) {
785
+ // Get the result
786
+ std::cout << "Success: " << success_future.get() << std::endl;
787
+ } else {
788
+ gripper.stop();
789
+ success_future.wait();
790
+ std::cout << "Gripper motion timed out." << std::endl;
791
+ }
792
+ ```
793
+
794
+ The Python API follows the c++ API closely:
795
+
796
+ ```python
797
+ import franky
798
+
799
+ gripper = franky.Gripper("172.16.0.2")
800
+
801
+ speed = 0.02 # [m/s]
802
+ force = 20.0 # [N]
803
+
804
+ # Move the fingers to a specific width (5cm)
805
+ success = gripper.move(0.05, speed)
806
+
807
+ # Grasp an object of unknown width
808
+ success &= gripper.grasp(0.0, speed, force, epsilon_outer=1.0)
809
+
810
+ # Get the width of the grasped object
811
+ width = gripper.width
812
+
813
+ # Release the object
814
+ gripper.open(speed)
815
+
816
+ # There are also asynchronous versions of the methods
817
+ success_future = gripper.move_async(0.05, speed)
818
+
819
+ # Wait for 1s
820
+ if success_future.wait(1):
821
+ print(f"Success: {success_future.get()}")
822
+ else:
823
+ gripper.stop()
824
+ success_future.wait()
825
+ print("Gripper motion timed out.")
826
+ ```
827
+
828
+ ## 🛠️ Development
829
+
830
+ Franky is currently tested against following versions
831
+
832
+ - libfranka 0.7.1, 0.8.0, 0.9.2, 0.10.0, 0.11.0, 0.12.1, 0.13.3, 0.14.2, 0.15.0
833
+ - Eigen 3.4.0
834
+ - Pybind11 2.13.6
835
+ - POCO 1.12.5p2
836
+ - Pinocchio 3.4.0
837
+ - Python 3.7, 3.8, 3.9, 3.10, 3.11, 3.12, 3.13
838
+ - Catch2 2.13.8 (for testing only)
839
+
840
+ ## 📜 License
841
+
842
+ For non-commercial applications, this software is licensed under the LGPL v3.0.
843
+ If you want to use Franky within commercial applications or under a different license, please contact us for individual
844
+ agreements.
845
+
846
+ ## 🔍 Differences to frankx
847
+
848
+ Franky started originally as a fork of [frankx](https://github.com/pantor/frankx), though both codebase and
849
+ functionality differ substantially from frankx by now.
850
+ Aside of bug fixes and general performance improvements, Franky provides the following new features/improvements:
851
+
852
+ * [Motions can be updated asynchronously.](#-real-time-motions)
853
+ * [Reactions allow for the registration of callbacks instead of just printing to stdout when fired.](#-real-time-reactions)
854
+ * [Motions allow for the registration of callbacks for profiling.](#motion-callbacks)
855
+ * [The robot state is also available during control.](#robot-state)
856
+ * A larger part of the libfranka API is exposed to python (e.g.,`setCollisionBehavior`, `setJoinImpedance`, and
857
+ `setCartesianImpedance`).
858
+ * Cartesian motion generation handles boundaries in Euler angles properly.
859
+ * [There is a new joint motion type that supports waypoints.](#-motion-types)
860
+ * [The signature of `Affine` changed.](#-geometry) `Affine` does not handle elbow positions anymore.
861
+ Instead, a new class `RobotPose` stores both the end-effector pose and optionally the elbow position.
862
+ * The `MotionData` class does not exist anymore.
863
+ Instead, reactions and other settings moved to `Motion`.
864
+ * [The `Measure` class allows for arithmetic operations.](#-real-time-reactions)
865
+ * Exceptions caused by libfranka are raised properly instead of being printed to stdout.
866
+ * [We provide wheels for both Franka Research 3 and the older Franka Panda](#-setup)
867
+ * Franky supports [joint velocity control](#joint-velocity-control)
868
+ and [cartesian velocity control](#cartesian-velocity-control)
869
+ * The dynamics limits are not hard-coded anymore but can be [set for each robot instance](#-robot).