LEAP Hand灵巧手使用说明-2.Python SDK

Ubuntu 上安装

python3 -m venv test_env

source test_env/bin/activate

software_1.png 

pip install dynamixel_sdk numpy

software_2.png 

sudo chmod 777 /dev/serial/by-id/*

software_3.png 

cd /home/robot/projects/LEAP_Hand_API/python

software_4.png 

python3 main.py


Windows 上安装

使用 Windows powershell

我们建议创建一个虚拟环境并使用 pip 安装代码:

Set-ExecutionPolicy Unrestricted -Scope Process

python -m venv test_env

.\test_env\Scripts\activate.ps1

pip install dynamixel_sdk numpy

python main.py


import numpy as np
from leap_hand_utils.dynamixel_client import *
import leap_hand_utils.leap_hand_utils as lhu
import time

#######################################################
"""这段代码可以控制和查询LEAP Hand机械手

建议必要时进行查询,且每秒低于90个样本。尽量使用组合命令以节省时间。
同时不要忘记README中关于USB延迟的设置。

# Allegro手部约定:
# 0.0是完全伸出的初始姿势,当手指更多闭合时角度变为正值(弧度制)。

# LEAP手部约定:
# 3.14弧度是食指、中指、无名指MCP关节的平伸初始姿势。
# 应用正角度使关节更多闭合(弧度制)。
# MCP关节以3.14弧度为中心,可以正向或负向移动(弧度制)。

# 关节编号从食指(0-3)、中指(4-7)、无名指(8-11)到拇指(12-15),
# 每个手指从MCP侧摆、MCP前后摆、PIP到DIP。
# 例如,食指的MCP侧摆是ID 0,无名指的MCP前后摆是9,无名指的DIP是11

"""
########################################################

class LeapNode:
    def __init__(self):
        #### 参数设置
        # 建议保持电流限制:Lite版本为350,完整版本为550
        # 如果手部力度太弱则增加KP,如果抖动则减小KP
        self.kP = 600  # 比例增益,控制刚度
        self.kI = 0    # 积分增益
        self.kD = 200  # 微分增益,控制阻尼
        self.curr_lim = 350  # 电流限制,完整电机设置为550!
        
        # 初始化位置变量,将Allegro的零位转换为LEAP手部坐标系
        self.prev_pos = self.pos = self.curr_pos = lhu.allegro_to_LEAPhand(np.zeros(16))
        
        # 电机ID列表,对应16个关节
        self.motors = motors = [0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15]
        
        # 尝试连接多个可能的串口(自动搜索)
        try:
            self.dxl_client = DynamixelClient(motors, '/dev/ttyUSB0', 4000000)
            self.dxl_client.connect()
        except Exception:
            try:
                self.dxl_client = DynamixelClient(motors, '/dev/ttyUSB1', 4000000)
                self.dxl_client.connect()
            except Exception:
                self.dxl_client = DynamixelClient(motors, 'COM13', 4000000)
                self.dxl_client.connect()
        
        # 启用位置-电流控制模式,命令位置并限制电流以防电机过载[4](@ref)
        self.dxl_client.sync_write(motors, np.ones(len(motors))*5, 11, 1)
        self.dxl_client.set_torque_enabled(motors, True)
        
        # 设置PID参数
        self.dxl_client.sync_write(motors, np.ones(len(motors)) * self.kP, 84, 2)  # 比例增益(刚度)
        self.dxl_client.sync_write([0,4,8], np.ones(3) * (self.kP * 0.75), 84, 2)  # 侧摆关节的P增益稍小
        self.dxl_client.sync_write(motors, np.ones(len(motors)) * self.kI, 82, 2)  # 积分增益
        self.dxl_client.sync_write(motors, np.ones(len(motors)) * self.kD, 80, 2)  # 微分增益(阻尼)
        self.dxl_client.sync_write([0,4,8], np.ones(3) * (self.kD * 0.75), 80, 2)   # 侧摆关节的D增益稍小
        
        # 设置电流限制(单位:毫安),防止过热和抓握过紧
        self.dxl_client.sync_write(motors, np.ones(len(motors)) * self.curr_lim, 102, 2)
        
        # 写入初始位置
        self.dxl_client.write_desired_pos(self.motors, self.curr_pos)

    # 接收LEAP姿势并直接控制机器人[5](@ref)
    def set_leap(self, pose):
        """使用LEAP手部原始角度设置位置"""
        self.prev_pos = self.curr_pos  # 保存之前位置
        self.curr_pos = np.array(pose)  # 更新当前位置
        self.dxl_client.write_desired_pos(self.motors, self.curr_pos)  # 发送位置命令

    # Allegro兼容关节角度。增加180度使完全打开位置在0而不是180[5](@ref)
    def set_allegro(self, pose):
        """使用Allegro手部兼容角度设置位置"""
        pose = lhu.allegro_to_LEAPhand(pose, zeros=False)  # 坐标转换
        self.prev_pos = self.curr_pos
        self.curr_pos = np.array(pose)
        self.dxl_client.write_desired_pos(self.motors, self.curr_pos)

    # 策略的模拟兼容性,假设范围是[-1,1]然后转换为LEAP手部范围
    def set_ones(self, pose):
        """使用标准化范围[-1,1]设置位置"""
        pose = lhu.sim_ones_to_LEAPhand(np.array(pose))  # 范围映射
        self.prev_pos = self.curr_pos
        self.curr_pos = np.array(pose)
        self.dxl_client.write_desired_pos(self.motors, self.curr_pos)

    # 读取机器人位置
    def read_pos(self):
        """读取当前所有关节的位置"""
        return self.dxl_client.read_pos()

    # 读取速度
    def read_vel(self):
        """读取当前所有关节的速度"""
        return self.dxl_client.read_vel()

    # 读取电流
    def read_cur(self):
        """读取当前所有关节的电流"""
        return self.dxl_client.read_cur()

    # 组合命令更快,返回数据列表[5](@ref)
    def pos_vel(self):
        """同时读取位置和速度(更高效)"""
        return self.dxl_client.read_pos_vel()

    # 组合命令更快,返回数据列表
    def pos_vel_eff_srv(self):
        """同时读取位置、速度和电流(最完整的查询)"""
        return self.dxl_client.read_pos_vel_cur()

# 初始化节点
def main(**kwargs):
    """主函数:初始化手部并运行控制循环"""
    leap_hand = LeapNode()  # 创建LEAP手部实例
    
    while True:
        # 设置为打开姿势并读取关节角度(33Hz)
        leap_hand.set_allegro(np.zeros(16))  # 零位对应打开手势
        print("Position: " + str(leap_hand.read_pos()))  # 打印当前位置
        time.sleep(0.03)  # 控制循环频率约33Hz

if __name__ == "__main__":
    main()  # 程序入口点