Compare commits

...

2 Commits

Author SHA1 Message Date
b04e6e0c7b dual arm fisrt complete with master arm
Some checks failed
Secret Leaks / trufflehog (push) Failing after 1m30s
2025-07-03 19:44:10 +08:00
96804bc86c still mant bugs 2025-07-02 11:42:03 +08:00
9 changed files with 1206 additions and 21 deletions

View File

@@ -47,4 +47,16 @@ class RealmanMotorsBusConfig(MotorsBusConfig):
ip: str
port: int
motors: dict[str, tuple[int, str]]
init_joint: dict[str, list]
init_joint: dict[str, list]
@MotorsBusConfig.register_subclass("realman_dual")
@dataclass
class RealmanDualMotorsBusConfig(MotorsBusConfig):
left_ip: str
right_ip: str
left_port: int
right_port: int
motors: dict[str, tuple[int, str]]
init_joint: dict[str, list]
axis: dict[str, int]

View File

@@ -0,0 +1,354 @@
import time
import threading
from typing import Dict
from dataclasses import dataclass
from contextlib import contextmanager
from lerobot.common.robot_devices.motors.configs import RealmanDualMotorsBusConfig
from Robotic_Arm.rm_robot_interface import *
def compare_joint_difference(master_joints, follow_joints, threshold=30.0):
"""
比较主臂和从臂关节数据的差异
Args:
master_joints (list): 主臂关节数据 [joint1, joint2, ..., joint6]
follow_joints (list): 从臂关节数据 [joint1, joint2, ..., joint6]
threshold (float): 差异阈值默认5度
Returns:
bool: True表示差异在阈值内False表示超过阈值
"""
# 检查数据长度
if len(master_joints) != len(follow_joints):
return False
# 计算每个关节的绝对差异
for i in range(len(master_joints)):
diff = abs(master_joints[i] - follow_joints[i])
if diff > threshold:
return False
return True
@dataclass
class ArmState:
"""机械臂状态数据类"""
joint_positions: list
gripper_position: int
pose: list
class RealmanDualMotorsBus:
"""
对Realman SDK的二次封装
"""
def __init__(self, config: RealmanDualMotorsBusConfig):
self.config = config
self._initialize_arms()
self._initialize_parameters()
self._initialize_positions()
self._initialize_threading()
def _initialize_arms(self):
"""初始化机械臂连接"""
self.left_rmarm = RoboticArm(rm_thread_mode_e.RM_TRIPLE_MODE_E)
self.right_rmarm = RoboticArm(rm_thread_mode_e.RM_TRIPLE_MODE_E)
self.handle_left = self.left_rmarm.rm_create_robot_arm(
self.config.left_ip, self.config.left_port
)
self.handle_right = self.right_rmarm.rm_create_robot_arm(
self.config.right_ip, self.config.right_port
)
def _initialize_parameters(self):
"""初始化参数"""
self.motors = self.config.motors
self.axis = self.config.axis
self.joint_count = sum(self.axis.values())
self.left_offset = self.axis['left_joint']
def _initialize_positions(self):
"""初始化位置"""
self.init_joint_position = self.config.init_joint['joint']
self.safe_disable_position = self.config.init_joint['joint']
# 移动到初始位置
self._move_to_initial_position()
# 获取初始姿态
time.sleep(3)
self.init_pose = self._get_initial_pose()
def _initialize_threading(self):
"""初始化线程控制"""
self.left_slow_busy = False
self.right_slow_busy = False
self._thread_lock = threading.Lock()
# 添加读取相关的线程控制
self._state_cache = {}
self._cache_lock = threading.Lock()
self._keep_reading = True
# 启动后台读取线程
self._start_background_readers()
def _start_background_readers(self):
"""启动后台读取线程"""
# 左臂读取线程
threading.Thread(
target=self._left_read_task,
daemon=True,
name="left_arm_reader"
).start()
# 右臂读取线程
threading.Thread(
target=self._right_read_task,
daemon=True,
name="right_arm_reader"
).start()
@property
def motor_names(self) -> list[str]:
return list(self.motors.keys())
@property
def motor_models(self) -> list[str]:
return [model for _, model in self.motors.values()]
@property
def motor_indices(self) -> list[int]:
return [idx for idx, _ in self.motors.values()]
@contextmanager
def _timeout_context(self, timeout: float = 5.0):
"""超时上下文管理器"""
start_time = time.time()
try:
yield lambda: time.time() - start_time < timeout
except Exception as e:
raise TimeoutError(f"操作超时: {e}")
def _left_read_task(self):
"""左臂后台读取任务 - 模仿_left_slow_task的风格"""
while self._keep_reading:
try:
left_state = self._read_arm_state(self.left_rmarm, "left")
with self._cache_lock:
self._state_cache.update(left_state)
except Exception as e:
print(f"左臂读取失败: {e}")
time.sleep(0.005)
def _right_read_task(self):
"""右臂后台读取任务 - 模仿_right_slow_task的风格"""
while self._keep_reading:
try:
right_state = self._read_arm_state(self.right_rmarm, "right")
with self._cache_lock:
self._state_cache.update(right_state)
except Exception as e:
print(f"右臂读取失败: {e}")
time.sleep(0.005)
def _read_arm_state(self, arm: RoboticArm, prefix: str) -> dict:
"""读取单臂状态 - 保持原有逻辑"""
joint_msg = arm.rm_get_current_arm_state()[1]
gripper_msg = arm.rm_get_gripper_state()[1]
joint_state = joint_msg['joint']
gripper_state = gripper_msg['actpos']
state_dict = {}
for i in range(6):
state_dict[f"{prefix}_joint_{i+1}"] = joint_state[i] / 180
state_dict[f"{prefix}_gripper"] = (gripper_state - 500) / 500
return state_dict
def _move_to_initial_position(self):
"""移动到初始位置"""
left_joints = self.init_joint_position[:self.left_offset]
right_joints = self.init_joint_position[self.left_offset+1:-1]
self.left_rmarm.rm_movej(left_joints, 5, 0, 0, 1)
self.right_rmarm.rm_movej(right_joints, 5, 0, 0, 1)
def _get_initial_pose(self) -> list:
"""获取初始姿态"""
left_ret = self.left_rmarm.rm_get_current_arm_state()
right_ret = self.right_rmarm.rm_get_current_arm_state()
return left_ret[1]['pose'] + right_ret[1]['pose']
def _validate_joint_count(self, joints: list, expected_count: int):
"""验证关节数量"""
if len(joints) != expected_count:
raise ValueError(f"关节数量不匹配: 期望 {expected_count}, 实际 {len(joints)}")
def _extract_joint_state(self, state: dict, arm_prefix: str) -> list:
"""提取关节状态"""
return [state[v] * 180 for v in state if f"{arm_prefix}" in v]
def _execute_slow_movement(self, arm: str, joint_data: list):
"""执行慢速运动"""
busy_flag = f"{arm}_slow_busy"
if not getattr(self, busy_flag):
setattr(self, busy_flag, True)
target_method = getattr(self, f"_{arm}_slow_task")
threading.Thread(
target=target_method,
args=(joint_data.copy(),),
daemon=True
).start()
def _left_slow_task(self, joint_data: list):
"""左臂慢速任务"""
try:
self.write_left_joint_slow(joint_data)
finally:
self.left_slow_busy = False
def _right_slow_task(self, joint_data: list):
"""右臂慢速任务"""
try:
self.write_right_joint_slow(joint_data)
finally:
self.right_slow_busy = False
def _execute_arm_action(self, arm: str, action: dict, master_joint: list, follow_joint: list):
"""执行单臂动作"""
controller_status = action['master_controller_status'][arm]
if controller_status['infrared'] == 1:
if compare_joint_difference(master_joint, follow_joint):
if arm == 'left':
self.write_left_joint_canfd(master_joint)
else:
self.write_right_joint_canfd(master_joint)
else:
self._execute_slow_movement(arm, master_joint)
def write_endpose(self, target_endpose: list):
assert target_endpose == 12, "the length of target pose is not equal 12"
self.left_rmarm.rm_movej_p(target_endpose[:6], 50, 0, 0, 1)
self.right_rmarm.rm_movej_p(target_endpose[6:], 50, 0, 0, 1)
def write_left_joint_slow(self, left_joint: list):
assert len(left_joint) == self.left_offset, "len of left master joint is not equal the count of left joint"
self.left_rmarm.rm_movej(left_joint, 5, 0, 0, 1)
def write_right_joint_slow(self, right_joint: list):
assert len(right_joint) == self.left_offset, "len of right master joint is not equal the count of right joint"
self.right_rmarm.rm_movej(right_joint, 5, 0, 0, 1)
def write_left_joint_canfd(self, left_joint: list):
assert len(left_joint) == self.left_offset, "len of left master joint is not equal the count of left joint"
self.left_rmarm.rm_movej_canfd(left_joint, False)
def write_right_joint_canfd(self, right_joint: list):
assert len(right_joint) == self.left_offset, "len of right master joint is not equal the count of right joint"
self.right_rmarm.rm_movej_canfd(right_joint, False)
def write_endpose_canfd(self, target_endpose: list):
assert target_endpose == 12, "the length of target pose is not equal 12"
self.left_rmarm.rm_movep_canfd(target_endpose[:6], False)
self.right_rmarm.rm_movep_canfd(target_endpose[6:], False)
def write_dual_gripper(self, left_gripper: int, right_gripper: int):
self.left_rmarm.rm_set_gripper_position(left_gripper, False, 2)
self.right_rmarm.rm_set_gripper_position(right_gripper, False, 2)
def read_current_arm_joint_state(self):
return self.left_rmarm.rm_get_current_arm_state()[1]['joint'] + self.right_rmarm.rm_get_current_arm_state()[1]['joint']
def read_current_arm_endpose_state(self):
return self.left_rmarm.rm_get_current_arm_state()[1]['pose'] + self.right_rmarm.rm_get_current_arm_state()[1]['pose']
########################## lerobot function ##########################
def connect(self, enable: bool = True) -> bool:
"""使能机械臂并检测使能状态"""
with self._timeout_context() as is_timeout_valid:
while is_timeout_valid():
try:
if enable:
left_ret = self.left_rmarm.rm_get_current_arm_state()
right_ret = self.right_rmarm.rm_get_current_arm_state()
if left_ret[0] == 0 and right_ret[0] == 0:
print("机械臂使能成功")
return True
else:
RoboticArm.rm_destory()
print("机械臂断开连接")
return True
except Exception as e:
print(f"连接异常: {e}")
time.sleep(1)
print("连接超时")
return False
def set_calibration(self):
raise NotImplementedError
def revert_calibration(self):
raise NotImplementedError
def apply_calibration(self):
"""
移动到初始位置
"""
self.write(target_joint=self.init_joint_position)
def write(self, target_joint: list):
"""写入关节位置"""
self._validate_joint_count(target_joint, self.joint_count)
left_joints = target_joint[:self.left_offset]
left_gripper = target_joint[self.left_offset]
right_joints = target_joint[self.left_offset+1:-1]
right_gripper = target_joint[-1]
self.left_rmarm.rm_movej_follow(left_joints)
self.left_rmarm.rm_set_gripper_position(left_gripper, block=False, timeout=2)
self.right_rmarm.rm_movej_follow(right_joints)
self.right_rmarm.rm_set_gripper_position(right_gripper, block=False, timeout=2)
def write_action(self, action: dict, state: dict):
# 提取状态数据
follow_left_joint = self._extract_joint_state(state, "left_joint")
follow_right_joint = self._extract_joint_state(state, "right_joint")
# 提取动作数据
master_left_joint = action['left_joint_actions']
master_right_joint = action['right_joint_actions']
left_gripper = int(action['left_gripper_actions'] * 1000)
right_gripper = int(action['right_gripper_actions'] * 1000)
# 执行夹爪动作
self.write_dual_gripper(left_gripper, right_gripper)
# 执行关节动作
self._execute_arm_action('left', action, master_left_joint, follow_left_joint)
self._execute_arm_action('right', action, master_right_joint, follow_right_joint)
def read(self) -> Dict:
"""读取机械臂状态 - 直接从缓存获取"""
with self._cache_lock:
return self._state_cache.copy()
def safe_disconnect(self):
"""安全断开连接"""
try:
self.write(target_joint=self.safe_disable_position)
time.sleep(2) # 等待移动完成
except Exception as e:
print(f"移动到安全位置失败: {e}")
finally:
RoboticArm.rm_destory()
########################## lerobot function ##########################

View File

@@ -49,6 +49,10 @@ def make_motors_buses_from_configs(motors_bus_configs: dict[str, MotorsBusConfig
motors_buses[key] = RealmanMotorsBus(cfg)
elif cfg.type == "realman_dual":
from lerobot.common.robot_devices.motors.realman_dual import RealmanDualMotorsBus
motors_buses[key] = RealmanDualMotorsBus(cfg)
else:
raise ValueError(f"The motor type '{cfg.type}' is not valid.")

View File

@@ -27,7 +27,8 @@ from lerobot.common.robot_devices.motors.configs import (
DynamixelMotorsBusConfig,
FeetechMotorsBusConfig,
MotorsBusConfig,
RealmanMotorsBusConfig
RealmanMotorsBusConfig,
RealmanDualMotorsBusConfig
)
@@ -745,21 +746,76 @@ class RealmanRobotConfig(RobotConfig):
}
)
# right_follower_arm: dict[str, MotorsBusConfig] = field(
# default_factory=lambda: {
# "main": RealmanMotorsBusConfig(
# ip = "192.168.3.19",
# port = 8080,
# motors={
# # name: (index, model)
# "joint_1": [1, "realman"],
# "joint_2": [2, "realman"],
# "joint_3": [3, "realman"],
# "joint_4": [4, "realman"],
# "joint_5": [5, "realman"],
# "joint_6": [6, "realman"],
# "gripper": (7, "realman"),
# },
# )
# }
# )
@RobotConfig.register_subclass("realman_dual")
@dataclass
class RealmanDualRobotConfig(RobotConfig):
inference_time: bool = False
max_gripper: int = 990
min_gripper: int = 10
servo_config_file: str = "/home/maic/LYT/lerobot/lerobot/common/robot_devices/teleop/servo_dual.yaml"
follower_arm: dict[str, MotorsBusConfig] = field(
default_factory=lambda: {
"main": RealmanDualMotorsBusConfig(
axis= {'left_joint': 6, 'left_gripper': 1, 'right_joint': 6, 'right_gripper': 1},
left_ip = "192.168.3.18",
left_port = 8080,
right_ip = "192.168.3.19",
right_port = 8080,
init_joint = {'joint': [-170, 90, 0, 90, 120, 0, 10, 170, 90, 0, -90, 120, 0, 10]},
motors={
# name: (index, model)
"left_joint_1": [1, "realman"],
"left_joint_2": [2, "realman"],
"left_joint_3": [3, "realman"],
"left_joint_4": [4, "realman"],
"left_joint_5": [5, "realman"],
"left_joint_6": [6, "realman"],
"left_gripper": [7, "realman"],
"right_joint_1": [8, "realman"],
"right_joint_2": [9, "realman"],
"right_joint_3": [10, "realman"],
"right_joint_4": [11, "realman"],
"right_joint_5": [12, "realman"],
"right_joint_6": [13, "realman"],
"right_gripper": [14, "realman"]
},
)
}
)
cameras: dict[str, CameraConfig] = field(
default_factory=lambda: {
"left": IntelRealSenseCameraConfig(
serial_number="153122077516",
fps=30,
width=640,
height=480,
use_depth=False
),
"right": IntelRealSenseCameraConfig(
serial_number="405622075165",
fps=30,
width=640,
height=480,
use_depth=False
),
"front": IntelRealSenseCameraConfig(
serial_number="145422072751",
fps=30,
width=640,
height=480,
use_depth=False
),
"high": IntelRealSenseCameraConfig(
serial_number="145422072193",
fps=30,
width=640,
height=480,
use_depth=False
),
}
)

View File

@@ -0,0 +1,312 @@
"""
Teleoperation Realman with a PS5 controller and
"""
import time
import torch
import numpy as np
import logging
from typing import Optional, Tuple, Dict
from dataclasses import dataclass, field, replace
from collections import deque
from lerobot.common.robot_devices.teleop.gamepad_dual import HybridController
from lerobot.common.robot_devices.motors.utils import get_motor_names, make_motors_buses_from_configs
from lerobot.common.robot_devices.cameras.utils import make_cameras_from_configs
from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError
from lerobot.common.robot_devices.robots.configs import RealmanDualRobotConfig
class RealmanDualRobot:
def __init__(self, config: RealmanDualRobotConfig | None = None, **kwargs):
if config is None:
config = RealmanDualRobotConfig()
# Overwrite config arguments using kwargs
self.config = replace(config, **kwargs)
self.robot_type = self.config.type
self.inference_time = self.config.inference_time # if it is inference time
# build cameras
self.cameras = make_cameras_from_configs(self.config.cameras)
# build realman motors
self.piper_motors = make_motors_buses_from_configs(self.config.follower_arm)
self.arm = self.piper_motors['main']
# build init teleop info
self.init_info = {
'init_joint': self.arm.init_joint_position,
'init_pose': self.arm.init_pose,
'max_gripper': config.max_gripper,
'min_gripper': config.min_gripper,
'servo_config_file': config.servo_config_file
}
# 初始化遥操作
self._initialize_teleop()
# init state
self._initialize_state()
def _initialize_teleop(self):
"""初始化遥操作"""
self.init_info = {
'init_joint': self.arm.init_joint_position,
'init_pose': self.arm.init_pose,
'max_gripper': self.config.max_gripper,
'min_gripper': self.config.min_gripper,
'servo_config_file': self.config.servo_config_file
}
if not self.inference_time:
self.teleop = HybridController(self.init_info)
else:
self.teleop = None
def _initialize_state(self):
"""初始化状态"""
self.joint_queue = deque(maxlen=2)
self.last_endpose = self.arm.init_pose
self.logs = {}
self.is_connected = False
def _read_robot_state(self) -> dict:
"""读取机器人状态"""
before_read_t = time.perf_counter()
state = self.arm.read()
self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t
return state
def _execute_action(self, action: dict, state: dict):
"""执行动作"""
before_write_t = time.perf_counter()
if action['control_mode'] == 'joint':
self.arm.write_action(action, state)
# 可以添加其他控制模式的处理
self.logs["write_pos_dt_s"] = time.perf_counter() - before_write_t
def _prepare_record_data(self) -> Tuple[Dict, Dict]:
"""准备记录数据"""
if len(self.joint_queue) < 2:
return {}, {}
state = torch.as_tensor(list(self.joint_queue[0]), dtype=torch.float32)
action = torch.as_tensor(list(self.joint_queue[-1]), dtype=torch.float32)
# 捕获图像
images = self._capture_images()
# 构建输出字典
obs_dict = {
"observation.state": state,
**{f"observation.images.{name}": img for name, img in images.items()}
}
action_dict = {"action": action}
return obs_dict, action_dict
def _update_state_queue(self):
"""更新状态队列"""
current_state = list(self.arm.read().values())
self.joint_queue.append(current_state)
def _capture_images(self) -> Dict[str, torch.Tensor]:
"""捕获图像"""
images = {}
for name, camera in self.cameras.items():
before_camread_t = time.perf_counter()
image = camera.async_read()
images[name] = torch.from_numpy(image)
self.logs[f"read_camera_{name}_dt_s"] = camera.logs["delta_timestamp_s"]
self.logs[f"async_read_camera_{name}_dt_s"] = time.perf_counter() - before_camread_t
return images
@property
def camera_features(self) -> dict:
cam_ft = {}
for cam_key, cam in self.cameras.items():
key = f"observation.images.{cam_key}"
cam_ft[key] = {
"shape": (cam.height, cam.width, cam.channels),
"names": ["height", "width", "channels"],
"info": None,
}
return cam_ft
@property
def motor_features(self) -> dict:
action_names = get_motor_names(self.piper_motors)
state_names = get_motor_names(self.piper_motors)
return {
"action": {
"dtype": "float32",
"shape": (len(action_names),),
"names": action_names,
},
"observation.state": {
"dtype": "float32",
"shape": (len(state_names),),
"names": state_names,
},
}
@property
def has_camera(self):
return len(self.cameras) > 0
@property
def num_cameras(self):
return len(self.cameras)
def connect(self) -> None:
"""Connect RealmanArm and cameras"""
if self.is_connected:
raise RobotDeviceAlreadyConnectedError(
"RealmanArm is already connected. Do not run `robot.connect()` twice."
)
# connect RealmanArm
self.arm.connect(enable=True)
print("RealmanArm conneted")
# connect cameras
for name in self.cameras:
self.cameras[name].connect()
self.is_connected = self.is_connected and self.cameras[name].is_connected
print(f"camera {name} conneted")
print("All connected")
self.is_connected = True
self.run_calibration()
def disconnect(self) -> None:
"""move to home position, disenable piper and cameras"""
# move piper to home position, disable
if not self.inference_time:
self.teleop.stop()
# disconnect piper
self.arm.safe_disconnect()
print("RealmanArm disable after 5 seconds")
time.sleep(5)
self.arm.connect(enable=False)
# disconnect cameras
if len(self.cameras) > 0:
for cam in self.cameras.values():
cam.disconnect()
self.is_connected = False
def run_calibration(self):
"""move piper to the home position"""
if not self.is_connected:
raise ConnectionError()
self.arm.apply_calibration()
if not self.inference_time:
self.teleop.reset()
def teleop_step(
self, record_data=False
) -> None | tuple[dict[str, torch.Tensor], dict[str, torch.Tensor]]:
if not self.is_connected:
raise ConnectionError()
if self.teleop is None and self.inference_time:
self.teleop = HybridController(self.init_info)
try:
# 读取当前状态
state = self._read_robot_state()
# 获取动作
action = self.teleop.get_action()
# 执行动作
self._execute_action(action, state)
# 更新状态队列
self._update_state_queue()
if record_data:
data = self._prepare_record_data()
return data
except Exception as e:
logging.error(f"遥操作步骤失败: {e}")
return None
def send_action(self, action: torch.Tensor) -> torch.Tensor:
"""Write the predicted actions from policy to the motors"""
if not self.is_connected:
raise RobotDeviceNotConnectedError(
"Piper is not connected. You need to run `robot.connect()`."
)
# send to motors, torch to list
target_joints = action.tolist()
len_joint = len(target_joints) - 1
target_joints = [target_joints[i]*180 for i in range(len_joint)] + [target_joints[-1]]
target_joints[-1] = int(target_joints[-1]*500 + 500)
self.arm.write(target_joints)
return action
def capture_observation(self) -> dict:
"""capture current images and joint positions"""
if not self.is_connected:
raise RobotDeviceNotConnectedError(
"Piper is not connected. You need to run `robot.connect()`."
)
# read current joint positions
before_read_t = time.perf_counter()
state = self.arm.read() # 6 joints + 1 gripper
self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t
state = torch.as_tensor(list(state.values()), dtype=torch.float32)
# read images from cameras
images = {}
for name in self.cameras:
before_camread_t = time.perf_counter()
images[name] = self.cameras[name].async_read()
images[name] = torch.from_numpy(images[name])
self.logs[f"read_camera_{name}_dt_s"] = self.cameras[name].logs["delta_timestamp_s"]
self.logs[f"async_read_camera_{name}_dt_s"] = time.perf_counter() - before_camread_t
# Populate output dictionnaries and format to pytorch
obs_dict = {}
obs_dict["observation.state"] = state
for name in self.cameras:
obs_dict[f"observation.images.{name}"] = images[name]
return obs_dict
def teleop_safety_stop(self):
""" move to home position after record one episode """
self.run_calibration()
def __del__(self):
if self.is_connected:
self.disconnect()
if not self.inference_time:
self.teleop.stop()
if __name__ == '__main__':
robot = RealmanDualRobot()
robot.connect()
# robot.run_calibration()
while True:
robot.teleop_step(record_data=True)
# robot.capture_observation()
# dummy_action = torch.Tensor([-0.40586111280653214, 0.5522833506266276, 0.4998166826036241, -0.3539944542778863, -0.524433347913954, 0.9064999898274739, 0.482])
# robot.send_action(dummy_action)
# robot.disconnect()
# print('ok')

View File

@@ -25,7 +25,8 @@ from lerobot.common.robot_devices.robots.configs import (
So100RobotConfig,
So101RobotConfig,
StretchRobotConfig,
RealmanRobotConfig
RealmanRobotConfig,
RealmanDualRobotConfig
)
@@ -87,6 +88,11 @@ def make_robot_from_config(config: RobotConfig):
from lerobot.common.robot_devices.robots.realman import RealmanRobot
return RealmanRobot(config)
elif isinstance(config, RealmanDualRobotConfig):
from lerobot.common.robot_devices.robots.realman_dual import RealmanDualRobot
return RealmanDualRobot(config)
else:
from lerobot.common.robot_devices.robots.stretch import StretchRobot

View File

@@ -0,0 +1,114 @@
import pygame
import threading
import time
import serial
import binascii
import logging
import yaml
from typing import Dict
from dataclasses import dataclass
from Robotic_Arm.rm_robot_interface import *
from .servo_server import ServoArmServer
@dataclass
class ControllerConfig:
"""控制器配置"""
init_joint: list
init_pose: list
max_gripper: int
min_gripper: int
config_file: str
class HybridController:
def __init__(self, init_info):
self.config = self._parse_init_info(init_info)
self.joint = self.config.init_joint.copy()
self.pose = self.config.init_pose.copy()
self.joint_control_mode = True
self._initialize_master_arm()
def _parse_init_info(self, init_info: dict) -> ControllerConfig:
"""解析初始化信息"""
return ControllerConfig(
init_joint=init_info['init_joint'],
init_pose=init_info.get('init_pose', [0]*12),
max_gripper=init_info['max_gripper'],
min_gripper=init_info['min_gripper'],
config_file=init_info['servo_config_file']
)
def _initialize_master_arm(self):
"""初始化主控臂"""
try:
self.master_dual_arm = ServoArmServer(self.config.config_file)
except Exception as e:
logging.error(f"初始化主控臂失败: {e}")
raise
def get_action(self) -> Dict:
"""获取控制动作"""
try:
master_joint_actions = self.master_dual_arm.get_joint_data()
return self._format_action(master_joint_actions)
except Exception as e:
logging.error(f"获取动作失败: {e}")
def _format_action(self, master_joint_actions: dict) -> dict:
"""格式化动作数据"""
master_controller_status = {
'left': master_joint_actions['left_controller_status'],
'right': master_joint_actions['right_controller_status']
}
return {
'control_mode': 'joint' if self.joint_control_mode else 'end_pose',
'master_joint_actions': master_joint_actions['dual_joint_actions'],
'left_joint_actions': master_joint_actions['left_joint_actions'][:-1],
'right_joint_actions': master_joint_actions['right_joint_actions'][:-1],
'left_gripper_actions': master_joint_actions['left_joint_actions'][-1], # 修复bug
'right_gripper_actions': master_joint_actions['right_joint_actions'][-1],
'master_controller_status': master_controller_status,
'end_pose': self.pose
}
def switch_control_mode(self):
"""切换控制模式"""
self.joint_control_mode = not self.joint_control_mode
mode = "关节" if self.joint_control_mode else "末端"
print(f"切换到{mode}控制模式")
def stop(self):
"""停止控制器"""
try:
if hasattr(self, 'master_dual_arm') and self.master_dual_arm:
self.master_dual_arm.shutdown()
print("混合控制器已退出")
except Exception as e:
logging.error(f"停止控制器失败: {e}")
def reset(self):
"""重置控制器"""
self.joint = self.config.init_joint.copy()
self.pose = self.config.init_pose.copy()
self.joint_control_mode = True
# 使用示例
if __name__ == "__main__":
init_info = {
'init_joint': [-175, 90, 90, 45, 90, -90, 10, 175, 90, 90, -45, 90, 90, 10],
'init_pose': [[-0.0305, 0.125938, 0.13153, 3.141, 0.698, -1.57, -0.030486, -0.11487, 0.144707, 3.141, 0.698, 1.57]],
'max_gripper': 990,
'min_gripper': 10,
'servo_config_file': '/home/maic/LYT/lerobot/lerobot/common/robot_devices/teleop/servo_dual.yaml'
}
arm_controller = HybridController(init_info)
time.sleep(1)
try:
while True:
print(arm_controller.get_action())
time.sleep(1)
except KeyboardInterrupt:
arm_controller.stop()

View File

@@ -0,0 +1,6 @@
left_port: /dev/ttyUSB0
right_port: /dev/ttyUSB1
baudrate: 460800
joint_hex_data: "55 AA 02 00 00 67"
control_hex_data: "55 AA 08 00 00 B9"
arm_axis: 6

View File

@@ -0,0 +1,321 @@
import threading
import time
import serial
import binascii
import logging
import yaml
from typing import Dict
# logging.basicConfig(
# level=logging.INFO, format="%(asctime)s - %(levelname)s - %(message)s"
# )
class ServoArmServer:
def __init__(self, config_file="servo_dual.yaml"):
"""初始化服务器,创建左右机械臂实例"""
self.config_file = config_file
self.left_servo_arm = None
self.right_servo_arm = None
self.running = False
self.data_lock = threading.Lock()
self.latest_data = {
'left_joint_actions': {},
'right_joint_actions': {},
'left_controller_status': {},
'right_controller_status': {},
'timestamp': time.time()
}
# 初始化机械臂
self._initialize_arms()
# 启动数据采集线程
self._start_data_collection()
def _initialize_arms(self):
"""初始化左右机械臂"""
try:
self.left_servo_arm = ServoArm(self.config_file, "left_port")
logging.info("左master机械臂初始化成功")
except Exception as e:
logging.error(f"左master机械臂初始化失败: {e}")
try:
self.right_servo_arm = ServoArm(self.config_file, "right_port")
logging.info("右master机械臂初始化成功")
except Exception as e:
logging.error(f"右master机械臂初始化失败: {e}")
def _start_data_collection(self):
"""启动数据采集线程"""
self.running = True
# 创建左臂数据采集线程
self.left_data_thread = threading.Thread(target=self._left_arm_data_loop)
self.left_data_thread.daemon = True
self.left_data_thread.start()
# 创建右臂数据采集线程
self.right_data_thread = threading.Thread(target=self._right_arm_data_loop)
self.right_data_thread.daemon = True
self.right_data_thread.start()
logging.info("左右机械臂数据采集线程已启动")
def _left_arm_data_loop(self):
"""左机械臂数据采集循环"""
while self.running:
try:
left_actions = {}
left_controller_status = {}
# 获取左机械臂数据
if self.left_servo_arm and self.left_servo_arm.connected:
left_actions = self.left_servo_arm.get_joint_actions()
left_controller_status = self.left_servo_arm.get_controller_status()
if self._check_val_safety(left_actions) == False:
time.sleep(0.02)
continue
# 更新左机械臂数据
with self.data_lock:
self.latest_data['left_joint_actions'] = [left_actions[k] for k in left_actions]
self.latest_data['left_controller_status'] = left_controller_status
# 更新dual_joint_actions
if self.latest_data['right_joint_actions']:
self.latest_data['dual_joint_actions'] = self.latest_data['left_joint_actions'] + self.latest_data['right_joint_actions']
self.latest_data['timestamp'] = time.time()
time.sleep(0.02) # 50Hz采集频率
except Exception as e:
logging.error(f"左机械臂数据采集错误: {e}")
time.sleep(0.1)
def _right_arm_data_loop(self):
"""右机械臂数据采集循环"""
while self.running:
try:
right_actions = {}
right_controller_status = {}
# 获取右机械臂数据
if self.right_servo_arm and self.right_servo_arm.connected:
right_actions = self.right_servo_arm.get_joint_actions()
right_controller_status = self.right_servo_arm.get_controller_status()
if self._check_val_safety(right_actions) == False:
time.sleep(0.02)
continue
# 更新右机械臂数据
with self.data_lock:
self.latest_data['right_joint_actions'] = [right_actions[k] for k in right_actions]
self.latest_data['right_controller_status'] = right_controller_status
# 更新dual_joint_actions
if self.latest_data['left_joint_actions']:
self.latest_data['dual_joint_actions'] = self.latest_data['left_joint_actions'] + self.latest_data['right_joint_actions']
self.latest_data['timestamp'] = time.time()
time.sleep(0.02) # 50Hz采集频率
except Exception as e:
logging.error(f"右机械臂数据采集错误: {e}")
time.sleep(0.1)
def _check_val_safety(self, data: dict):
data = [data[k] for k in data]
ret = True
if len(data) != self.left_servo_arm.arm_axis + 1:
ret = False
for v in data:
if v > 180 or v < -180:
ret = False
return ret
# ZeroRPC 服务方法
def get_joint_data(self):
"""获取最新的关节数据"""
with self.data_lock:
return self.latest_data.copy()
def get_left_joint_actions(self):
"""获取左机械臂关节数据和控制器状态"""
with self.data_lock:
return {
'data': self.latest_data['left_joint_actions'],
'controller_status': self.latest_data['left_controller_status'],
'timestamp': self.latest_data['timestamp']
}
def get_right_joint_actions(self):
"""获取右机械臂关节数据和控制器状态"""
with self.data_lock:
return {
'data': self.latest_data['right_joint_actions'],
'controller_status': self.latest_data['right_controller_status'],
'timestamp': self.latest_data['timestamp']
}
def get_connection_status(self):
"""获取连接状态"""
return {
'left_connected': self.left_servo_arm.connected if self.left_servo_arm else False,
'right_connected': self.right_servo_arm.connected if self.right_servo_arm else False,
'server_running': self.running
}
def ping(self):
"""测试连接"""
return "pong"
def shutdown(self):
"""关闭服务器"""
logging.info("正在关闭服务器...")
self.running = False
if self.left_servo_arm:
self.left_servo_arm.close()
if self.right_servo_arm:
self.right_servo_arm.close()
return "Server shutdown"
class ServoArm:
def __init__(self, config_file="config.yaml", port_name="left_port"):
"""初始化机械臂的串口连接并发送初始数据。
Args:
config_file (str): 配置文件的路径。
"""
self.config = self._load_config(config_file)
self.port = self.config[port_name]
self.baudrate = self.config["baudrate"]
self.joint_hex_data = self.config["joint_hex_data"]
self.control_hex_data = self.config["control_hex_data"]
self.arm_axis = self.config.get("arm_axis", 7)
try:
self.serial_conn = serial.Serial(self.port, self.baudrate, timeout=0)
self.bytes_to_send = binascii.unhexlify(self.joint_hex_data.replace(" ", ""))
self.serial_conn.write(self.bytes_to_send)
time.sleep(1)
self.connected = True
logging.info(f"串口连接成功: {self.port}")
except Exception as e:
logging.error(f"串口连接失败: {e}")
self.connected = False
def _load_config(self, config_file):
"""加载配置文件。
Args:
config_file (str): 配置文件的路径。
Returns:
dict: 配置文件内容。
"""
try:
with open(config_file, "r") as file:
config = yaml.safe_load(file)
return config
except Exception as e:
logging.error(f"配置文件加载失败: {e}")
# 返回默认配置
return {
"port": "/dev/ttyUSB0",
"baudrate": 460800,
"joint_hex_data": "55 AA 02 00 00 67",
"control_hex_data": "55 AA 08 00 00 B9",
"arm_axis": 6
}
def _bytes_to_signed_int(self, byte_data):
"""将字节数据转换为有符号整数。
Args:
byte_data (bytes): 字节数据。
Returns:
int: 有符号整数。
"""
return int.from_bytes(byte_data, byteorder="little", signed=True)
def _parse_joint_data(self, hex_received):
"""解析接收到的十六进制数据并提取关节数据。
Args:
hex_received (str): 接收到的十六进制字符串数据。
Returns:
dict: 解析后的关节数据。
"""
logging.debug(f"hex_received: {hex_received}")
joints = {}
for i in range(self.arm_axis):
start = 14 + i * 10
end = start + 8
joint_hex = hex_received[start:end]
joint_byte_data = bytearray.fromhex(joint_hex)
joint_value = self._bytes_to_signed_int(joint_byte_data) / 10000.0
joints[f"joint_{i+1}"] = joint_value #/ 180
grasp_start = 14 + self.arm_axis*10
grasp_hex = hex_received[grasp_start:grasp_start+8]
grasp_byte_data = bytearray.fromhex(grasp_hex)
# 夹爪进行归一化处理
grasp_value = self._bytes_to_signed_int(grasp_byte_data)/1000
joints["grasp"] = grasp_value
return joints
def _parse_controller_data(self, hex_received):
status = {
'infrared': 0,
'button': 0
}
if len(hex_received) == 18:
status['infrared'] = self._bytes_to_signed_int(bytearray.fromhex(hex_received[12:14]))
status['button'] = self._bytes_to_signed_int(bytearray.fromhex(hex_received[14:16]))
# print(infrared)
return status
def get_joint_actions(self):
"""从串口读取数据并解析关节动作。
Returns:
dict: 包含关节数据的字典。
"""
if not self.connected:
return {}
try:
self.serial_conn.write(self.bytes_to_send)
time.sleep(0.025)
bytes_received = self.serial_conn.read(self.serial_conn.inWaiting())
if len(bytes_received) == 0:
return {}
hex_received = binascii.hexlify(bytes_received).decode("utf-8").upper()
actions = self._parse_joint_data(hex_received)
return actions
except Exception as e:
logging.error(f"读取串口数据错误: {e}")
return {}
def get_controller_status(self):
bytes_to_send = binascii.unhexlify(self.control_hex_data.replace(" ", ""))
self.serial_conn.write(bytes_to_send)
time.sleep(0.025)
bytes_received = self.serial_conn.read(self.serial_conn.inWaiting())
hex_received = binascii.hexlify(bytes_received).decode("utf-8").upper()
# print("control status:", hex_received)
status = self._parse_controller_data(hex_received)
return status
def close(self):
"""关闭串口连接"""
if self.connected and hasattr(self, 'serial_conn'):
self.serial_conn.close()
self.connected = False
logging.info("串口连接已关闭")