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