Skip to content

Commit 8e88118

Browse files
committed
Add potential fix for YAM arm gripper not responding
1 parent dd4ac2f commit 8e88118

File tree

3 files changed

+204
-13
lines changed

3 files changed

+204
-13
lines changed

src/lerobot/robots/bi_yam_follower/README.md

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -119,6 +119,16 @@ lerobot-record \
119119
- `teleop.right_arm_port`: Server port for right leader arm (default: 5001)
120120
- `teleop.server_host`: Server hostname (default: "localhost")
121121

122+
## Gripper Control with Teaching Handles
123+
124+
The teaching handles don't have physical grippers, but they have an **encoder knob** that controls the follower gripper:
125+
126+
- **Turn the encoder knob**: Controls gripper position (0 = closed, 1 = open)
127+
- The encoder position is automatically read by the enhanced leader server
128+
- The follower grippers will mirror your encoder movements in real-time
129+
130+
The `setup_bi_yam_servers.py` script automatically uses an enhanced server for leader arms that exposes encoder data through the RPC interface.
131+
122132
## Architecture
123133

124134
### Data Flow

src/lerobot/scripts/setup_bi_yam_servers.py

Lines changed: 28 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -91,13 +91,23 @@ def find_i2rt_script():
9191
)
9292

9393

94-
def launch_server_process(can_channel, gripper, mode, server_port):
94+
def launch_server_process(can_channel, gripper, mode, server_port, use_encoder_server=False):
9595
"""Launch a single server process for a Yam arm."""
96-
try:
97-
script_path = find_i2rt_script()
98-
except RuntimeError as e:
99-
print(f"Error: {e}")
100-
sys.exit(1)
96+
if use_encoder_server:
97+
# Use enhanced server with encoder support for teaching handles
98+
script_path = os.path.join(
99+
os.path.dirname(os.path.abspath(__file__)), "yam_server_with_encoder.py"
100+
)
101+
if not os.path.exists(script_path):
102+
print(f"Error: Enhanced server script not found at {script_path}")
103+
sys.exit(1)
104+
else:
105+
# Use standard i2rt server for followers
106+
try:
107+
script_path = find_i2rt_script()
108+
except RuntimeError as e:
109+
print(f"Error: {e}")
110+
sys.exit(1)
101111

102112
cmd = [
103113
sys.executable,
@@ -112,7 +122,8 @@ def launch_server_process(can_channel, gripper, mode, server_port):
112122
str(server_port),
113123
]
114124

115-
print(f"Starting: {' '.join(cmd)}")
125+
server_type = "Enhanced (Encoder)" if use_encoder_server else "Standard"
126+
print(f"Starting [{server_type}]: {' '.join(cmd)}")
116127

117128
try:
118129
process = subprocess.Popen(cmd)
@@ -133,33 +144,37 @@ def main():
133144

134145
# Define the server processes to launch
135146
server_configs = [
136-
# Right follower arm
147+
# Right follower arm (standard server)
137148
{
138149
"can_channel": "can_follower_r",
139150
"gripper": "linear_4310",
140151
"mode": "follower",
141152
"server_port": 1234,
153+
"use_encoder_server": False,
142154
},
143-
# Left follower arm
155+
# Left follower arm (standard server)
144156
{
145157
"can_channel": "can_follower_l",
146158
"gripper": "linear_4310",
147159
"mode": "follower",
148160
"server_port": 1235,
161+
"use_encoder_server": False,
149162
},
150-
# Right leader arm (teaching handle)
163+
# Right leader arm (enhanced server with encoder support)
151164
{
152165
"can_channel": "can_leader_r",
153166
"gripper": "yam_teaching_handle",
154-
"mode": "follower", # Note: We use follower mode to expose as a read-only server
167+
"mode": "follower",
155168
"server_port": 5001,
169+
"use_encoder_server": True, # Use enhanced server for encoder data
156170
},
157-
# Left leader arm (teaching handle)
171+
# Left leader arm (enhanced server with encoder support)
158172
{
159173
"can_channel": "can_leader_l",
160174
"gripper": "yam_teaching_handle",
161-
"mode": "follower", # Note: We use follower mode to expose as a read-only server
175+
"mode": "follower",
162176
"server_port": 5002,
177+
"use_encoder_server": True, # Use enhanced server for encoder data
163178
},
164179
]
165180

Lines changed: 166 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,166 @@
1+
#!/usr/bin/env python3
2+
"""
3+
Enhanced Yam arm server that exposes encoder data for teaching handles.
4+
5+
This script wraps the i2rt robot to expose encoder button states through
6+
the portal RPC interface, allowing LeRobot to read gripper commands from
7+
the teaching handle.
8+
9+
Based on i2rt's minimum_gello.py but with encoder support.
10+
"""
11+
12+
import time
13+
from dataclasses import dataclass
14+
from typing import Dict, Literal
15+
16+
import numpy as np
17+
import portal
18+
import tyro
19+
20+
from i2rt.robots.get_robot import get_yam_robot
21+
from i2rt.robots.motor_chain_robot import MotorChainRobot
22+
from i2rt.robots.robot import Robot
23+
from i2rt.robots.utils import GripperType
24+
25+
DEFAULT_ROBOT_PORT = 11333
26+
27+
28+
class EnhancedYamRobot(Robot):
29+
"""
30+
Wrapper around MotorChainRobot that exposes encoder data.
31+
32+
For teaching handles, reads encoder position and button states
33+
to provide gripper control information.
34+
"""
35+
36+
def __init__(self, robot: MotorChainRobot, is_teaching_handle: bool = False):
37+
self._robot = robot
38+
self._motor_chain = robot.motor_chain
39+
self._is_teaching_handle = is_teaching_handle
40+
41+
def num_dofs(self) -> int:
42+
"""Get the number of joints in the robot."""
43+
return self._robot.num_dofs()
44+
45+
def get_joint_pos(self) -> np.ndarray:
46+
"""Get the current joint positions."""
47+
joint_pos = self._robot.get_joint_pos()
48+
49+
# For teaching handles, add gripper state from encoder
50+
if self._is_teaching_handle:
51+
try:
52+
encoder_states = self._motor_chain.get_same_bus_device_states()
53+
if encoder_states and len(encoder_states) > 0:
54+
# Encoder position mapped to gripper (0=closed, 1=open)
55+
gripper_pos = 1 - encoder_states[0].position
56+
joint_pos = np.concatenate([joint_pos, [gripper_pos]])
57+
except Exception as e:
58+
print(f"Warning: Could not read encoder state: {e}")
59+
# Fallback to default open position
60+
joint_pos = np.concatenate([joint_pos, [1.0]])
61+
62+
return joint_pos
63+
64+
def command_joint_pos(self, joint_pos: np.ndarray) -> None:
65+
"""Command the robot to a given joint position."""
66+
# For teaching handles, ignore gripper command if included
67+
if self._is_teaching_handle and len(joint_pos) > self._robot.num_dofs():
68+
joint_pos = joint_pos[: self._robot.num_dofs()]
69+
70+
self._robot.command_joint_pos(joint_pos)
71+
72+
def command_joint_state(self, joint_state: Dict[str, np.ndarray]) -> None:
73+
"""Command the robot to a given state."""
74+
self._robot.command_joint_state(joint_state)
75+
76+
def get_observations(self) -> Dict[str, np.ndarray]:
77+
"""
78+
Get the current observations of the robot.
79+
80+
For teaching handles, includes encoder data:
81+
- joint_pos: 6 joint positions
82+
- gripper_pos: Encoder position mapped to gripper (0=closed, 1=open)
83+
- io_inputs: Button states from encoder
84+
"""
85+
obs = self._robot.get_observations()
86+
87+
# For teaching handles, add encoder data
88+
if self._is_teaching_handle:
89+
try:
90+
encoder_states = self._motor_chain.get_same_bus_device_states()
91+
if encoder_states and len(encoder_states) > 0:
92+
# Add gripper position from encoder
93+
gripper_pos = 1 - encoder_states[0].position
94+
obs["gripper_pos"] = np.array([gripper_pos])
95+
96+
# Add button states
97+
obs["io_inputs"] = encoder_states[0].io_inputs
98+
except Exception as e:
99+
print(f"Warning: Could not read encoder state: {e}")
100+
# Provide defaults
101+
obs["gripper_pos"] = np.array([1.0])
102+
obs["io_inputs"] = np.array([0.0])
103+
104+
return obs
105+
106+
107+
class ServerRobot:
108+
"""A simple server for a robot."""
109+
110+
def __init__(self, robot: Robot, port: int):
111+
self._robot = robot
112+
self._server = portal.Server(port)
113+
print(f"Enhanced Robot Server Binding to {port}, Robot: {robot}")
114+
115+
self._server.bind("num_dofs", self._robot.num_dofs)
116+
self._server.bind("get_joint_pos", self._robot.get_joint_pos)
117+
self._server.bind("command_joint_pos", self._robot.command_joint_pos)
118+
self._server.bind("command_joint_state", self._robot.command_joint_state)
119+
self._server.bind("get_observations", self._robot.get_observations)
120+
121+
def serve(self) -> None:
122+
"""Serve the robot."""
123+
self._server.start()
124+
125+
126+
@dataclass
127+
class Args:
128+
gripper: Literal["crank_4310", "linear_3507", "linear_4310", "yam_teaching_handle", "no_gripper"] = (
129+
"yam_teaching_handle"
130+
)
131+
mode: Literal["follower", "leader"] = "follower"
132+
server_host: str = "localhost"
133+
server_port: int = DEFAULT_ROBOT_PORT
134+
can_channel: str = "can0"
135+
136+
137+
def main(args: Args) -> None:
138+
"""Main function to start the enhanced Yam server."""
139+
gripper_type = GripperType.from_string_name(args.gripper)
140+
is_teaching_handle = gripper_type == GripperType.YAM_TEACHING_HANDLE
141+
142+
# Get the base robot from i2rt
143+
base_robot = get_yam_robot(channel=args.can_channel, gripper_type=gripper_type)
144+
145+
# Wrap it with encoder support
146+
robot = EnhancedYamRobot(base_robot, is_teaching_handle=is_teaching_handle)
147+
148+
# Start the server
149+
server_robot = ServerRobot(robot, args.server_port)
150+
151+
print(f"\n{'='*60}")
152+
print(f"Enhanced Yam Server Started")
153+
print(f" CAN Channel: {args.can_channel}")
154+
print(f" Gripper Type: {args.gripper}")
155+
print(f" Teaching Handle: {is_teaching_handle}")
156+
print(f" Port: {args.server_port}")
157+
if is_teaching_handle:
158+
print(f" Encoder Support: ENABLED ✓")
159+
print(f"{'='*60}\n")
160+
161+
server_robot.serve()
162+
163+
164+
if __name__ == "__main__":
165+
main(tyro.cli(Args))
166+

0 commit comments

Comments
 (0)