reachy-mini 1.2.5rc1__py3-none-any.whl → 1.2.11__py3-none-any.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.
Files changed (65) hide show
  1. reachy_mini/apps/app.py +24 -21
  2. reachy_mini/apps/manager.py +17 -3
  3. reachy_mini/apps/sources/hf_auth.py +92 -0
  4. reachy_mini/apps/sources/hf_space.py +1 -1
  5. reachy_mini/apps/sources/local_common_venv.py +199 -24
  6. reachy_mini/apps/templates/main.py.j2 +4 -3
  7. reachy_mini/daemon/app/dashboard/static/js/apps.js +9 -1
  8. reachy_mini/daemon/app/dashboard/static/js/appstore.js +228 -0
  9. reachy_mini/daemon/app/dashboard/static/js/logs.js +148 -0
  10. reachy_mini/daemon/app/dashboard/templates/logs.html +37 -0
  11. reachy_mini/daemon/app/dashboard/templates/sections/appstore.html +92 -0
  12. reachy_mini/daemon/app/dashboard/templates/sections/cache.html +82 -0
  13. reachy_mini/daemon/app/dashboard/templates/sections/daemon.html +5 -0
  14. reachy_mini/daemon/app/dashboard/templates/settings.html +1 -0
  15. reachy_mini/daemon/app/main.py +172 -7
  16. reachy_mini/daemon/app/models.py +8 -0
  17. reachy_mini/daemon/app/routers/apps.py +56 -0
  18. reachy_mini/daemon/app/routers/cache.py +58 -0
  19. reachy_mini/daemon/app/routers/hf_auth.py +57 -0
  20. reachy_mini/daemon/app/routers/logs.py +124 -0
  21. reachy_mini/daemon/app/routers/state.py +25 -1
  22. reachy_mini/daemon/app/routers/wifi_config.py +75 -0
  23. reachy_mini/daemon/app/services/bluetooth/bluetooth_service.py +1 -1
  24. reachy_mini/daemon/app/services/bluetooth/commands/WIFI_RESET.sh +8 -0
  25. reachy_mini/daemon/app/services/wireless/launcher.sh +8 -2
  26. reachy_mini/daemon/app/services/wireless/reachy-mini-daemon.service +13 -0
  27. reachy_mini/daemon/backend/abstract.py +29 -9
  28. reachy_mini/daemon/backend/mockup_sim/__init__.py +12 -0
  29. reachy_mini/daemon/backend/mockup_sim/backend.py +176 -0
  30. reachy_mini/daemon/backend/mujoco/backend.py +0 -5
  31. reachy_mini/daemon/backend/robot/backend.py +78 -5
  32. reachy_mini/daemon/daemon.py +46 -7
  33. reachy_mini/daemon/utils.py +71 -15
  34. reachy_mini/io/zenoh_client.py +26 -0
  35. reachy_mini/io/zenoh_server.py +10 -6
  36. reachy_mini/kinematics/nn_kinematics.py +2 -2
  37. reachy_mini/kinematics/placo_kinematics.py +15 -15
  38. reachy_mini/media/__init__.py +55 -1
  39. reachy_mini/media/audio_base.py +185 -13
  40. reachy_mini/media/audio_control_utils.py +60 -5
  41. reachy_mini/media/audio_gstreamer.py +97 -16
  42. reachy_mini/media/audio_sounddevice.py +120 -19
  43. reachy_mini/media/audio_utils.py +110 -5
  44. reachy_mini/media/camera_base.py +182 -11
  45. reachy_mini/media/camera_constants.py +132 -4
  46. reachy_mini/media/camera_gstreamer.py +42 -2
  47. reachy_mini/media/camera_opencv.py +83 -5
  48. reachy_mini/media/camera_utils.py +95 -7
  49. reachy_mini/media/media_manager.py +139 -6
  50. reachy_mini/media/webrtc_client_gstreamer.py +142 -13
  51. reachy_mini/media/webrtc_daemon.py +72 -7
  52. reachy_mini/motion/recorded_move.py +76 -2
  53. reachy_mini/reachy_mini.py +196 -40
  54. reachy_mini/tools/reflash_motors.py +1 -1
  55. reachy_mini/tools/scan_motors.py +86 -0
  56. reachy_mini/tools/setup_motor.py +49 -31
  57. reachy_mini/utils/interpolation.py +1 -1
  58. reachy_mini/utils/wireless_version/startup_check.py +278 -21
  59. reachy_mini/utils/wireless_version/update.py +44 -1
  60. {reachy_mini-1.2.5rc1.dist-info → reachy_mini-1.2.11.dist-info}/METADATA +7 -6
  61. {reachy_mini-1.2.5rc1.dist-info → reachy_mini-1.2.11.dist-info}/RECORD +65 -53
  62. {reachy_mini-1.2.5rc1.dist-info → reachy_mini-1.2.11.dist-info}/WHEEL +0 -0
  63. {reachy_mini-1.2.5rc1.dist-info → reachy_mini-1.2.11.dist-info}/entry_points.txt +0 -0
  64. {reachy_mini-1.2.5rc1.dist-info → reachy_mini-1.2.11.dist-info}/licenses/LICENSE +0 -0
  65. {reachy_mini-1.2.5rc1.dist-info → reachy_mini-1.2.11.dist-info}/top_level.txt +0 -0
@@ -9,8 +9,9 @@ It also includes methods for multimedia interactions like playing sounds and loo
9
9
  import asyncio
10
10
  import json
11
11
  import logging
12
+ import platform
12
13
  import time
13
- from typing import Dict, List, Optional, Union
14
+ from typing import Dict, List, Literal, Optional, Union, cast
14
15
 
15
16
  import cv2
16
17
  import numpy as np
@@ -18,7 +19,7 @@ import numpy.typing as npt
18
19
  from asgiref.sync import async_to_sync
19
20
  from scipy.spatial.transform import Rotation as R
20
21
 
21
- from reachy_mini.daemon.utils import daemon_check
22
+ from reachy_mini.daemon.utils import daemon_check, is_local_camera_available
22
23
  from reachy_mini.io.protocol import GotoTaskRequest
23
24
  from reachy_mini.io.zenoh_client import ZenohClient
24
25
  from reachy_mini.media.media_manager import MediaBackend, MediaManager
@@ -49,12 +50,17 @@ SLEEP_HEAD_POSE = np.array(
49
50
  ]
50
51
  )
51
52
 
53
+ ConnectionMode = Literal["auto", "localhost_only", "network"]
54
+
52
55
 
53
56
  class ReachyMini:
54
57
  """Reachy Mini class for controlling a simulated or real Reachy Mini robot.
55
58
 
56
59
  Args:
57
- localhost_only (bool): If True, will only connect to localhost daemons, defaults to True.
60
+ connection_mode: Select how to connect to the daemon. Use
61
+ `"localhost_only"` to restrict connections to daemons running on
62
+ localhost, `"network"` to scout for daemons on the LAN, or `"auto"`
63
+ (default) to try localhost first then fall back to the network.
58
64
  spawn_daemon (bool): If True, will spawn a daemon to control the robot, defaults to False.
59
65
  use_sim (bool): If True and spawn_daemon is True, will spawn a simulated robot, defaults to True.
60
66
 
@@ -63,25 +69,33 @@ class ReachyMini:
63
69
  def __init__(
64
70
  self,
65
71
  robot_name: str = "reachy_mini",
66
- localhost_only: bool = True,
72
+ connection_mode: ConnectionMode = "auto",
67
73
  spawn_daemon: bool = False,
68
74
  use_sim: bool = False,
69
75
  timeout: float = 5.0,
70
76
  automatic_body_yaw: bool = True,
71
77
  log_level: str = "INFO",
72
78
  media_backend: str = "default",
79
+ localhost_only: Optional[bool] = None,
73
80
  ) -> None:
74
81
  """Initialize the Reachy Mini robot.
75
82
 
76
83
  Args:
77
84
  robot_name (str): Name of the robot, defaults to "reachy_mini".
78
- localhost_only (bool): If True, will only connect to localhost daemons, defaults to True.
85
+ connection_mode: `"auto"` (default), `"localhost_only"` or `"network"`.
86
+ `"auto"` will first try daemons on localhost and fall back to
87
+ network discovery if no local daemon responds.
88
+ localhost_only (Optional[bool]): Deprecated alias for the connection
89
+ mode. Set `False` to search for network daemons. Will be removed
90
+ in a future release.
79
91
  spawn_daemon (bool): If True, will spawn a daemon to control the robot, defaults to False.
80
92
  use_sim (bool): If True and spawn_daemon is True, will spawn a simulated robot, defaults to True.
81
93
  timeout (float): Timeout for the client connection, defaults to 5.0 seconds.
82
94
  automatic_body_yaw (bool): If True, the body yaw will be used to compute the IK and FK. Default is False.
83
95
  log_level (str): Logging level, defaults to "INFO".
84
- media_backend (str): Media backend to use, either "default" (OpenCV), "gstreamer" or "webrtc", defaults to "default".
96
+ media_backend (str): Use "no_media" to disable media entirely. Any other value
97
+ triggers auto-detection: Lite uses OpenCV, Wireless uses GStreamer (local)
98
+ or WebRTC (remote) based on environment.
85
99
 
86
100
  It will try to connect to the daemon, and if it fails, it will raise an exception.
87
101
 
@@ -90,8 +104,12 @@ class ReachyMini:
90
104
  self.logger.setLevel(log_level)
91
105
  self.robot_name = robot_name
92
106
  daemon_check(spawn_daemon, use_sim)
93
- self.client = ZenohClient(robot_name, localhost_only)
94
- self.client.wait_for_connection(timeout=timeout)
107
+ normalized_mode = self._normalize_connection_mode(
108
+ connection_mode, localhost_only
109
+ )
110
+ self.client, self.connection_mode = self._initialize_client(
111
+ normalized_mode, timeout
112
+ )
95
113
  self.set_automatic_body_yaw(automatic_body_yaw)
96
114
  self._last_head_pose: Optional[npt.NDArray[np.float64]] = None
97
115
  self.is_recording = False
@@ -131,40 +149,97 @@ class ReachyMini:
131
149
  """Expose the MediaManager instance used by ReachyMini."""
132
150
  return self.media_manager
133
151
 
152
+ @property
153
+ def imu(self) -> Dict[str, List[float] | float] | None:
154
+ """Get the current IMU data from the backend.
155
+
156
+ Returns:
157
+ dict with the following keys, or None if IMU is not available (Lite version)
158
+ or no data received yet:
159
+ - 'accelerometer': [x, y, z] in m/s^2
160
+ - 'gyroscope': [x, y, z] in rad/s
161
+ - 'quaternion': [w, x, y, z] orientation quaternion
162
+ - 'temperature': float in °C
163
+
164
+ Note:
165
+ - Data is cached from the last Zenoh update at 50Hz
166
+ - Quaternion is in [w, x, y, z] format
167
+
168
+ Example:
169
+ >>> imu_data = reachy.imu
170
+ >>> if imu_data is not None:
171
+ >>> accel_x, accel_y, accel_z = imu_data['accelerometer']
172
+ >>> gyro_x, gyro_y, gyro_z = imu_data['gyroscope']
173
+ >>> quat_w, quat_x, quat_y, quat_z = imu_data['quaternion']
174
+ >>> temp = imu_data['temperature']
175
+
176
+ """
177
+ return self.client.get_current_imu_data()
178
+
134
179
  def _configure_mediamanager(
135
180
  self, media_backend: str, log_level: str
136
181
  ) -> MediaManager:
137
- mbackend = MediaBackend.DEFAULT
138
182
  daemon_status = self.client.get_status()
183
+ is_wireless = daemon_status.get("wireless_version", False)
139
184
 
140
- # If wireless, force webrtc unless no_media is selected
141
- if media_backend != "no_media" and daemon_status.get(
142
- "wireless_version"
143
- ):
144
- mbackend = MediaBackend.WEBRTC
185
+ # If no_media is requested, skip all media initialization
186
+ if media_backend.lower() == "no_media":
187
+ self.logger.info("No media backend requested.")
188
+ mbackend = MediaBackend.NO_MEDIA
145
189
  else:
146
- match media_backend.lower():
147
- case "webrtc":
148
- if not daemon_status.get("wireless_version"):
190
+ if is_wireless:
191
+ if is_local_camera_available():
192
+ # Local client on CM4: use GStreamer to read from unix socket
193
+ # This avoids WebRTC encode/decode overhead
194
+ if "no_video" in media_backend.lower():
195
+ mbackend = MediaBackend.GSTREAMER_NO_VIDEO
196
+ self.logger.info(
197
+ "Auto-detected: Wireless + local camera socket. "
198
+ "Using GStreamer audio-only backend (no WebRTC overhead)."
199
+ )
200
+ else:
201
+ mbackend = MediaBackend.GSTREAMER
202
+ self.logger.info(
203
+ "Auto-detected: Wireless + local camera socket. "
204
+ "Using GStreamer backend (no WebRTC overhead)."
205
+ )
206
+ else:
207
+ # Remote client: use WebRTC for streaming
208
+ self.logger.info(
209
+ "Auto-detected: Wireless + remote client. "
210
+ "Using WebRTC backend for streaming."
211
+ )
212
+ mbackend = MediaBackend.WEBRTC
213
+ else:
214
+ # Lite version: use specified backend if compatible
215
+ try:
216
+ mbackend = MediaBackend(media_backend.lower())
217
+ if mbackend == MediaBackend.WEBRTC:
149
218
  self.logger.warning(
150
- "Non-wireless version detected, daemon should use the flag '--wireless-version'. Reverting to default"
219
+ f"Incompatible media backend on Lite: {media_backend}, using default backend."
151
220
  )
152
221
  mbackend = MediaBackend.DEFAULT
222
+ # TODO : Remove when wheel is released !
223
+ elif "gstreamer" in media_backend.lower() and (
224
+ platform.system() == "Darwin" or platform.system() == "Windows"
225
+ ):
226
+ self.logger.warning(
227
+ f"Unsupported media backend on Lite for {platform.system()}: {media_backend}, using default backend."
228
+ )
229
+ mbackend = (
230
+ MediaBackend.DEFAULT_NO_VIDEO
231
+ if "no_video" in media_backend.lower()
232
+ else MediaBackend.DEFAULT
233
+ )
153
234
  else:
154
- self.logger.info("WebRTC backend configured successfully.")
155
- mbackend = MediaBackend.WEBRTC
156
- case "gstreamer":
157
- mbackend = MediaBackend.GSTREAMER
158
- case "default":
159
- mbackend = MediaBackend.DEFAULT
160
- case "no_media":
161
- mbackend = MediaBackend.NO_MEDIA
162
- case "default_no_video":
163
- mbackend = MediaBackend.DEFAULT_NO_VIDEO
164
- case _:
165
- raise ValueError(
166
- f"Invalid media_backend '{media_backend}'. Supported values are 'default', 'gstreamer', 'no_media', 'default_no_video', and 'webrtc'."
235
+ self.logger.info(
236
+ f"Auto-detected: Lite. Using {mbackend} backend."
237
+ )
238
+ except ValueError:
239
+ self.logger.warning(
240
+ f"Invalid media backend on Lite: {media_backend}, using default backend."
167
241
  )
242
+ mbackend = MediaBackend.DEFAULT
168
243
 
169
244
  return MediaManager(
170
245
  use_sim=self.client.get_status()["simulation_enabled"],
@@ -173,6 +248,78 @@ class ReachyMini:
173
248
  signalling_host=self.client.get_status()["wlan_ip"],
174
249
  )
175
250
 
251
+ def _normalize_connection_mode(
252
+ self,
253
+ connection_mode: ConnectionMode,
254
+ legacy_localhost_only: Optional[bool],
255
+ ) -> ConnectionMode:
256
+ """Normalize connection mode input, optionally honoring the legacy alias."""
257
+ normalized = connection_mode.lower()
258
+ if normalized not in {"auto", "localhost_only", "network"}:
259
+ raise ValueError(
260
+ "Invalid connection_mode. Use 'auto', 'localhost_only', or 'network'."
261
+ )
262
+ resolved = cast(ConnectionMode, normalized)
263
+
264
+ if legacy_localhost_only is None:
265
+ return resolved
266
+
267
+ self.logger.warning(
268
+ "The 'localhost_only' argument is deprecated and will be removed in a "
269
+ "future release. Please switch to connection_mode."
270
+ )
271
+
272
+ if resolved != "auto":
273
+ self.logger.warning(
274
+ "Both connection_mode=%s and localhost_only=%s were provided. "
275
+ "connection_mode takes precedence.",
276
+ resolved,
277
+ legacy_localhost_only,
278
+ )
279
+ return resolved
280
+
281
+ return "localhost_only" if legacy_localhost_only else "network"
282
+
283
+ def _initialize_client(
284
+ self, requested_mode: ConnectionMode, timeout: float
285
+ ) -> tuple[ZenohClient, ConnectionMode]:
286
+ """Create a client according to the requested mode, adding auto fallback."""
287
+ requested_mode = cast(ConnectionMode, requested_mode.lower())
288
+ if requested_mode == "auto":
289
+ try:
290
+ client = self._connect_single(localhost_only=True, timeout=timeout)
291
+ selected: ConnectionMode = "localhost_only"
292
+ except Exception as err:
293
+ self.logger.info(
294
+ "Auto connection: localhost attempt failed (%s). "
295
+ "Trying network discovery.",
296
+ err,
297
+ )
298
+ client = self._connect_single(localhost_only=False, timeout=timeout)
299
+ selected = "network"
300
+ self.logger.info("Connection mode selected: %s", selected)
301
+ return client, selected
302
+
303
+ if requested_mode == "localhost_only":
304
+ client = self._connect_single(localhost_only=True, timeout=timeout)
305
+ selected = "localhost_only"
306
+ else:
307
+ client = self._connect_single(localhost_only=False, timeout=timeout)
308
+ selected = "network"
309
+
310
+ self.logger.info("Connection mode selected: %s", selected)
311
+ return client, selected
312
+
313
+ def _connect_single(self, localhost_only: bool, timeout: float) -> ZenohClient:
314
+ """Connect once with the requested tunneling mode and guard cleanup."""
315
+ client = ZenohClient(self.robot_name, localhost_only)
316
+ try:
317
+ client.wait_for_connection(timeout=timeout)
318
+ except Exception:
319
+ client.disconnect()
320
+ raise
321
+ return client
322
+
176
323
  def set_target(
177
324
  self,
178
325
  head: Optional[npt.NDArray[np.float64]] = None, # 4x4 pose matrix
@@ -268,12 +415,16 @@ class ReachyMini:
268
415
  )
269
416
 
270
417
  req = GotoTaskRequest(
271
- head=np.array(head, dtype=np.float64).flatten().tolist()
272
- if head is not None
273
- else None,
274
- antennas=np.array(antennas, dtype=np.float64).flatten().tolist()
275
- if antennas is not None
276
- else None,
418
+ head=(
419
+ np.array(head, dtype=np.float64).flatten().tolist()
420
+ if head is not None
421
+ else None
422
+ ),
423
+ antennas=(
424
+ np.array(antennas, dtype=np.float64).flatten().tolist()
425
+ if antennas is not None
426
+ else None
427
+ ),
277
428
  duration=duration,
278
429
  method=method,
279
430
  body_yaw=body_yaw,
@@ -606,9 +757,10 @@ class ReachyMini:
606
757
  cmd = {}
607
758
 
608
759
  if pose is not None:
609
- assert pose.shape == (4, 4), (
610
- f"Head pose should be a 4x4 matrix, got {pose.shape}."
611
- )
760
+ assert pose.shape == (
761
+ 4,
762
+ 4,
763
+ ), f"Head pose should be a 4x4 matrix, got {pose.shape}."
612
764
  cmd["head_pose"] = pose.tolist()
613
765
  else:
614
766
  raise ValueError("Pose must be provided as a 4x4 matrix.")
@@ -667,6 +819,8 @@ class ReachyMini:
667
819
 
668
820
  Args:
669
821
  ids (List[str] | None): List of motor names to enable. If None, all motors will be enabled.
822
+ Valid names match `src/reachy_mini/assets/config/hardware_config.yaml`:
823
+ `body_rotation`, `stewart_1` … `stewart_6`, `right_antenna`, `left_antenna`.
670
824
 
671
825
  """
672
826
  self._set_torque(True, ids=ids)
@@ -676,6 +830,8 @@ class ReachyMini:
676
830
 
677
831
  Args:
678
832
  ids (List[str] | None): List of motor names to disable. If None, all motors will be disabled.
833
+ Valid names match `src/reachy_mini/assets/config/hardware_config.yaml`:
834
+ `body_rotation`, `stewart_1` … `stewart_6`, `right_antenna`, `left_antenna`.
679
835
 
680
836
  """
681
837
  self._set_torque(False, ids=ids)
@@ -97,7 +97,7 @@ def reflash_motors(
97
97
  )
98
98
  except RuntimeError as e:
99
99
  console.print(
100
- f" Configuration check failed for motor '{motor_name}': {e}",
100
+ f"[FAIL] Configuration check failed for motor '{motor_name}': {e}",
101
101
  style="red",
102
102
  )
103
103
  return
@@ -0,0 +1,86 @@
1
+ """Scan a serial bus to find which motor IDs respond at common baudrates."""
2
+
3
+ import os
4
+ import time
5
+ from typing import List
6
+
7
+ import serial.tools.list_ports
8
+ from rustypot import Xl330PyController
9
+
10
+ SERIAL_TIMEOUT = 0.01
11
+ COMMANDS_BITS_LENGTH = {
12
+ "Ping": (10 + 14) * 10,
13
+ "Read": (14 + 15) * 10,
14
+ "Write": (16 + 11) * 10,
15
+ }
16
+ XL_BAUDRATE_CONV_TABLE = {
17
+ 9600: 0,
18
+ 57600: 1,
19
+ 115200: 2,
20
+ 1000000: 3,
21
+ 2000000: 4,
22
+ 3000000: 5,
23
+ 4000000: 6,
24
+ }
25
+
26
+ def find_serial_port(
27
+ wireless_version: bool = False,
28
+ vid: str = "1a86",
29
+ pid: str = "55d3",
30
+ pi_uart: str = "/dev/ttyAMA3",
31
+ ) -> list[str]:
32
+ """Replicate from the daemon.utils.find_serial_port function."""
33
+ # If it's a wireless version, we should use the Raspberry Pi UART
34
+ if wireless_version:
35
+ return [pi_uart] if os.path.exists(pi_uart) else []
36
+
37
+ # If it's a lite version, we should find it using the VID and PID
38
+ ports = serial.tools.list_ports.comports()
39
+
40
+ vid = vid.upper()
41
+ pid = pid.upper()
42
+
43
+ return [p.device for p in ports if f"USB VID:PID={vid}:{pid}" in p.hwid]
44
+
45
+ def scan(port: str, baudrate: int) -> List[int]:
46
+ """Scan the bus at the given baudrate and return detected IDs."""
47
+ found_motors: list[int] = []
48
+ try:
49
+ controller = Xl330PyController(port, baudrate, float(SERIAL_TIMEOUT) + float(COMMANDS_BITS_LENGTH["Ping"]) / baudrate)
50
+ for motor_id in range(255):
51
+ try:
52
+ if controller.ping(motor_id):
53
+ found_motors.append(motor_id)
54
+ except Exception:
55
+ pass
56
+ except Exception as e:
57
+ print(f"Error while scanning port {port} at baudrate {baudrate}: {e}")
58
+ finally:
59
+ # CRITICAL: Close the controller to release the serial port
60
+ if controller is not None:
61
+ try:
62
+ del controller
63
+ except Exception:
64
+ pass
65
+ # Small delay to ensure port is fully released
66
+ time.sleep(SERIAL_TIMEOUT)
67
+ return found_motors
68
+
69
+ def main() -> None:
70
+ """Iterate through baudrates and print the IDs found at each."""
71
+ try:
72
+ port = find_serial_port()[0]
73
+ except IndexError:
74
+ print("No serial port found. Please check your USB connection and permissions.")
75
+ return
76
+ for baudrate in XL_BAUDRATE_CONV_TABLE.keys():
77
+ print(f"Trying baudrate: {baudrate}")
78
+ found_motors = scan(port, baudrate)
79
+ if found_motors:
80
+ print(f"Found motors at baudrate {baudrate}: {found_motors}")
81
+ else:
82
+ print(f"No motors found at baudrate {baudrate}")
83
+
84
+
85
+ if __name__ == "__main__":
86
+ main()
@@ -32,6 +32,24 @@ XL_BAUDRATE_CONV_TABLE = {
32
32
  4000000: 6,
33
33
  }
34
34
 
35
+ id2name = {
36
+ 10: "body_rotation",
37
+ 11: "stewart_1",
38
+ 12: "stewart_2",
39
+ 13: "stewart_3",
40
+ 14: "stewart_4",
41
+ 15: "stewart_5",
42
+ 16: "stewart_6",
43
+ 17: "right_antenna",
44
+ 18: "left_antenna",
45
+ }
46
+
47
+ # (TX + RX) * (1 start + 8 data + 1 stop)
48
+ COMMANDS_BITS_LENGTH = {
49
+ "Ping": (10 + 14) * 10,
50
+ "Read": (14 + 15) * 10,
51
+ "Write": (16 + 11) * 10,
52
+ }
35
53
 
36
54
  def setup_motor(
37
55
  motor_config: MotorConfig,
@@ -47,9 +65,9 @@ def setup_motor(
47
65
  from_baudrate,
48
66
  ):
49
67
  raise RuntimeError(
50
- f"No motor found on port {serial_port}. "
51
- f"Make sure the motor is in factory settings (ID {from_id} and baudrate {from_baudrate}) and connected to the specified port."
68
+ f"No motor found on port {serial_port}. Make sure Reachy Mini is powered !"
52
69
  )
70
+ # f"Make sure the motor {id2name.get(from_id, from_id)} is in factory settings (ID {from_id} and baudrate {from_baudrate}) and connected to the specified port."
53
71
 
54
72
  # Make sure the torque is disabled to be able to write EEPROM
55
73
  disable_torque(serial_port, from_id, from_baudrate)
@@ -132,19 +150,19 @@ def lookup_for_motor(
132
150
  end="",
133
151
  flush=True,
134
152
  )
135
- c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT)
153
+ c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT + float(COMMANDS_BITS_LENGTH["Ping"]) / baudrate)
136
154
  ret = c.ping(id)
137
155
  if not silent:
138
- print(f"{'' if ret else ''}")
156
+ print(f"{'[OK]' if ret else '[FAIL]'}")
139
157
  return ret
140
158
 
141
159
 
142
160
  def disable_torque(serial_port: str, id: int, baudrate: int) -> None:
143
161
  """Disable the torque of the motor with the given ID on the specified serial port."""
144
162
  print(f"Disabling torque for motor with ID {id}...", end="", flush=True)
145
- c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT)
163
+ c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT + float(COMMANDS_BITS_LENGTH["Write"]) / baudrate)
146
164
  c.write_torque_enable(id, False)
147
- print("")
165
+ print("[OK]")
148
166
 
149
167
 
150
168
  def change_baudrate(
@@ -152,25 +170,25 @@ def change_baudrate(
152
170
  ) -> None:
153
171
  """Change the baudrate of the motor with the given ID on the specified serial port."""
154
172
  print(f"Changing baudrate to {target_baudrate}...", end="", flush=True)
155
- c = Xl330PyController(serial_port, baudrate=base_baudrate, timeout=SERIAL_TIMEOUT)
173
+ c = Xl330PyController(serial_port, baudrate=base_baudrate, timeout=SERIAL_TIMEOUT + float(COMMANDS_BITS_LENGTH["Write"]) / base_baudrate)
156
174
  c.write_baud_rate(id, XL_BAUDRATE_CONV_TABLE[target_baudrate])
157
- print("")
175
+ print("[OK]")
158
176
 
159
177
 
160
178
  def change_id(serial_port: str, current_id: int, new_id: int, baudrate: int) -> None:
161
179
  """Change the ID of the motor with the given current ID on the specified serial port."""
162
180
  print(f"Changing ID from {current_id} to {new_id}...", end="", flush=True)
163
- c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT)
181
+ c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT + float(COMMANDS_BITS_LENGTH["Write"]) / baudrate)
164
182
  c.write_id(current_id, new_id)
165
- print("")
183
+ print("[OK]")
166
184
 
167
185
 
168
186
  def change_offset(serial_port: str, id: int, offset: int, baudrate: int) -> None:
169
187
  """Change the offset of the motor with the given ID on the specified serial port."""
170
188
  print(f"Changing offset for motor with ID {id} to {offset}...", end="", flush=True)
171
- c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT)
189
+ c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT + float(COMMANDS_BITS_LENGTH["Write"]) / baudrate)
172
190
  c.write_homing_offset(id, offset)
173
- print("")
191
+ print("[OK]")
174
192
 
175
193
 
176
194
  def change_operating_mode(
@@ -182,9 +200,9 @@ def change_operating_mode(
182
200
  end="",
183
201
  flush=True,
184
202
  )
185
- c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT)
203
+ c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT + float(COMMANDS_BITS_LENGTH["Write"]) / baudrate)
186
204
  c.write_operating_mode(id, operating_mode)
187
- print("")
205
+ print("[OK]")
188
206
 
189
207
 
190
208
  def change_angle_limits(
@@ -200,10 +218,10 @@ def change_angle_limits(
200
218
  end="",
201
219
  flush=True,
202
220
  )
203
- c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT)
221
+ c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT + float(COMMANDS_BITS_LENGTH["Write"]) / baudrate)
204
222
  c.write_raw_min_position_limit(id, angle_limit_min)
205
223
  c.write_raw_max_position_limit(id, angle_limit_max)
206
- print("")
224
+ print("[OK]")
207
225
 
208
226
 
209
227
  def change_shutdown_error(
@@ -215,9 +233,9 @@ def change_shutdown_error(
215
233
  end="",
216
234
  flush=True,
217
235
  )
218
- c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT)
236
+ c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT + float(COMMANDS_BITS_LENGTH["Write"]) / baudrate)
219
237
  c.write_shutdown(id, shutdown_error)
220
- print("")
238
+ print("[OK]")
221
239
 
222
240
 
223
241
  def change_return_delay_time(
@@ -229,14 +247,14 @@ def change_return_delay_time(
229
247
  end="",
230
248
  flush=True,
231
249
  )
232
- c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT)
250
+ c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT + float(COMMANDS_BITS_LENGTH["Write"]) / baudrate)
233
251
  c.write_return_delay_time(id, return_delay_time)
234
- print("")
252
+ print("[OK]")
235
253
 
236
254
 
237
255
  def light_led_up(serial_port: str, id: int, baudrate: int) -> None:
238
256
  """Light the LED of the motor with the given ID on the specified serial port."""
239
- c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT)
257
+ c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT + float(COMMANDS_BITS_LENGTH["Write"]) / baudrate)
240
258
 
241
259
  trials = 0
242
260
 
@@ -251,7 +269,7 @@ def light_led_up(serial_port: str, id: int, baudrate: int) -> None:
251
269
 
252
270
  def light_led_down(serial_port: str, id: int, baudrate: int) -> None:
253
271
  """Light the LED of the motor with the given ID on the specified serial port."""
254
- c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT)
272
+ c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT + float(COMMANDS_BITS_LENGTH["Write"]) / baudrate)
255
273
  trials = 0
256
274
 
257
275
  while trials < 3:
@@ -267,14 +285,14 @@ def check_configuration(
267
285
  motor_config: MotorConfig, serial_port: str, baudrate: int
268
286
  ) -> None:
269
287
  """Check the configuration of the motor with the given ID on the specified serial port."""
270
- c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT)
288
+ c = Xl330PyController(serial_port, baudrate=baudrate, timeout=SERIAL_TIMEOUT + float(COMMANDS_BITS_LENGTH["Read"]) / baudrate)
271
289
 
272
290
  print("Checking configuration...")
273
291
 
274
292
  # Check if there is a motor with the desired ID
275
293
  if not c.ping(motor_config.id):
276
294
  raise RuntimeError(f"No motor with ID {motor_config.id} found, cannot proceed")
277
- print(f"Found motor with ID {motor_config.id} ✅.")
295
+ print(f"Found motor with ID {motor_config.id} [OK].")
278
296
 
279
297
  # Read return delay time
280
298
  return_delay = c.read_return_delay_time(motor_config.id)[0]
@@ -282,7 +300,7 @@ def check_configuration(
282
300
  raise RuntimeError(
283
301
  f"Return delay time is {return_delay}, expected {motor_config.return_delay_time}"
284
302
  )
285
- print(f"Return delay time is correct: {return_delay} ✅.")
303
+ print(f"Return delay time is correct: {return_delay} [OK].")
286
304
 
287
305
  # Read operating mode
288
306
  operating_mode = c.read_operating_mode(motor_config.id)[0]
@@ -290,7 +308,7 @@ def check_configuration(
290
308
  raise RuntimeError(
291
309
  f"Operating mode is {operating_mode}, expected {motor_config.operating_mode}"
292
310
  )
293
- print(f"Operating mode is correct: {operating_mode} ✅.")
311
+ print(f"Operating mode is correct: {operating_mode} [OK].")
294
312
 
295
313
  # Read angle limits
296
314
  angle_limit_min = c.read_raw_min_position_limit(motor_config.id)[0]
@@ -304,14 +322,14 @@ def check_configuration(
304
322
  f"Angle limit max is {angle_limit_max}, expected {motor_config.angle_limit_max}"
305
323
  )
306
324
  print(
307
- f"Angle limits are correct: [{motor_config.angle_limit_min}, {motor_config.angle_limit_max}] ✅."
325
+ f"Angle limits are correct: [{motor_config.angle_limit_min}, {motor_config.angle_limit_max}] [OK]."
308
326
  )
309
327
 
310
328
  # Read homing offset
311
329
  offset = c.read_homing_offset(motor_config.id)[0]
312
330
  if offset != motor_config.offset:
313
331
  raise RuntimeError(f"Homing offset is {offset}, expected {motor_config.offset}")
314
- print(f"Homing offset is correct: {offset} ✅.")
332
+ print(f"Homing offset is correct: {offset} [OK].")
315
333
 
316
334
  # Read shutdown
317
335
  shutdown = c.read_shutdown(motor_config.id)[0]
@@ -319,9 +337,9 @@ def check_configuration(
319
337
  raise RuntimeError(
320
338
  f"Shutdown is {shutdown}, expected {motor_config.shutdown_error}"
321
339
  )
322
- print(f"Shutdown error is correct: {shutdown} ✅.")
340
+ print(f"Shutdown error is correct: {shutdown} [OK].")
323
341
 
324
- print("Configuration is correct ✅!")
342
+ print("Configuration is correct [OK]!")
325
343
 
326
344
 
327
345
  def run(args: argparse.Namespace) -> None:
@@ -356,7 +374,7 @@ def run(args: argparse.Namespace) -> None:
356
374
  baudrate=config.serial.baudrate,
357
375
  )
358
376
  except RuntimeError as e:
359
- print(f" Configuration check failed for motor '{motor_name}': {e}")
377
+ print(f"[FAIL] Configuration check failed for motor '{motor_name}': {e}")
360
378
  return
361
379
 
362
380
  light_led_up(
@@ -19,7 +19,7 @@ def minimum_jerk(
19
19
  final_velocity: Optional[npt.NDArray[np.float64]] = None,
20
20
  final_acceleration: Optional[npt.NDArray[np.float64]] = None,
21
21
  ) -> InterpolationFunc:
22
- """Compute the mimimum jerk interpolation function from starting position to goal position."""
22
+ """Compute the minimum jerk interpolation function from starting position to goal position."""
23
23
  if starting_velocity is None:
24
24
  starting_velocity = np.zeros(starting_position.shape)
25
25
  if starting_acceleration is None: