You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Copy file name to clipboardExpand all lines: README.md
+63-5Lines changed: 63 additions & 5 deletions
Display the source diff
Display the rich diff
Original file line number
Diff line number
Diff line change
@@ -11,10 +11,46 @@ A Python client library for interacting with [I2RT](https://i2rt.com/) products,
11
11
- Visualization and gravity compensation using MuJoCo physics engine
12
12
- Gripper force control mode and auto calibration
13
13
14
+
## Examples
15
+
16
+
We are continuously expanding our collection of examples with detailed documentation under [`examples/`](./examples). These examples are designed to help you get started quickly and demonstrate common use cases.
17
+
18
+
## Available Examples
19
+
20
+
### [Bimanual Lead Follower](./examples/bimanual_lead_follower/README.md)
21
+
Demonstrates coordinated control of two robotic arms in a leader-follower configuration.
|`crank_4310`| Zero-linkage crank gripper, optimized for minimizing gripper width. |
62
103
|`linear_3507`| Linear gripper with smaller DM3507 motor. Lightweight, but requires calibration or starting with the gripper in the closed configuration. |
63
104
|`linear_4310`| Linear gripper with the standard DM4310 motor (not shown on photo above). Slightly heavier but can provide a bit more gripping force. |
64
-
|`yam_teaching_handle`| Used for the leader arm setup. Includes a trigger to control the gripper and two customizable buttons that can be mapped to different functions. |
105
+
|`yam_teaching_handle`| Used for the leader arm setup. Includes a trigger to control the gripper and two customizable buttons that can be mapped to different functions. For more information related to the teaching handle, please see [yam_handle_readme.md](doc/yam_handle_readme.md)|
65
106
66
107
The linear gripper requires an additional calibration step because its motor must rotate more than 2π radians to complete the full stroke.
67
108
@@ -97,9 +138,9 @@ To launch the follower robot run.
In this mode, the current joint positions (`qpos`) are used as the PD target, keeping the arm stable in its initial state.
189
231
232
+
One important way to reduce the risk of the arm going out of control is to avoid entering zero-gravity mode.
233
+
234
+
By default, the arm initializes in zero-gravity mode. As mentioned earlier, if the arm does not have a timeout but the gravity compensation loop fails, the motor controller will continue applying a constant torque. This can lead to unexpected and potentially unsafe behavior.
235
+
236
+
To prevent this, you should always set a PD target. With a PD target, the motor controller ensures the arm reaches a stable state rather than drifting under uncontrolled torque.
237
+
238
+
You can disable the default zero-gravity initialization like this:
0 commit comments