ps5387 commited on
Commit
ea25c84
·
verified ·
1 Parent(s): 941bf23

Upload 3 files

Browse files
Files changed (3) hide show
  1. configs.py +614 -0
  2. model.safetensors +3 -0
  3. train_config.json +170 -0
configs.py ADDED
@@ -0,0 +1,614 @@
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
1
+ # Copyright 2024 The HuggingFace Inc. team. All rights reserved.
2
+ #
3
+ # Licensed under the Apache License, Version 2.0 (the "License");
4
+ # you may not use this file except in compliance with the License.
5
+ # You may obtain a copy of the License at
6
+ #
7
+ # http://www.apache.org/licenses/LICENSE-2.0
8
+ #
9
+ # Unless required by applicable law or agreed to in writing, software
10
+ # distributed under the License is distributed on an "AS IS" BASIS,
11
+ # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12
+ # See the License for the specific language governing permissions and
13
+ # limitations under the License.
14
+
15
+ import abc
16
+ from dataclasses import dataclass, field
17
+ from typing import Sequence
18
+
19
+ import draccus
20
+
21
+ from lerobot.common.robot_devices.cameras.configs import (
22
+ CameraConfig,
23
+ IntelRealSenseCameraConfig,
24
+ OpenCVCameraConfig,
25
+
26
+ )
27
+ from lerobot.common.robot_devices.motors.configs import (
28
+ DynamixelMotorsBusConfig,
29
+ FeetechMotorsBusConfig,
30
+ MotorsBusConfig,
31
+ )
32
+
33
+
34
+ @dataclass
35
+ class RobotConfig(draccus.ChoiceRegistry, abc.ABC):
36
+ @property
37
+ def type(self) -> str:
38
+ return self.get_choice_name(self.__class__)
39
+
40
+
41
+ # TODO(rcadene, aliberts): remove ManipulatorRobotConfig abstraction
42
+ @dataclass
43
+ class ManipulatorRobotConfig(RobotConfig):
44
+ leader_arms: dict[str, MotorsBusConfig] = field(default_factory=lambda: {})
45
+ follower_arms: dict[str, MotorsBusConfig] = field(default_factory=lambda: {})
46
+ cameras: dict[str, CameraConfig] = field(default_factory=lambda: {})
47
+
48
+ # Optionally limit the magnitude of the relative positional target vector for safety purposes.
49
+ # Set this to a positive scalar to have the same value for all motors, or a list that is the same length
50
+ # as the number of motors in your follower arms (assumes all follower arms have the same number of
51
+ # motors).
52
+ max_relative_target: list[float] | float | None = None
53
+
54
+ # Optionally set the leader arm in torque mode with the gripper motor set to this angle. This makes it
55
+ # possible to squeeze the gripper and have it spring back to an open position on its own. If None, the
56
+ # gripper is not put in torque mode.
57
+ gripper_open_degree: float | None = None
58
+
59
+ mock: bool = False
60
+
61
+ def __post_init__(self):
62
+ if self.mock:
63
+ for arm in self.leader_arms.values():
64
+ if not arm.mock:
65
+ arm.mock = True
66
+ for arm in self.follower_arms.values():
67
+ if not arm.mock:
68
+ arm.mock = True
69
+ for cam in self.cameras.values():
70
+ if not cam.mock:
71
+ cam.mock = True
72
+
73
+ if self.max_relative_target is not None and isinstance(self.max_relative_target, Sequence):
74
+ for name in self.follower_arms:
75
+ if len(self.follower_arms[name].motors) != len(self.max_relative_target):
76
+ raise ValueError(
77
+ f"len(max_relative_target)={len(self.max_relative_target)} but the follower arm with name {name} has "
78
+ f"{len(self.follower_arms[name].motors)} motors. Please make sure that the "
79
+ f"`max_relative_target` list has as many parameters as there are motors per arm. "
80
+ "Note: This feature does not yet work with robots where different follower arms have "
81
+ "different numbers of motors."
82
+ )
83
+
84
+
85
+ @RobotConfig.register_subclass("aloha")
86
+ @dataclass
87
+ class AlohaRobotConfig(ManipulatorRobotConfig):
88
+ # Specific to Aloha, LeRobot comes with default calibration files. Assuming the motors have been
89
+ # properly assembled, no manual calibration step is expected. If you need to run manual calibration,
90
+ # simply update this path to ".cache/calibration/aloha"
91
+ calibration_dir: str = ".cache/calibration/aloha_default"
92
+
93
+ # /!\ FOR SAFETY, READ THIS /!\
94
+ # `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
95
+ # Set this to a positive scalar to have the same value for all motors, or a list that is the same length as
96
+ # the number of motors in your follower arms.
97
+ # For Aloha, for every goal position request, motor rotations are capped at 5 degrees by default.
98
+ # When you feel more confident with teleoperation or running the policy, you can extend
99
+ # this safety limit and even removing it by setting it to `null`.
100
+ # Also, everything is expected to work safely out-of-the-box, but we highly advise to
101
+ # first try to teleoperate the grippers only (by commenting out the rest of the motors in this yaml),
102
+ # then to gradually add more motors (by uncommenting), until you can teleoperate both arms fully
103
+ max_relative_target: int | None = 5
104
+
105
+ leader_arms: dict[str, MotorsBusConfig] = field(
106
+ default_factory=lambda: {
107
+ "left": DynamixelMotorsBusConfig(
108
+ # window_x
109
+ port="/dev/ttyDXL_leader_left",
110
+ motors={
111
+ # name: (index, model)
112
+ "waist": [1, "xm430-w350"],
113
+ "shoulder": [2, "xm430-w350"],
114
+ "shoulder_shadow": [3, "xm430-w350"],
115
+ "elbow": [4, "xm430-w350"],
116
+ "elbow_shadow": [5, "xm430-w350"],
117
+ "forearm_roll": [6, "xm430-w350"],
118
+ "wrist_angle": [7, "xm430-w350"],
119
+ "wrist_rotate": [8, "xl430-w250"],
120
+ "gripper": [9, "xc430-w150"],
121
+ },
122
+ ),
123
+ "right": DynamixelMotorsBusConfig(
124
+ # window_x
125
+ port="/dev/ttyDXL_leader_right",
126
+ motors={
127
+ # name: (index, model)
128
+ "waist": [1, "xm430-w350"],
129
+ "shoulder": [2, "xm430-w350"],
130
+ "shoulder_shadow": [3, "xm430-w350"],
131
+ "elbow": [4, "xm430-w350"],
132
+ "elbow_shadow": [5, "xm430-w350"],
133
+ "forearm_roll": [6, "xm430-w350"],
134
+ "wrist_angle": [7, "xm430-w350"],
135
+ "wrist_rotate": [8, "xl430-w250"],
136
+ "gripper": [9, "xc430-w150"],
137
+ },
138
+ ),
139
+ }
140
+ )
141
+
142
+ follower_arms: dict[str, MotorsBusConfig] = field(
143
+ default_factory=lambda: {
144
+ "left": DynamixelMotorsBusConfig(
145
+ port="/dev/ttyDXL_follower_left",
146
+ motors={
147
+ # name: (index, model)
148
+ "waist": [1, "xm540-w270"],
149
+ "shoulder": [2, "xm540-w270"],
150
+ "shoulder_shadow": [3, "xm540-w270"],
151
+ "elbow": [4, "xm540-w270"],
152
+ "elbow_shadow": [5, "xm540-w270"],
153
+ "forearm_roll": [6, "xm540-w270"],
154
+ "wrist_angle": [7, "xm540-w270"],
155
+ "wrist_rotate": [8, "xm430-w350"],
156
+ "gripper": [9, "xm430-w350"],
157
+ },
158
+ ),
159
+ "right": DynamixelMotorsBusConfig(
160
+ port="/dev/ttyDXL_follower_right",
161
+ motors={
162
+ # name: (index, model)
163
+ "waist": [1, "xm540-w270"],
164
+ "shoulder": [2, "xm540-w270"],
165
+ "shoulder_shadow": [3, "xm540-w270"],
166
+ "elbow": [4, "xm540-w270"],
167
+ "elbow_shadow": [5, "xm540-w270"],
168
+ "forearm_roll": [6, "xm540-w270"],
169
+ "wrist_angle": [7, "xm540-w270"],
170
+ "wrist_rotate": [8, "xm430-w350"],
171
+ "gripper": [9, "xm430-w350"],
172
+ },
173
+ ),
174
+ }
175
+ )
176
+
177
+ # Troubleshooting: If one of your IntelRealSense cameras freeze during
178
+ # data recording due to bandwidth limit, you might need to plug the camera
179
+ # on another USB hub or PCIe card.
180
+ cameras: dict[str, CameraConfig] = field(
181
+ default_factory=lambda: {
182
+ "cam_high": IntelRealSenseCameraConfig(
183
+ serial_number=128422271347,
184
+ fps=30,
185
+ width=640,
186
+ height=480,
187
+ ),
188
+ "cam_low": IntelRealSenseCameraConfig(
189
+ serial_number=130322270656,
190
+ fps=30,
191
+ width=640,
192
+ height=480,
193
+ ),
194
+ "cam_left_wrist": IntelRealSenseCameraConfig(
195
+ serial_number=218622272670,
196
+ fps=30,
197
+ width=640,
198
+ height=480,
199
+ ),
200
+ "cam_right_wrist": IntelRealSenseCameraConfig(
201
+ serial_number=130322272300,
202
+ fps=30,
203
+ width=640,
204
+ height=480,
205
+ ),
206
+ }
207
+ )
208
+
209
+ mock: bool = False
210
+
211
+
212
+ @RobotConfig.register_subclass("koch")
213
+ @dataclass
214
+ class KochRobotConfig(ManipulatorRobotConfig):
215
+ calibration_dir: str = ".cache/calibration/koch"
216
+ # `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
217
+ # Set this to a positive scalar to have the same value for all motors, or a list that is the same length as
218
+ # the number of motors in your follower arms.
219
+ max_relative_target: int | None = None
220
+
221
+ leader_arms: dict[str, MotorsBusConfig] = field(
222
+ default_factory=lambda: {
223
+ "main": DynamixelMotorsBusConfig(
224
+ port="/dev/tty.usbmodem585A0085511",
225
+ motors={
226
+ # name: (index, model)
227
+ "shoulder_pan": [1, "xl330-m077"],
228
+ "shoulder_lift": [2, "xl330-m077"],
229
+ "elbow_flex": [3, "xl330-m077"],
230
+ "wrist_flex": [4, "xl330-m077"],
231
+ "wrist_roll": [5, "xl330-m077"],
232
+ "gripper": [6, "xl330-m077"],
233
+ },
234
+ ),
235
+ }
236
+ )
237
+
238
+ follower_arms: dict[str, MotorsBusConfig] = field(
239
+ default_factory=lambda: {
240
+ "main": DynamixelMotorsBusConfig(
241
+ port="/dev/tty.usbmodem585A0076891",
242
+ motors={
243
+ # name: (index, model)
244
+ "shoulder_pan": [1, "xl430-w250"],
245
+ "shoulder_lift": [2, "xl430-w250"],
246
+ "elbow_flex": [3, "xl330-m288"],
247
+ "wrist_flex": [4, "xl330-m288"],
248
+ "wrist_roll": [5, "xl330-m288"],
249
+ "gripper": [6, "xl330-m288"],
250
+ },
251
+ ),
252
+ }
253
+ )
254
+
255
+ cameras: dict[str, CameraConfig] = field(
256
+ default_factory=lambda: {
257
+ "laptop": OpenCVCameraConfig(
258
+ camera_index=2,
259
+ fps=30,
260
+ width=640,
261
+ height=480,
262
+ ),
263
+ "phone": OpenCVCameraConfig(
264
+ camera_index=4,
265
+ fps=30,
266
+ width=640,
267
+ height=480,
268
+ ),
269
+ }
270
+ )
271
+
272
+ # ~ Koch specific settings ~
273
+ # Sets the leader arm in torque mode with the gripper motor set to this angle. This makes it possible
274
+ # to squeeze the gripper and have it spring back to an open position on its own.
275
+ gripper_open_degree: float = 35.156
276
+
277
+ mock: bool = False
278
+
279
+
280
+ @RobotConfig.register_subclass("koch_bimanual")
281
+ @dataclass
282
+ class KochBimanualRobotConfig(ManipulatorRobotConfig):
283
+ calibration_dir: str = ".cache/calibration/koch_bimanual"
284
+ # `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
285
+ # Set this to a positive scalar to have the same value for all motors, or a list that is the same length as
286
+ # the number of motors in your follower arms.
287
+ max_relative_target: int | None = None
288
+
289
+ leader_arms: dict[str, MotorsBusConfig] = field(
290
+ default_factory=lambda: {
291
+ "left": DynamixelMotorsBusConfig(
292
+ port="/dev/tty.usbmodem585A0085511",
293
+ motors={
294
+ # name: (index, model)
295
+ "shoulder_pan": [1, "xl330-m077"],
296
+ "shoulder_lift": [2, "xl330-m077"],
297
+ "elbow_flex": [3, "xl330-m077"],
298
+ "wrist_flex": [4, "xl330-m077"],
299
+ "wrist_roll": [5, "xl330-m077"],
300
+ "gripper": [6, "xl330-m077"],
301
+ },
302
+ ),
303
+ "right": DynamixelMotorsBusConfig(
304
+ port="/dev/tty.usbmodem575E0031751",
305
+ motors={
306
+ # name: (index, model)
307
+ "shoulder_pan": [1, "xl330-m077"],
308
+ "shoulder_lift": [2, "xl330-m077"],
309
+ "elbow_flex": [3, "xl330-m077"],
310
+ "wrist_flex": [4, "xl330-m077"],
311
+ "wrist_roll": [5, "xl330-m077"],
312
+ "gripper": [6, "xl330-m077"],
313
+ },
314
+ ),
315
+ }
316
+ )
317
+
318
+ follower_arms: dict[str, MotorsBusConfig] = field(
319
+ default_factory=lambda: {
320
+ "left": DynamixelMotorsBusConfig(
321
+ port="/dev/tty.usbmodem585A0076891",
322
+ motors={
323
+ # name: (index, model)
324
+ "shoulder_pan": [1, "xl430-w250"],
325
+ "shoulder_lift": [2, "xl430-w250"],
326
+ "elbow_flex": [3, "xl330-m288"],
327
+ "wrist_flex": [4, "xl330-m288"],
328
+ "wrist_roll": [5, "xl330-m288"],
329
+ "gripper": [6, "xl330-m288"],
330
+ },
331
+ ),
332
+ "right": DynamixelMotorsBusConfig(
333
+ port="/dev/tty.usbmodem575E0032081",
334
+ motors={
335
+ # name: (index, model)
336
+ "shoulder_pan": [1, "xl430-w250"],
337
+ "shoulder_lift": [2, "xl430-w250"],
338
+ "elbow_flex": [3, "xl330-m288"],
339
+ "wrist_flex": [4, "xl330-m288"],
340
+ "wrist_roll": [5, "xl330-m288"],
341
+ "gripper": [6, "xl330-m288"],
342
+ },
343
+ ),
344
+ }
345
+ )
346
+
347
+ cameras: dict[str, CameraConfig] = field(
348
+ default_factory=lambda: {
349
+ "laptop": OpenCVCameraConfig(
350
+ camera_index=0,
351
+ fps=30,
352
+ width=640,
353
+ height=480,
354
+ ),
355
+ "phone": OpenCVCameraConfig(
356
+ camera_index=1,
357
+ fps=30,
358
+ width=640,
359
+ height=480,
360
+ ),
361
+ }
362
+ )
363
+
364
+ # ~ Koch specific settings ~
365
+ # Sets the leader arm in torque mode with the gripper motor set to this angle. This makes it possible
366
+ # to squeeze the gripper and have it spring back to an open position on its own.
367
+ gripper_open_degree: float = 35.156
368
+
369
+ mock: bool = False
370
+
371
+
372
+ @RobotConfig.register_subclass("moss")
373
+ @dataclass
374
+ class MossRobotConfig(ManipulatorRobotConfig):
375
+ calibration_dir: str = ".cache/calibration/moss"
376
+ # `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
377
+ # Set this to a positive scalar to have the same value for all motors, or a list that is the same length as
378
+ # the number of motors in your follower arms.
379
+ max_relative_target: int | None = None
380
+
381
+ leader_arms: dict[str, MotorsBusConfig] = field(
382
+ default_factory=lambda: {
383
+ "main": FeetechMotorsBusConfig(
384
+ port="/dev/tty.usbmodem58760431091",
385
+ motors={
386
+ # name: (index, model)
387
+ "shoulder_pan": [1, "sts3215"],
388
+ "shoulder_lift": [2, "sts3215"],
389
+ "elbow_flex": [3, "sts3215"],
390
+ "wrist_flex": [4, "sts3215"],
391
+ "wrist_roll": [5, "sts3215"],
392
+ "gripper": [6, "sts3215"],
393
+ },
394
+ ),
395
+ }
396
+ )
397
+
398
+ follower_arms: dict[str, MotorsBusConfig] = field(
399
+ default_factory=lambda: {
400
+ "main": FeetechMotorsBusConfig(
401
+ port="/dev/tty.usbmodem585A0076891",
402
+ motors={
403
+ # name: (index, model)
404
+ "shoulder_pan": [1, "sts3215"],
405
+ "shoulder_lift": [2, "sts3215"],
406
+ "elbow_flex": [3, "sts3215"],
407
+ "wrist_flex": [4, "sts3215"],
408
+ "wrist_roll": [5, "sts3215"],
409
+ "gripper": [6, "sts3215"],
410
+ },
411
+ ),
412
+ }
413
+ )
414
+
415
+ cameras: dict[str, CameraConfig] = field(
416
+ default_factory=lambda: {
417
+ "laptop": OpenCVCameraConfig(
418
+ camera_index=0,
419
+ fps=30,
420
+ width=640,
421
+ height=480,
422
+ ),
423
+ "phone": OpenCVCameraConfig(
424
+ camera_index=1,
425
+ fps=30,
426
+ width=640,
427
+ height=480,
428
+ ),
429
+ }
430
+ )
431
+
432
+ mock: bool = False
433
+
434
+
435
+ @RobotConfig.register_subclass("so100")
436
+ @dataclass
437
+ class So100RobotConfig(ManipulatorRobotConfig):
438
+ calibration_dir: str = ".cache/calibration/so100"
439
+ # `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
440
+ # Set this to a positive scalar to have the same value for all motors, or a list that is the same length as
441
+ # the number of motors in your follower arms.
442
+ max_relative_target: int | None = None
443
+
444
+ leader_arms: dict[str, MotorsBusConfig] = field(
445
+ default_factory=lambda: {
446
+ "main": FeetechMotorsBusConfig(
447
+ port="/dev/ttyACM1",
448
+ motors={
449
+ # name: (index, model)
450
+ "shoulder_pan": [1, "sts3215"],
451
+ "shoulder_lift": [2, "sts3215"],
452
+ "elbow_flex": [3, "sts3215"],
453
+ "wrist_flex": [4, "sts3215"],
454
+ "wrist_roll": [5, "sts3215"],
455
+ "gripper": [6, "sts3215"],
456
+ },
457
+ ),
458
+ }
459
+ )
460
+
461
+ follower_arms: dict[str, MotorsBusConfig] = field(
462
+ default_factory=lambda: {
463
+ "main": FeetechMotorsBusConfig(
464
+ port="/dev/ttyACM0",
465
+ motors={
466
+ # name: (index, model)
467
+ "shoulder_pan": [1, "sts3215"],
468
+ "shoulder_lift": [2, "sts3215"],
469
+ "elbow_flex": [3, "sts3215"],
470
+ "wrist_flex": [4, "sts3215"],
471
+ "wrist_roll": [5, "sts3215"],
472
+ "gripper": [6, "sts3215"],
473
+ },
474
+ ),
475
+ }
476
+ )
477
+
478
+ cameras: dict[str, CameraConfig] = field(
479
+ default_factory=lambda: {
480
+ "laptop": OpenCVCameraConfig(
481
+ camera_index=4,
482
+ fps=30,
483
+ width=640,
484
+ height=480,
485
+ ),
486
+ "phone": OpenCVCameraConfig(
487
+ camera_index=2,
488
+ fps=30,
489
+ width=640,
490
+ height=480,
491
+ ),
492
+ }
493
+ )
494
+
495
+ mock: bool = False
496
+
497
+
498
+ @RobotConfig.register_subclass("stretch")
499
+ @dataclass
500
+ class StretchRobotConfig(RobotConfig):
501
+ # `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
502
+ # Set this to a positive scalar to have the same value for all motors, or a list that is the same length as
503
+ # the number of motors in your follower arms.
504
+ max_relative_target: int | None = None
505
+
506
+ cameras: dict[str, CameraConfig] = field(
507
+ default_factory=lambda: {
508
+ "navigation": OpenCVCameraConfig(
509
+ camera_index="/dev/hello-nav-head-camera",
510
+ fps=10,
511
+ width=1280,
512
+ height=720,
513
+ rotation=-90,
514
+ ),
515
+ "head": IntelRealSenseCameraConfig(
516
+ name="Intel RealSense D435I",
517
+ fps=30,
518
+ width=640,
519
+ height=480,
520
+ rotation=90,
521
+ ),
522
+ "wrist": IntelRealSenseCameraConfig(
523
+ name="Intel RealSense D405",
524
+ fps=30,
525
+ width=640,
526
+ height=480,
527
+ ),
528
+ }
529
+ )
530
+
531
+ mock: bool = False
532
+
533
+
534
+ @RobotConfig.register_subclass("lekiwi")
535
+ @dataclass
536
+ class LeKiwiRobotConfig(RobotConfig):
537
+ # `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
538
+ # Set this to a positive scalar to have the same value for all motors, or a list that is the same length as
539
+ # the number of motors in your follower arms.
540
+ max_relative_target: int | None = None
541
+
542
+ # Network Configuration
543
+ ip: str = "192.168.0.193"
544
+ port: int = 5555
545
+ video_port: int = 5556
546
+
547
+ cameras: dict[str, CameraConfig] = field(
548
+ default_factory=lambda: {
549
+ "front": OpenCVCameraConfig(
550
+ camera_index="/dev/video0", fps=30, width=640, height=480, rotation=90
551
+ ),
552
+ "wrist": OpenCVCameraConfig(
553
+ camera_index="/dev/video2", fps=30, width=640, height=480, rotation=180
554
+ ),
555
+ }
556
+ )
557
+
558
+ calibration_dir: str = ".cache/calibration/lekiwi"
559
+
560
+ leader_arms: dict[str, MotorsBusConfig] = field(
561
+ default_factory=lambda: {
562
+ "main": FeetechMotorsBusConfig(
563
+ port="/dev/tty.usbmodem585A0077581",
564
+ motors={
565
+ # name: (index, model)
566
+ "shoulder_pan": [1, "sts3215"],
567
+ "shoulder_lift": [2, "sts3215"],
568
+ "elbow_flex": [3, "sts3215"],
569
+ "wrist_flex": [4, "sts3215"],
570
+ "wrist_roll": [5, "sts3215"],
571
+ "gripper": [6, "sts3215"],
572
+ },
573
+ ),
574
+ }
575
+ )
576
+
577
+ follower_arms: dict[str, MotorsBusConfig] = field(
578
+ default_factory=lambda: {
579
+ "main": FeetechMotorsBusConfig(
580
+ port="/dev/ttyACM0",
581
+ motors={
582
+ # name: (index, model)
583
+ "shoulder_pan": [1, "sts3215"],
584
+ "shoulder_lift": [2, "sts3215"],
585
+ "elbow_flex": [3, "sts3215"],
586
+ "wrist_flex": [4, "sts3215"],
587
+ "wrist_roll": [5, "sts3215"],
588
+ "gripper": [6, "sts3215"],
589
+ "left_wheel": (7, "sts3215"),
590
+ "back_wheel": (8, "sts3215"),
591
+ "right_wheel": (9, "sts3215"),
592
+ },
593
+ ),
594
+ }
595
+ )
596
+
597
+ teleop_keys: dict[str, str] = field(
598
+ default_factory=lambda: {
599
+ # Movement
600
+ "forward": "w",
601
+ "backward": "s",
602
+ "left": "a",
603
+ "right": "d",
604
+ "rotate_left": "z",
605
+ "rotate_right": "x",
606
+ # Speed control
607
+ "speed_up": "r",
608
+ "speed_down": "f",
609
+ # quit teleop
610
+ "quit": "q",
611
+ }
612
+ )
613
+
614
+ mock: bool = False
model.safetensors ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:c245d22f44f74744699e27b1e74e1138876dfe8d353ec3c44b7f7ac5a73e0561
3
+ size 206701072
train_config.json ADDED
@@ -0,0 +1,170 @@
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
1
+ {
2
+ "dataset": {
3
+ "repo_id": "ps5387/shake_lerobot3",
4
+ "root": null,
5
+ "episodes": null,
6
+ "image_transforms": {
7
+ "enable": false,
8
+ "max_num_transforms": 3,
9
+ "random_order": false,
10
+ "tfs": {
11
+ "brightness": {
12
+ "weight": 1.0,
13
+ "type": "ColorJitter",
14
+ "kwargs": {
15
+ "brightness": [
16
+ 0.8,
17
+ 1.2
18
+ ]
19
+ }
20
+ },
21
+ "contrast": {
22
+ "weight": 1.0,
23
+ "type": "ColorJitter",
24
+ "kwargs": {
25
+ "contrast": [
26
+ 0.8,
27
+ 1.2
28
+ ]
29
+ }
30
+ },
31
+ "saturation": {
32
+ "weight": 1.0,
33
+ "type": "ColorJitter",
34
+ "kwargs": {
35
+ "saturation": [
36
+ 0.5,
37
+ 1.5
38
+ ]
39
+ }
40
+ },
41
+ "hue": {
42
+ "weight": 1.0,
43
+ "type": "ColorJitter",
44
+ "kwargs": {
45
+ "hue": [
46
+ -0.05,
47
+ 0.05
48
+ ]
49
+ }
50
+ },
51
+ "sharpness": {
52
+ "weight": 1.0,
53
+ "type": "SharpnessJitter",
54
+ "kwargs": {
55
+ "sharpness": [
56
+ 0.5,
57
+ 1.5
58
+ ]
59
+ }
60
+ }
61
+ }
62
+ },
63
+ "revision": null,
64
+ "use_imagenet_stats": true,
65
+ "video_backend": "torchcodec"
66
+ },
67
+ "env": null,
68
+ "policy": {
69
+ "type": "act",
70
+ "n_obs_steps": 1,
71
+ "normalization_mapping": {
72
+ "VISUAL": "MEAN_STD",
73
+ "STATE": "MEAN_STD",
74
+ "ACTION": "MEAN_STD"
75
+ },
76
+ "input_features": {
77
+ "observation.state": {
78
+ "type": "STATE",
79
+ "shape": [
80
+ 6
81
+ ]
82
+ },
83
+ "observation.images.laptop": {
84
+ "type": "VISUAL",
85
+ "shape": [
86
+ 3,
87
+ 480,
88
+ 640
89
+ ]
90
+ },
91
+ "observation.images.phone": {
92
+ "type": "VISUAL",
93
+ "shape": [
94
+ 3,
95
+ 480,
96
+ 640
97
+ ]
98
+ }
99
+ },
100
+ "output_features": {
101
+ "action": {
102
+ "type": "ACTION",
103
+ "shape": [
104
+ 6
105
+ ]
106
+ }
107
+ },
108
+ "device": "cuda",
109
+ "use_amp": false,
110
+ "chunk_size": 100,
111
+ "n_action_steps": 100,
112
+ "vision_backbone": "resnet18",
113
+ "pretrained_backbone_weights": "ResNet18_Weights.IMAGENET1K_V1",
114
+ "replace_final_stride_with_dilation": false,
115
+ "pre_norm": false,
116
+ "dim_model": 512,
117
+ "n_heads": 8,
118
+ "dim_feedforward": 3200,
119
+ "feedforward_activation": "relu",
120
+ "n_encoder_layers": 4,
121
+ "n_decoder_layers": 1,
122
+ "use_vae": true,
123
+ "latent_dim": 32,
124
+ "n_vae_encoder_layers": 4,
125
+ "temporal_ensemble_coeff": null,
126
+ "dropout": 0.1,
127
+ "kl_weight": 10.0,
128
+ "optimizer_lr": 1e-05,
129
+ "optimizer_weight_decay": 0.0001,
130
+ "optimizer_lr_backbone": 1e-05
131
+ },
132
+ "output_dir": "/scratch/ps5387/HANDSHAKE_outputs/train/SHAKE3",
133
+ "job_name": "act_so100_HS",
134
+ "resume": false,
135
+ "seed": 1000,
136
+ "num_workers": 4,
137
+ "batch_size": 94,
138
+ "steps": 100000,
139
+ "eval_freq": 20000,
140
+ "log_freq": 200,
141
+ "save_checkpoint": true,
142
+ "save_freq": 10000,
143
+ "use_policy_training_preset": true,
144
+ "optimizer": {
145
+ "type": "adamw",
146
+ "lr": 1e-05,
147
+ "weight_decay": 0.0001,
148
+ "grad_clip_norm": 10.0,
149
+ "betas": [
150
+ 0.9,
151
+ 0.999
152
+ ],
153
+ "eps": 1e-08
154
+ },
155
+ "scheduler": null,
156
+ "eval": {
157
+ "n_episodes": 50,
158
+ "batch_size": 50,
159
+ "use_async_envs": false
160
+ },
161
+ "wandb": {
162
+ "enable": false,
163
+ "disable_artifact": false,
164
+ "project": "lerobot",
165
+ "entity": null,
166
+ "notes": null,
167
+ "run_id": null,
168
+ "mode": null
169
+ }
170
+ }