franky-control 1.0.2__cp38-cp38-manylinux_2_34_x86_64.whl → 1.1.1__cp38-cp38-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.
franky/__init__.py CHANGED
@@ -1,12 +1,17 @@
1
1
  from .robot import Robot
2
- from .robot_web_session import RobotWebSession
2
+ from .robot_web_session import (
3
+ RobotWebSession,
4
+ RobotWebSessionError,
5
+ FrankaAPIError,
6
+ TakeControlTimeoutError,
7
+ )
3
8
  from .reaction import (
4
9
  Reaction,
5
10
  TorqueReaction,
6
11
  JointVelocityReaction,
7
12
  JointPositionReaction,
8
13
  CartesianVelocityReaction,
9
- CartesianPoseReaction
14
+ CartesianPoseReaction,
10
15
  )
11
16
  from .motion import Motion
12
17
  from ._franky import *
franky/motion.py CHANGED
@@ -1,12 +1,17 @@
1
1
  from typing import Union
2
2
 
3
- from ._franky import BaseCartesianPoseMotion, BaseCartesianVelocityMotion, BaseJointPositionMotion, \
4
- BaseJointVelocityMotion, BaseTorqueMotion
3
+ from ._franky import (
4
+ BaseCartesianPoseMotion,
5
+ BaseCartesianVelocityMotion,
6
+ BaseJointPositionMotion,
7
+ BaseJointVelocityMotion,
8
+ BaseTorqueMotion,
9
+ )
5
10
 
6
11
  Motion = Union[
7
12
  BaseCartesianPoseMotion,
8
13
  BaseCartesianVelocityMotion,
9
14
  BaseJointPositionMotion,
10
15
  BaseJointVelocityMotion,
11
- BaseTorqueMotion
16
+ BaseTorqueMotion,
12
17
  ]
franky/reaction.py CHANGED
@@ -1,10 +1,16 @@
1
- from ._franky import Condition, BaseCartesianPoseMotion, BaseCartesianVelocityMotion, BaseJointPositionMotion, \
2
- BaseJointVelocityMotion, BaseTorqueMotion, \
3
- CartesianPoseReaction as _CartesianPoseReaction, \
4
- CartesianVelocityReaction as _CartesianVelocityReaction, \
5
- JointPositionReaction as _JointPositionReaction, \
6
- JointVelocityReaction as _JointVelocityReaction, \
7
- TorqueReaction as _TorqueReaction
1
+ from ._franky import (
2
+ Condition,
3
+ BaseCartesianPoseMotion,
4
+ BaseCartesianVelocityMotion,
5
+ BaseJointPositionMotion,
6
+ BaseJointVelocityMotion,
7
+ BaseTorqueMotion,
8
+ CartesianPoseReaction as _CartesianPoseReaction,
9
+ CartesianVelocityReaction as _CartesianVelocityReaction,
10
+ JointPositionReaction as _JointPositionReaction,
11
+ JointVelocityReaction as _JointVelocityReaction,
12
+ TorqueReaction as _TorqueReaction,
13
+ )
8
14
 
9
15
  from .motion import Motion
10
16
 
@@ -40,4 +46,9 @@ class TorqueReaction(_TorqueReaction, Reaction):
40
46
 
41
47
 
42
48
  _REACTION_TYPES = [
43
- CartesianPoseReaction, CartesianVelocityReaction, JointPositionReaction, JointVelocityReaction, TorqueReaction]
49
+ CartesianPoseReaction,
50
+ CartesianVelocityReaction,
51
+ JointPositionReaction,
52
+ JointVelocityReaction,
53
+ TorqueReaction,
54
+ ]
@@ -7,22 +7,37 @@ import time
7
7
  import urllib.parse
8
8
  from http.client import HTTPSConnection, HTTPResponse
9
9
  from typing import Dict, Optional, Any, Literal
10
- from urllib.error import HTTPError
11
10
 
12
11
 
13
- class FrankaAPIError(Exception):
14
- def __init__(self, target: str, http_code: int, http_reason: str, headers: Dict[str, str], message: str):
12
+ class RobotWebSessionError(Exception):
13
+ pass
14
+
15
+
16
+ class FrankaAPIError(RobotWebSessionError):
17
+ def __init__(
18
+ self,
19
+ target: str,
20
+ http_code: int,
21
+ http_reason: str,
22
+ headers: Dict[str, str],
23
+ message: str,
24
+ ):
15
25
  super().__init__(
16
- f"Franka API returned error {http_code} ({http_reason}) when accessing end-point {target}: {message}")
26
+ f"Franka API returned error {http_code} ({http_reason}) when accessing end-point {target}: {message}"
27
+ )
17
28
  self.target = target
18
29
  self.http_code = http_code
19
30
  self.headers = headers
20
31
  self.message = message
21
32
 
22
33
 
34
+ class TakeControlTimeoutError(RobotWebSessionError):
35
+ pass
36
+
37
+
23
38
  class RobotWebSession:
24
- def __init__(self, fci_hostname: str, username: str, password: str):
25
- self.__fci_hostname = fci_hostname
39
+ def __init__(self, hostname: str, username: str, password: str):
40
+ self.__hostname = hostname
26
41
  self.__username = username
27
42
  self.__password = password
28
43
 
@@ -33,24 +48,45 @@ class RobotWebSession:
33
48
 
34
49
  @staticmethod
35
50
  def __encode_password(user: str, password: str) -> str:
36
- bs = ",".join([str(b) for b in hashlib.sha256((password + "#" + user + "@franka").encode("utf-8")).digest()])
51
+ bs = ",".join(
52
+ [
53
+ str(b)
54
+ for b in hashlib.sha256(
55
+ (password + "#" + user + "@franka").encode("utf-8")
56
+ ).digest()
57
+ ]
58
+ )
37
59
  return base64.encodebytes(bs.encode("utf-8")).decode("utf-8")
38
60
 
39
- def _send_api_request(self, target: str, headers: Optional[Dict[str, str]] = None, body: Optional[Any] = None,
40
- method: Literal["GET", "POST", "DELETE"] = "POST"):
41
- _headers = {
42
- "Cookie": f"authorization={self.__token}"
43
- }
61
+ def _send_api_request(
62
+ self,
63
+ target: str,
64
+ headers: Optional[Dict[str, str]] = None,
65
+ body: Optional[Any] = None,
66
+ method: Literal["GET", "POST", "DELETE"] = "POST",
67
+ ):
68
+ _headers = {"Cookie": f"authorization={self.__token}"}
44
69
  if headers is not None:
45
70
  _headers.update(headers)
46
71
  self.__client.request(method, target, headers=_headers, body=body)
47
72
  res: HTTPResponse = self.__client.getresponse()
48
73
  if res.getcode() != 200:
49
- raise FrankaAPIError(target, res.getcode(), res.reason, dict(res.headers), res.read().decode("utf-8"))
74
+ raise FrankaAPIError(
75
+ target,
76
+ res.getcode(),
77
+ res.reason,
78
+ dict(res.headers),
79
+ res.read().decode("utf-8"),
80
+ )
50
81
  return res.read()
51
82
 
52
- def send_api_request(self, target: str, headers: Optional[Dict[str, str]] = None, body: Optional[Any] = None,
53
- method: Literal["GET", "POST", "DELETE"] = "POST"):
83
+ def send_api_request(
84
+ self,
85
+ target: str,
86
+ headers: Optional[Dict[str, str]] = None,
87
+ body: Optional[Any] = None,
88
+ method: Literal["GET", "POST", "DELETE"] = "POST",
89
+ ):
54
90
  last_error = None
55
91
  for i in range(3):
56
92
  try:
@@ -59,28 +95,38 @@ class RobotWebSession:
59
95
  last_error = ex
60
96
  raise last_error
61
97
 
62
- def send_control_api_request(self, target: str, headers: Optional[Dict[str, str]] = None,
63
- body: Optional[Any] = None,
64
- method: Literal["GET", "POST", "DELETE"] = "POST"):
98
+ def send_control_api_request(
99
+ self,
100
+ target: str,
101
+ headers: Optional[Dict[str, str]] = None,
102
+ body: Optional[Any] = None,
103
+ method: Literal["GET", "POST", "DELETE"] = "POST",
104
+ ):
65
105
  if headers is None:
66
106
  headers = {}
67
107
  self.__check_control_token()
68
- _headers = {
69
- "X-Control-Token": self.__control_token
70
- }
108
+ _headers = {"X-Control-Token": self.__control_token}
71
109
  _headers.update(headers)
72
110
  return self.send_api_request(target, headers=_headers, method=method, body=body)
73
111
 
74
- def open(self):
112
+ def open(self, timeout: float = 30.0):
75
113
  if self.is_open:
76
114
  raise RuntimeError("Session is already open.")
77
- self.__client = HTTPSConnection(self.__fci_hostname, timeout=12, context=ssl._create_unverified_context())
115
+ self.__client = HTTPSConnection(
116
+ self.__hostname, timeout=timeout, context=ssl._create_unverified_context()
117
+ )
78
118
  self.__client.connect()
79
119
  payload = json.dumps(
80
- {"login": self.__username, "password": self.__encode_password(self.__username, self.__password)})
120
+ {
121
+ "login": self.__username,
122
+ "password": self.__encode_password(self.__username, self.__password),
123
+ }
124
+ )
81
125
  self.__token = self.send_api_request(
82
- "/admin/api/login", headers={"content-type": "application/json"},
83
- body=payload).decode("utf-8")
126
+ "/admin/api/login",
127
+ headers={"content-type": "application/json"},
128
+ body=payload,
129
+ ).decode("utf-8")
84
130
  return self
85
131
 
86
132
  def close(self):
@@ -92,82 +138,125 @@ class RobotWebSession:
92
138
  self.__client.close()
93
139
 
94
140
  def __enter__(self):
95
- self.open()
141
+ return self.open()
96
142
 
97
143
  def __exit__(self, type, value, traceback):
98
144
  self.close()
99
145
 
100
146
  def __check_control_token(self):
101
147
  if self.__control_token is None:
102
- raise RuntimeError("Client does not have control. Call take_control() first.")
148
+ raise RuntimeError(
149
+ "Client does not have control. Call take_control() first."
150
+ )
103
151
 
104
- def take_control(self, wait_timeout: float = 10.0):
105
- if self.__control_token is None:
152
+ def take_control(self, wait_timeout: float = 30.0, force: bool = False):
153
+ if not self.has_control():
106
154
  res = self.send_api_request(
107
- "/admin/api/control-token/request", headers={"content-type": "application/json"},
108
- body=json.dumps({"requestedBy": self.__username}))
155
+ f"/admin/api/control-token/request{'?force' if force else ''}",
156
+ headers={"content-type": "application/json"},
157
+ body=json.dumps({"requestedBy": self.__username}),
158
+ )
159
+ if force:
160
+ print(
161
+ "Forcibly taking control: "
162
+ f"Please physically take control by pressing the top button on the FR3 within {wait_timeout}s!"
163
+ )
109
164
  response_dict = json.loads(res)
110
165
  self.__control_token = response_dict["token"]
111
166
  self.__control_token_id = response_dict["id"]
112
167
  # One should probably use websockets here but that would introduce another dependency
113
168
  start = time.time()
114
- while time.time() - start < wait_timeout and not self.has_control():
115
- time.sleep(1.0)
116
- return self.has_control()
169
+ has_control = self.has_control()
170
+ while time.time() - start < wait_timeout and not has_control:
171
+ time.sleep(max(0.0, min(1.0, wait_timeout - (time.time() - start))))
172
+ has_control = self.has_control()
173
+ if not has_control:
174
+ raise TakeControlTimeoutError(
175
+ f"Timed out waiting for control to be granted after {wait_timeout}s."
176
+ )
117
177
 
118
178
  def release_control(self):
119
179
  if self.__control_token is not None:
120
180
  self.send_control_api_request(
121
- "/admin/api/control-token", headers={"content-type": "application/json"}, method="DELETE",
122
- body=json.dumps({"token": self.__control_token}))
181
+ "/admin/api/control-token",
182
+ headers={"content-type": "application/json"},
183
+ method="DELETE",
184
+ body=json.dumps({"token": self.__control_token}),
185
+ )
123
186
  self.__control_token = None
124
187
  self.__control_token_id = None
125
188
 
126
189
  def enable_fci(self):
127
190
  self.send_control_api_request(
128
- "/desk/api/system/fci", headers={"content-type": "application/x-www-form-urlencoded"},
129
- body=f"token={urllib.parse.quote(base64.b64encode(self.__control_token.encode('ascii')))}")
191
+ "/desk/api/system/fci",
192
+ headers={"content-type": "application/x-www-form-urlencoded"},
193
+ body=f"token={urllib.parse.quote(base64.b64encode(self.__control_token.encode('ascii')))}",
194
+ )
130
195
 
131
196
  def has_control(self):
132
197
  if self.__control_token_id is not None:
133
198
  status = self.get_system_status()
134
199
  active_token = status["controlToken"]["activeToken"]
135
- return active_token is not None and active_token["id"] == self.__control_token_id
200
+ return (
201
+ active_token is not None
202
+ and active_token["id"] == self.__control_token_id
203
+ )
136
204
  return False
137
205
 
138
206
  def start_task(self, task: str):
139
207
  self.send_api_request(
140
- "/desk/api/execution", headers={"content-type": "application/x-www-form-urlencoded"},
141
- body=f"id={task}")
208
+ "/desk/api/execution",
209
+ headers={"content-type": "application/x-www-form-urlencoded"},
210
+ body=f"id={task}",
211
+ )
142
212
 
143
213
  def unlock_brakes(self):
144
214
  self.send_control_api_request(
145
- "/desk/api/joints/unlock", headers={"content-type": "application/x-www-form-urlencoded"})
215
+ "/desk/api/joints/unlock",
216
+ headers={"content-type": "application/x-www-form-urlencoded"},
217
+ )
146
218
 
147
219
  def lock_brakes(self):
148
220
  self.send_control_api_request(
149
- "/desk/api/joints/lock", headers={"content-type": "application/x-www-form-urlencoded"})
221
+ "/desk/api/joints/lock",
222
+ headers={"content-type": "application/x-www-form-urlencoded"},
223
+ )
150
224
 
151
225
  def set_mode_programming(self):
152
226
  self.send_control_api_request(
153
- "/desk/api/operating-mode/programming", headers={"content-type": "application/x-www-form-urlencoded"})
227
+ "/desk/api/operating-mode/programming",
228
+ headers={"content-type": "application/x-www-form-urlencoded"},
229
+ )
154
230
 
155
231
  def set_mode_execution(self):
156
232
  self.send_control_api_request(
157
- "/desk/api/operating-mode/execution", headers={"content-type": "application/x-www-form-urlencoded"})
233
+ "/desk/api/operating-mode/execution",
234
+ headers={"content-type": "application/x-www-form-urlencoded"},
235
+ )
158
236
 
159
237
  def get_system_status(self):
160
- return json.loads(self.send_api_request("/admin/api/system-status", method="GET").decode("utf-8"))
238
+ return json.loads(
239
+ self.send_api_request("/admin/api/system-status", method="GET").decode(
240
+ "utf-8"
241
+ )
242
+ )
161
243
 
162
244
  def execute_self_test(self):
163
245
  if self.get_system_status()["safety"]["recoverableErrors"]["td2Timeout"]:
164
246
  self.send_control_api_request(
165
- "/admin/api/safety/recoverable-safety-errors/acknowledge?error_id=TD2Timeout")
166
- response = json.loads(self.send_control_api_request(
167
- "/admin/api/safety/td2-tests/execute", headers={"content-type": "application/json"}).decode("utf-8"))
247
+ "/admin/api/safety/recoverable-safety-errors/acknowledge?error_id=TD2Timeout"
248
+ )
249
+ response = json.loads(
250
+ self.send_control_api_request(
251
+ "/admin/api/safety/td2-tests/execute",
252
+ headers={"content-type": "application/json"},
253
+ ).decode("utf-8")
254
+ )
168
255
  assert response["code"] == "SuccessResponse"
169
256
  time.sleep(0.5)
170
- while self.get_system_status()["safety"]["safetyControllerStatus"] == "SelfTest":
257
+ while (
258
+ self.get_system_status()["safety"]["safetyControllerStatus"] == "SelfTest"
259
+ ):
171
260
  time.sleep(0.5)
172
261
 
173
262
  @property
@@ -162,4 +162,4 @@ General Public License ever published by the Free Software Foundation.
162
162
  whether future versions of the GNU Lesser General Public License shall
163
163
  apply, that proxy's public statement of acceptance of any version is
164
164
  permanent authorization for you to choose that version for the
165
- Library.
165
+ Library.
@@ -1,6 +1,6 @@
1
1
  Metadata-Version: 2.1
2
2
  Name: franky-control
3
- Version: 1.0.2
3
+ Version: 1.1.1
4
4
  Summary: High-level control library for Franka robots.
5
5
  Home-page: https://github.com/TimSchneider42/franky
6
6
  Author: Tim Schneider
@@ -64,25 +64,25 @@ at [https://timschneider42.github.io/franky/](https://timschneider42.github.io/f
64
64
 
65
65
  ## 🚀 Features
66
66
 
67
- - **Control your Franka robot directly from Python in just a few lines!**
67
+ - **Control your Franka robot directly from Python in just a few lines!**
68
68
  No more endless hours setting up ROS, juggling packages, or untangling dependencies. Just `pip install` — no ROS at all.
69
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)
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
71
  Franky uses [Ruckig](https://github.com/pantor/ruckig) to generate smooth, time-optimal trajectories while respecting velocity, acceleration, and jerk limits.
72
72
 
73
73
  - **[Real-time control from Python and C++](#real-time-motions)**
74
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
75
 
76
- - **[Reactive behavior](#-real-time-reactions)**
76
+ - **[Reactive behavior](#-real-time-reactions)**
77
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
78
 
79
- - **[Motion and reaction callbacks](#motion-callbacks)**
79
+ - **[Motion and reaction callbacks](#motion-callbacks)**
80
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
81
 
82
- - **Things are moving too fast? [Tune the robot's dynamics to your needs](#-robot)**
82
+ - **Things are moving too fast? [Tune the robot's dynamics to your needs](#-robot)**
83
83
  Adjust max velocity, acceleration, and jerk to match your setup or task. Fine control for smooth, safe operation.
84
84
 
85
- - **Full Python access to the libfranka API**
85
+ - **Full Python access to the libfranka API**
86
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
87
 
88
88
  ## 📖 Python Quickstart Guide
@@ -97,6 +97,7 @@ otherwise, follow the [setup instructions](#setup) first.
97
97
 
98
98
  Now we are already ready to go!
99
99
  Unlock the brakes in the web interface, activate FCI, and start coding:
100
+
100
101
  ```python
101
102
  from franky import *
102
103
 
@@ -196,6 +197,60 @@ pip install numpy
196
197
  pip install --no-index --find-links=./dist franky-control
197
198
  ```
198
199
 
200
+ ### Using Docker
201
+
202
+ To use Franky within Docker we provide a [Dockerfile](docker/run/Dockerfile) and
203
+ accompanying [docker-compose](docker-compose.yml) file.
204
+
205
+ ```bash
206
+ git clone --recurse-submodules https://github.com/timschneider42/franky.git
207
+ cd franky/
208
+ docker compose build franky-run
209
+ ```
210
+
211
+ To use another version of libfranka than the default (0.15.0) add a build argument:
212
+
213
+ ```bash
214
+ docker compose build franky-run --build-arg LIBFRANKA_VERSION=0.9.2
215
+ ```
216
+
217
+ To run the container:
218
+
219
+ ```bash
220
+ docker compose run franky-run bash
221
+ ```
222
+
223
+ The container requires access to the host machines network *and* elevated user rights to allow the docker user to set RT
224
+ capabilities of the processes run from within it.
225
+
226
+ ### Can I use CUDA jointly with Franky?
227
+
228
+ 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.
229
+
230
+ First, make sure that you have rebooted your system after installing the real-time kernel.
231
+ 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.
232
+
233
+ If you are on Ubuntu, you can also use [this](tools/install_cuda_realtime.bash) script to install CUDA on your real-time system:
234
+ ```bash
235
+ # Download the script
236
+ wget https://raw.githubusercontent.com/timschneider42/franky/master/tools/install_cuda_realtime.bash
237
+
238
+ # Inspect the script to ensure it does what you expect
239
+
240
+ # Make it executable
241
+ chmod +x install_cuda_realtime.bash
242
+
243
+ # Execute the script
244
+ ./install_cuda_realtime.bash
245
+ ```
246
+
247
+ 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:
248
+ ```bash
249
+ bash <(wget -qO- https://raw.githubusercontent.com/timschneider42/franky/master/tools/install_cuda_realtime.bash)
250
+ ```
251
+
252
+ ### Building Franky
253
+
199
254
  Franky is based on [libfranka](https://github.com/frankaemika/libfranka), [Eigen](https://eigen.tuxfamily.org) for
200
255
  transformation calculations and [pybind11](https://github.com/pybind/pybind11) for the Python bindings.
201
256
  As the Franka is sensitive to acceleration discontinuities, it requires jerk-constrained motion generation, for which
@@ -226,32 +281,6 @@ pip install .
226
281
  Make sure that the built library `_franky.cpython-3**-****-linux-gnu.so` is in the Python path, e.g. by adjusting
227
282
  `PYTHONPATH` accordingly.
228
283
 
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
284
  #### Building Franky with Docker
256
285
 
257
286
  For building Franky and its wheels, we provide another Docker container that can also be launched using docker-compose:
@@ -299,6 +328,8 @@ motion = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
299
328
  robot.move(motion)
300
329
  ```
301
330
 
331
+ Before executing any code, make sure that you have enabled the Franka Control Interface (FCI) in the Franka UI web interface.
332
+
302
333
  Furthermore, we will introduce methods for geometric calculations, for moving the robot according to different motion
303
334
  types, how to implement real-time reactions and changing waypoints in real time as well as controlling the gripper.
304
335
 
@@ -340,7 +371,9 @@ robot.recover_from_errors()
340
371
  robot.relative_dynamics_factor = 0.05
341
372
 
342
373
  # Alternatively, you can define each constraint individually
343
- robot.relative_dynamics_factor = RelativeDynamicsFactor(velocity=0.1, acceleration=0.05, jerk=0.1)
374
+ robot.relative_dynamics_factor = RelativeDynamicsFactor(
375
+ velocity=0.1, acceleration=0.05, jerk=0.1
376
+ )
344
377
 
345
378
  # Or, for more finegrained access, set individual limits
346
379
  robot.translation_velocity_limit.set(3.0)
@@ -372,7 +405,7 @@ The robot state can be retrieved by accessing the following properties:
372
405
  obtained
373
406
  from [franka::RobotState::O_T_EE](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#a193781d47722b32925e0ea7ac415f442)
374
407
  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
408
+ * `current_joint_state`: Object of type `franky.JointState`, which contains the joint positions and velocities
376
409
  obtained
377
410
  from [franka::RobotState::q](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#ade3335d1ac2f6c44741a916d565f7091)
378
411
  and [franka::RobotState::dq](https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html#a706045af1b176049e9e56df755325bd2).
@@ -408,7 +441,8 @@ ee_pose_kin = robot.model.pose(Frame.EndEffector, q, f_t_ee, ee_t_k)
408
441
  # Get the jacobian of the current robot state
409
442
  jacobian = robot.model.body_jacobian(Frame.EndEffector, state)
410
443
 
411
- # Alternatively, just get the URDF as string and do the kinematics computation yourself (only for libfranka >= 0.15.0)
444
+ # Alternatively, just get the URDF as string and do the kinematics computation yourself (only
445
+ # for libfranka >= 0.15.0)
412
446
  urdf_model = robot.model_urdf
413
447
  ```
414
448
 
@@ -418,8 +452,7 @@ and [Model](https://timschneider42.github.io/franky/classfranky_1_1_model.html)
418
452
 
419
453
  ### <a id="motion-types" /> 🏃‍♂️ Motion Types
420
454
 
421
- Franky currently supports four different impedance control modes: **joint position control**, **joint velocity control
422
- **, **cartesian position control**, and **cartesian velocity control**.
455
+ Franky currently supports four different impedance control modes: **joint position control**, **joint velocity control**, **cartesian position control**, and **cartesian velocity control**.
423
456
  Each of these control modes is invoked by passing the robot an appropriate _Motion_ object.
424
457
 
425
458
  In the following, we provide a brief example for each motion type implemented by Franky in Python.
@@ -437,28 +470,37 @@ from franky import *
437
470
  # A point-to-point motion in the joint space
438
471
  m_jp1 = JointMotion([-0.3, 0.1, 0.3, -1.4, 0.1, 1.8, 0.7])
439
472
 
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).
473
+ # A motion in joint space with multiple waypoints. The robot will stop at each of these
474
+ # waypoints. If you want the robot to move continuously, you have to specify a target velocity
475
+ # at every waypoint as shown in the example following this one.
476
+ m_jp2 = JointWaypointMotion(
477
+ [
478
+ JointWaypoint([-0.3, 0.1, 0.3, -1.4, 0.1, 1.8, 0.7]),
479
+ JointWaypoint([0.0, 0.3, 0.3, -1.5, -0.2, 1.5, 0.8]),
480
+ JointWaypoint([0.1, 0.4, 0.3, -1.4, -0.3, 1.7, 0.9]),
481
+ ]
482
+ )
483
+
484
+ # Intermediate waypoints also permit to specify target velocities. The default target velocity
485
+ # is 0, meaning that the robot will stop at every waypoint.
486
+ m_jp3 = JointWaypointMotion(
487
+ [
488
+ JointWaypoint([-0.3, 0.1, 0.3, -1.4, 0.1, 1.8, 0.7]),
489
+ JointWaypoint(
490
+ JointState(
491
+ position=[0.0, 0.3, 0.3, -1.5, -0.2, 1.5, 0.8],
492
+ velocity=[0.1, 0.0, 0.0, 0.0, -0.0, 0.0, 0.0],
493
+ )
494
+ ),
495
+ JointWaypoint([0.1, 0.4, 0.3, -1.4, -0.3, 1.7, 0.9]),
496
+ ]
497
+ )
498
+
499
+ # Stop the robot in joint position control mode. The difference of JointStopMotion to other
500
+ # stop-motions such as CartesianStopMotion is that JointStopMotion stops the robot in joint
501
+ # position control mode while CartesianStopMotion stops it in cartesian pose control mode. The
502
+ # difference becomes relevant when asynchronous move commands are being sent or reactions are
503
+ # being used(see below).
462
504
  m_jp4 = JointStopMotion()
463
505
  ```
464
506
 
@@ -468,18 +510,30 @@ m_jp4 = JointStopMotion()
468
510
  from franky import *
469
511
 
470
512
  # 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
- ])
513
+ m_jv1 = JointVelocityMotion(
514
+ [0.1, 0.3, -0.1, 0.0, 0.1, -0.2, 0.4], duration=Duration(1000)
515
+ )
516
+
517
+ # Joint velocity motions also support waypoints. Unlike in joint position control, a joint
518
+ # velocity waypoint is a target velocity to be reached. This particular example first
519
+ # accelerates the joints, holds the velocity for 1s, then reverses direction for 2s, reverses
520
+ # direction again for 1s, and finally stops. It is important not to forget to stop the robot
521
+ # at the end of such a sequence, as it will otherwise throw an error.
522
+ m_jv2 = JointVelocityWaypointMotion(
523
+ [
524
+ JointVelocityWaypoint(
525
+ [0.1, 0.3, -0.1, 0.0, 0.1, -0.2, 0.4], hold_target_duration=Duration(1000)
526
+ ),
527
+ JointVelocityWaypoint(
528
+ [-0.1, -0.3, 0.1, -0.0, -0.1, 0.2, -0.4],
529
+ hold_target_duration=Duration(2000),
530
+ ),
531
+ JointVelocityWaypoint(
532
+ [0.1, 0.3, -0.1, 0.0, 0.1, -0.2, 0.4], hold_target_duration=Duration(1000)
533
+ ),
534
+ JointVelocityWaypoint([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]),
535
+ ]
536
+ )
483
537
 
484
538
  # Stop the robot in joint velocity control mode.
485
539
  m_jv3 = JointVelocityStopMotion()
@@ -497,29 +551,44 @@ quat = Rotation.from_euler("xyz", [0, 0, math.pi / 2]).as_quat()
497
551
  m_cp1 = CartesianMotion(Affine([0.4, -0.2, 0.3], quat))
498
552
 
499
553
  # 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)))
554
+ m_cp2 = CartesianMotion(
555
+ RobotPose(Affine([0.4, -0.2, 0.3], quat), elbow_state=ElbowState(0.3))
556
+ )
501
557
 
502
558
  # 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)
559
+ # (Note that this motion is relative both in position and orientation. Hence, when the robot's
560
+ # end-effector is oriented differently, it will move in a different direction)
505
561
  m_cp3 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
506
562
 
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
- ])
563
+ # Generalization of CartesianMotion that allows for multiple waypoints. The robot will stop at
564
+ # each of these waypoints. If you want the robot to move continuously, you have to specify a
565
+ # target velocity at every waypoint as shown in the example following this one.
566
+ m_cp4 = CartesianWaypointMotion(
567
+ [
568
+ CartesianWaypoint(
569
+ RobotPose(Affine([0.4, -0.2, 0.3], quat), elbow_state=ElbowState(0.3))
570
+ ),
571
+ # The following waypoint is relative to the prior one and 50% slower
572
+ CartesianWaypoint(
573
+ Affine([0.2, 0.0, 0.0]),
574
+ ReferenceType.Relative,
575
+ RelativeDynamicsFactor(0.5, 1.0, 1.0),
576
+ ),
577
+ ]
578
+ )
579
+
580
+ # Cartesian waypoints permit to specify target velocities
581
+ m_cp5 = CartesianWaypointMotion(
582
+ [
583
+ CartesianWaypoint(Affine([0.5, -0.2, 0.3], quat)),
584
+ CartesianWaypoint(
585
+ CartesianState(
586
+ pose=Affine([0.4, -0.1, 0.3], quat), velocity=Twist([-0.01, 0.01, 0.0])
587
+ )
588
+ ),
589
+ CartesianWaypoint(Affine([0.3, 0.0, 0.3], quat)),
590
+ ]
591
+ )
523
592
 
524
593
  # Stop the robot in cartesian position control mode.
525
594
  m_cp6 = CartesianStopMotion()
@@ -530,22 +599,37 @@ m_cp6 = CartesianStopMotion()
530
599
  ```python
531
600
  from franky import *
532
601
 
533
- # A cartesian velocity motion with linear (first argument) and angular (second argument) components
602
+ # A cartesian velocity motion with linear (first argument) and angular (second argument)
603
+ # components
534
604
  m_cv1 = CartesianVelocityMotion(Twist([0.2, -0.1, 0.1], [0.1, -0.1, 0.2]))
535
605
 
536
606
  # 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
- ])
607
+ m_cv2 = CartesianVelocityMotion(
608
+ RobotVelocity(Twist([0.2, -0.1, 0.1], [0.1, -0.1, 0.2]), elbow_velocity=-0.2)
609
+ )
610
+
611
+ # Cartesian velocity motions also support multiple waypoints. Unlike in cartesian position
612
+ # control, a cartesian velocity waypoint is a target velocity to be reached. This particular
613
+ # example first accelerates the end-effector, holds the velocity for 1s, then reverses
614
+ # direction for 2s, reverses direction again for 1s, and finally stops. It is important not to
615
+ # forget to stop the robot at the end of such a sequence, as it will otherwise throw an error.
616
+ m_cv4 = CartesianVelocityWaypointMotion(
617
+ [
618
+ CartesianVelocityWaypoint(
619
+ Twist([0.2, -0.1, 0.1], [0.1, -0.1, 0.2]),
620
+ hold_target_duration=Duration(1000),
621
+ ),
622
+ CartesianVelocityWaypoint(
623
+ Twist([-0.2, 0.1, -0.1], [-0.1, 0.1, -0.2]),
624
+ hold_target_duration=Duration(2000),
625
+ ),
626
+ CartesianVelocityWaypoint(
627
+ Twist([0.2, -0.1, 0.1], [0.1, -0.1, 0.2]),
628
+ hold_target_duration=Duration(1000),
629
+ ),
630
+ CartesianVelocityWaypoint(Twist()),
631
+ ]
632
+ )
549
633
 
550
634
  # Stop the robot in cartesian velocity control mode.
551
635
  m_cv6 = CartesianVelocityStopMotion()
@@ -574,14 +658,15 @@ The real robot can be moved by applying a motion to the robot using `move`:
574
658
  ```python
575
659
  # Before moving the robot, set an appropriate dynamics factor. We start small:
576
660
  robot.relative_dynamics_factor = 0.05
577
- # or alternatively, to control the scaling of velocity, acceleration, and jerk limits separately:
661
+ # or alternatively, to control the scaling of velocity, acceleration, and jerk limits
662
+ # separately:
578
663
  robot.relative_dynamics_factor = RelativeDynamicsFactor(0.05, 0.1, 0.15)
579
664
  # If these values are set too high, you will see discontinuity errors
580
665
 
581
666
  robot.move(m_jp1)
582
667
 
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).
668
+ # We can also set a relative dynamics factor in the move command. It will be multiplied with
669
+ # the other relative dynamics factors (robot and motion if present).
585
670
  robot.move(m_jp2, relative_dynamics_factor=0.8)
586
671
  ```
587
672
 
@@ -596,7 +681,8 @@ def cb(
596
681
  time_step: Duration,
597
682
  rel_time: Duration,
598
683
  abs_time: Duration,
599
- control_signal: JointPositions):
684
+ control_signal: JointPositions,
685
+ ):
600
686
  print(f"At time {abs_time}, the target joint positions were {control_signal.q}")
601
687
 
602
688
 
@@ -621,9 +707,10 @@ from franky import CartesianMotion, Affine, ReferenceType, Measure, Reaction
621
707
 
622
708
  motion = CartesianMotion(Affine([0.0, 0.0, 0.1]), ReferenceType.Relative) # Move down 10cm
623
709
 
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
710
+ # It is important that the reaction motion uses the same control mode as the original motion.
711
+ # Hence, we cannot register a JointMotion as a reaction motion to a CartesianMotion.
712
+ # Move up for 1cm
713
+ reaction_motion = CartesianMotion(Affine([0.0, 0.0, 0.01]), ReferenceType.Relative)
627
714
 
628
715
  # Trigger reaction if the Z force is greater than 30N
629
716
  reaction = Reaction(Measure.FORCE_Z > 30.0, reaction_motion)
@@ -686,7 +773,8 @@ them.
686
773
  In C++ you can additionally use lambdas to define more complex behaviours:
687
774
 
688
775
  ```c++
689
- auto motion = CartesianMotion(RobotPose(Affine({0.0, 0.0, 0.2}), 0.0), ReferenceType::Relative);
776
+ auto motion = CartesianMotion(
777
+ RobotPose(Affine({0.0, 0.0, 0.2}), 0.0), ReferenceType::Relative);
690
778
 
691
779
  // Stop motion if force is over 10N
692
780
  auto stop_motion = StopMotion<franka::CartesianPose>()
@@ -705,7 +793,7 @@ motion
705
793
  }),
706
794
  [](const franka::RobotState& state, double rel_time, double abs_time) {
707
795
  // Lambda reaction motion generator
708
- // (we are just returning a stop motion, but there could be arbitrary
796
+ // (we are just returning a stop motion, but there could be arbitrary
709
797
  // logic here for generating reaction motions)
710
798
  return StopMotion<franka::CartesianPose>();
711
799
  })
@@ -731,8 +819,8 @@ motion1 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
731
819
  robot.move(motion1, asynchronous=True)
732
820
 
733
821
  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.
822
+ # Note that similar to reactions, when preempting active motions with new motions, the
823
+ # control mode cannot change. Hence, we cannot use, e.g., a JointMotion here.
736
824
  motion2 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
737
825
  robot.move(motion2, asynchronous=True)
738
826
  ```
@@ -750,7 +838,7 @@ The next time `Robot.join_motion` or `Robot.move` are called, they will throw th
750
838
  Hence, after an asynchronous motion has finished, make sure to call `Robot.join_motion` to ensure being notified of any
751
839
  exceptions that occurred during the motion.
752
840
 
753
- ### Gripper
841
+ ### <a id="gripper" /> 👌 Gripper
754
842
 
755
843
  In the `franky::Gripper` class, the default gripper force and gripper speed can be set.
756
844
  Then, additionally to the libfranka commands, the following helper methods can be used:
@@ -825,6 +913,81 @@ else:
825
913
  print("Gripper motion timed out.")
826
914
  ```
827
915
 
916
+ ### Accessing the Web Interface API
917
+
918
+ 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.
919
+ The Franka UI also provides methods for locking and unlocking the brakes, setting the execution mode, and executing the safety self-test.
920
+ 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.
921
+
922
+ For that reason, Franky provides a `RobotWebSession` class that allows you to access the web interface API of the robot.
923
+ Note that directly accessing the web interface API is not officially supported and documented by Franka.
924
+ Hence, use this feature at your own risk.
925
+
926
+ A typical automated workflow could look like this:
927
+
928
+ ```python
929
+ import franky
930
+
931
+ with franky.RobotWebSession("172.16.0.2", "username", "password") as robot_web_session:
932
+ # First take control
933
+ try:
934
+ # Try taking control. The session currently holding control has to release it in order
935
+ # for this session to gain control. In the web interface, a notification will show
936
+ # prompting the user to release control. If the other session is another
937
+ # franky.RobotWebSession, then the `release_control` method can be called on the other
938
+ # session to release control.
939
+ robot_web_session.take_control(wait_timeout=10.0)
940
+ except franky.TakeControlTimeoutError:
941
+ # If nothing happens for 10s, we try to take control forcefully. This is particularly
942
+ # useful if the session holding control is dead. Taking control by force requires the
943
+ # user to manually push the blue button close to the robot's wrist.
944
+ robot_web_session.take_control(wait_timeout=30.0, force=True)
945
+
946
+ # Unlock the brakes
947
+ robot_web_session.unlock_brakes()
948
+
949
+ # Enable the FCI
950
+ robot_web_session.enable_fci()
951
+
952
+ # Create a franky.Robot instance and do whatever you want
953
+ ...
954
+
955
+ # Disable the FCI
956
+ robot_web_session.disable_fci()
957
+
958
+ # Lock brakes
959
+ robot_web_session.lock_brakes()
960
+ ```
961
+
962
+ 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.
963
+ `RobotWebSession` allows to automate this task as well:
964
+
965
+ ```python
966
+ import time
967
+ import franky
968
+
969
+ with franky.RobotWebSession("172.16.0.2", "username", "password") as robot_web_session:
970
+ # Execute self-test if the time until self-test is less than 5 minutes.
971
+ if robot_web_session.get_system_status()["safety"]["timeToTd2"] < 300:
972
+ robot_web_session.disable_fci()
973
+ robot_web_session.lock_brakes()
974
+ time.sleep(1.0)
975
+
976
+ robot_web_session.execute_self_test()
977
+
978
+ robot_web_session.unlock_brakes()
979
+ robot_web_session.enable_fci()
980
+ time.sleep(1.0)
981
+
982
+ # Recreate your franky.Robot instance as the FCI has been disabled and re-enabled
983
+ ...
984
+ ```
985
+
986
+ `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.
987
+
988
+ If you want to call other API functions, you can use the `RobotWebSession.send_api_request` and `RobotWebSession.send_control_api_request` methods.
989
+ See [robot_web_session.py](franky/robot_web_session.py) for an example of how to use these methods.
990
+
828
991
  ## 🛠️ Development
829
992
 
830
993
  Franky is currently tested against following versions
@@ -867,3 +1030,12 @@ Aside of bug fixes and general performance improvements, Franky provides the fol
867
1030
  * Franky supports [joint velocity control](#joint-velocity-control)
868
1031
  and [cartesian velocity control](#cartesian-velocity-control)
869
1032
  * The dynamics limits are not hard-coded anymore but can be [set for each robot instance](#-robot).
1033
+
1034
+ ## Contributing
1035
+
1036
+ If you wish to contribute to this project, you are welcome to create a pull request.
1037
+ Please run the [pre-commit](https://pre-commit.com/) hooks before submitting your pull request.
1038
+ To install the pre-commit hooks, run:
1039
+
1040
+ 1. [Install pre-commit](https://pre-commit.com/#install)
1041
+ 2. Install the Git hooks by running `pre-commit install` or, alternatively, run `pre-commit run --all-files manually.
@@ -0,0 +1,26 @@
1
+ franky/__init__.py,sha256=57BsmUytdeqMrhHglwvxMS6CgpAEVPw0KJge8_UTzEA,378
2
+ franky/_franky.cpython-38-x86_64-linux-gnu.so,sha256=ma1dPQVos-S7VtmVPwIQjbHXm0WAAeMl_5f327vUc5U,3049137
3
+ franky/_franky.pyi,sha256=odBnBaM2qGN4mUa8WvFN5SL9aszPgDTsZj5Jb9UkFHk,60047
4
+ franky/motion.py,sha256=TWsx2Ba9iYG9e-OxpuYZlVn1wdzKS-Zvz6ayHT_HYXQ,354
5
+ franky/reaction.py,sha256=cBuHAMek9yH-9Zmwfa0dzz2t5G_1SQEWXNdW7mhhCI8,1519
6
+ franky/robot.py,sha256=NaTNh4PaJshbz44eibvLCMt6O_Ak7TRVjhUR6AGay9A,236
7
+ franky/robot_web_session.py,sha256=rYpnUe4b8xj5JjCYxNRZ0uYz8lL2qfxKglcImFDw24Y,9070
8
+ franky_control.libs/libPocoFoundation-44d67b9f.so.95,sha256=6sSpoT5WNjvmbsEdjYvp5uu8nhEx-elAH67Gw8I2twA,3269633
9
+ franky_control.libs/libPocoNet-3bdfeb79.so.95,sha256=_ZbdxzOFhIIiSHA79e8yKNyCjfGVFbzYFvHqaKnqoFc,2482737
10
+ franky_control.libs/libboost_filesystem-0bf67256.so.1.75.0,sha256=MV-QRMY_pZ0zReU4H4AbcpyZ_sc6yZ6QR6QdDxF84Qc,139961
11
+ franky_control.libs/libboost_serialization-67da18f6.so.1.75.0,sha256=Wjn9rKqoXLrVK29NShhm_evaRsbhTFvvGydi8gwr5hs,319177
12
+ franky_control.libs/libconsole_bridge-acce180d.so.1.0,sha256=-iSKX9xNyLCSSrducf7rDx6hXzdU5v7xQqZDulppIP8,22769
13
+ franky_control.libs/libfmt-677b7a5c.so.8.1.1,sha256=rN3uzEn_limS_u6DV-BxdTEbs2GrhlicD_OjyAlKYpA,140649
14
+ franky_control.libs/libfranka-e5e9247f.so.0.15.0,sha256=rJDob_PoDQHpC78J-rhR67oqlhmlTnS2Red0bClsi2I,973497
15
+ franky_control.libs/libpinocchio_default-def973fb.so.3.1.0,sha256=cMnEW8NgbxqYEpdZH0Ymp-B5SEKzGiKq4GA0BcZ-JV4,9668545
16
+ franky_control.libs/libpinocchio_parsers-d98f9e85.so.3.1.0,sha256=HbwrdisSDbC2mXCz1NVhACUIaXconvI3i-BN1W9qJuE,707441
17
+ franky_control.libs/libtinyxml-69e5f0dd.so.0.2.6.2,sha256=V45jOzaljaUrtOAYBS20QBFHn0qPFHTEcWxdcOBoJNA,118121
18
+ franky_control.libs/liburdfdom_model-9ec0392f.so.1.0,sha256=Kwlq8DuENLdEX5URKcwUC06sl9rxUYoRjGx3EI-uRiY,146081
19
+ franky_control.libs/liburdfdom_model_state-01125232.so.1.0,sha256=LNMEG27nv_6BYvelpjXjr0YsBl-6IsGQfg3uG0DvTQQ,20857
20
+ franky_control.libs/liburdfdom_sensor-011819fa.so.1.0,sha256=LzFH_sfeyWcV042TmgSEXTQL1c0teyYg3veA8sTn_EM,20857
21
+ franky_control.libs/liburdfdom_world-4d53bc81.so.1.0,sha256=IziPhPYdFfZTgKDOnUMGLYSCsZRxYfC1rEKWjvzrpb4,146081
22
+ franky_control-1.1.1.dist-info/LICENSE,sha256=2n6rt7r999OuXp8iOqW9we7ORaxWncIbOwN1ILRGR2g,7651
23
+ franky_control-1.1.1.dist-info/METADATA,sha256=krU979EyVmkb6rZBCIm_sLRAurodnpVmyAJLOVGZXXU,40968
24
+ franky_control-1.1.1.dist-info/WHEEL,sha256=L3HW8fVbXzdi0Qbq6Dl6IkkMSshhqlUpffoAzAKCWvI,111
25
+ franky_control-1.1.1.dist-info/top_level.txt,sha256=LdDKRvHTODs6ll6Ow5b-gmWqt4NJffHxL83MRTCv_Ag,22
26
+ franky_control-1.1.1.dist-info/RECORD,,
@@ -1,26 +0,0 @@
1
- franky/__init__.py,sha256=lmRG8cc4eX-0gZgCkxxVCOrmuUEGJsppWl7DDURib-Y,293
2
- franky/_franky.cpython-38-x86_64-linux-gnu.so,sha256=giR-PnoKEbVXiTR_fGw-hRsy5aubJ7iIWjIl04C-uzk,3040945
3
- franky/_franky.pyi,sha256=odBnBaM2qGN4mUa8WvFN5SL9aszPgDTsZj5Jb9UkFHk,60047
4
- franky/motion.py,sha256=EZmZPvu2r4YBhcokV1PFh8s8NmiwOUERvct3Zz629C8,334
5
- franky/reaction.py,sha256=gDD7kVc_7Et2NwMmCB4Hcd12aK0eygJVqXzZ9Dzw0_M,1488
6
- franky/robot.py,sha256=NaTNh4PaJshbz44eibvLCMt6O_Ak7TRVjhUR6AGay9A,236
7
- franky/robot_web_session.py,sha256=zOTAqDF4PbZLqJFr3RcuBwfWRSEMiw0Eag1stk3GWKE,7622
8
- franky_control.libs/libPocoFoundation-44c2a91d.so.95,sha256=kMB_IJ_gYGE1jprdF_RIVEbhg9gQH3IimwBUksadJNc,3265609
9
- franky_control.libs/libPocoNet-2f9ce4bf.so.95,sha256=wwgasubJUNFpW5brGQoUiyCEx6NgPQSG2Vjgk66OQ0s,2482737
10
- franky_control.libs/libboost_filesystem-42b111b5.so.1.75.0,sha256=8tanNbQ7I455iTdjcNXuKf8snHpXq6N7SVvnX5H-_bY,139961
11
- franky_control.libs/libboost_serialization-0b785d4d.so.1.75.0,sha256=sOHF1ncSl_Hg4oBqbyEuQCYAE9IaREqfm-dspP-O5mw,319177
12
- franky_control.libs/libconsole_bridge-acce180d.so.1.0,sha256=-iSKX9xNyLCSSrducf7rDx6hXzdU5v7xQqZDulppIP8,22769
13
- franky_control.libs/libfmt-677b7a5c.so.8.1.1,sha256=rN3uzEn_limS_u6DV-BxdTEbs2GrhlicD_OjyAlKYpA,140649
14
- franky_control.libs/libfranka-976dfd01.so.0.15.0,sha256=q6EJaLfNrYHNcwJvov9s2sM18ahCZ2LgKZwZTbvDbok,973497
15
- franky_control.libs/libpinocchio_default-b05a4796.so.3.1.0,sha256=NFyO0kOaOcpnFYVAehcgJj5spee4weJ_PqPZ5uUqpEg,9668545
16
- franky_control.libs/libpinocchio_parsers-74bdc3cc.so.3.1.0,sha256=4yyz3Gw4SoyFEtvfx546_UMpH3GN9SjVWsWH28eCVSs,707441
17
- franky_control.libs/libtinyxml-69e5f0dd.so.0.2.6.2,sha256=V45jOzaljaUrtOAYBS20QBFHn0qPFHTEcWxdcOBoJNA,118121
18
- franky_control.libs/liburdfdom_model-9ec0392f.so.1.0,sha256=Kwlq8DuENLdEX5URKcwUC06sl9rxUYoRjGx3EI-uRiY,146081
19
- franky_control.libs/liburdfdom_model_state-01125232.so.1.0,sha256=LNMEG27nv_6BYvelpjXjr0YsBl-6IsGQfg3uG0DvTQQ,20857
20
- franky_control.libs/liburdfdom_sensor-011819fa.so.1.0,sha256=LzFH_sfeyWcV042TmgSEXTQL1c0teyYg3veA8sTn_EM,20857
21
- franky_control.libs/liburdfdom_world-4d53bc81.so.1.0,sha256=IziPhPYdFfZTgKDOnUMGLYSCsZRxYfC1rEKWjvzrpb4,146081
22
- franky_control-1.0.2.dist-info/LICENSE,sha256=6or154nLLU6bELzjh0mCreFjt0m2v72zLi3yHE0QbeE,7650
23
- franky_control-1.0.2.dist-info/METADATA,sha256=8w7ITX99ftSyZ4TTdgcZ8fxgYC0_UsNfzcbgatWPK-4,34881
24
- franky_control-1.0.2.dist-info/WHEEL,sha256=L3HW8fVbXzdi0Qbq6Dl6IkkMSshhqlUpffoAzAKCWvI,111
25
- franky_control-1.0.2.dist-info/top_level.txt,sha256=LdDKRvHTODs6ll6Ow5b-gmWqt4NJffHxL83MRTCv_Ag,22
26
- franky_control-1.0.2.dist-info/RECORD,,