# libgx **Repository Path**: yunlongdong/libgx ## Basic Information - **Project Name**: libgx - **Description**: Python ibrary for General Dexterous Hand Series - **Primary Language**: Unknown - **License**: Not specified - **Default Branch**: master - **Homepage**: None - **GVP Project**: No ## Statistics - **Stars**: 3 - **Forks**: 0 - **Created**: 2024-04-18 - **Last Updated**: 2024-08-30 ## Categories & Tags **Categories**: Uncategorized **Tags**: None ## README # Libgx: GX-Hand SDK 依赖 ``` pip install pyserial pip install ikpy ``` ## GX11三指11自由度全驱力控灵巧手 使用Type-C USB 和 DC 电源(5V)连接 GX11,然后在 demo.py 中更改端口(对于 Linux,端口可能是 /dev/ttyUSB* 或 /dev/ttyACM*,对于 Windows,可能是 COM*),然后运行: ``` python demo.py ``` GX11原点位置: Image GX11电机ID: Image GX11运动学坐标系(手指2): Image ## 代码案例 ```python from libgx.libgx11 import Hand # Instantiate Hand object hand = Hand('/dev/ttyUSB0') # Connect to the hand hand.connect() # Perform a grasping action hand.grasp() # Reset the hand hand.release() # Demonstrate coordinated finger movements for 10 seconds hand.move_demo(duration=10) ``` ### libgx.libgx11.Hand 类文档 `Hand` 类用于控制 GX11 机械手,提供连接、控制手指动作、获取关节角度等功能。 #### 初始化 ```python def __init__(self, port) ``` 初始化一个 `Hand` 实例。 - `port` (str): 串口名称或路径,/dev/ttyUSB* or /dev/ttyACM* for Linux, COM* for Windows。 #### 方法 ```python def connect(self) ``` 连接 GX11 机械手并初始化电机。 ```python def off(self) ``` 失能所有电机。 ```python def on(self) ``` 使能所有电机。 ```python def grasp(self) ``` 执行 GX11 抓取动作。 ```python def release(self) ``` 执行 GX11 复位动作。 ```python def finger_grasp(self, tighten=False, force=500) ``` 控制手指,可选择锁紧并设置锁紧力。 - `tighten` (bool): 是否锁紧手指。 - `force` (int): 锁紧力(单位 mA)。 ```python def getj(self) ``` 获取 GX11 机械手关节角度。 ```python def setj(self, js) ``` 设置 GX11 机械手关节角度。 - `js` (list): 关节角度列表(单位度)。 ```python def set_zero_whole_hand(self) ``` 将 GX11 手掌当前位置设置为零点(慎用)。 ```python def move_demo(self, duration=5) ``` 执行 GX11 手指联动演示。 - `duration` (float): 持续时间(单位秒)。 ```python def fk_finger1(self) ``` 计算 finger1 的正运动学,返回末端坐标(单位 m)。 ```python def ik_finger1(self, xyz) ``` 计算 finger1 的逆运动学,给定末端坐标(单位 m)。 - `xyz` (list): 末端坐标。 ```python def fk_finger2(self) ``` 计算 finger2 的正运动学,返回末端坐标(单位 m)。 ```python def ik_finger2(self, xyz) ``` 计算 finger2 的逆运动学,给定末端坐标(单位 m)。 - `xyz` (list): 末端坐标。 ```python def fk_finger3(self) ``` 计算 finger3 的正运动学,返回末端坐标(单位 m)。 ```python def ik_finger3(self, xyz) ``` 计算 finger3 的逆运动学,给定末端坐标(单位 m)。 - `xyz` (list): 末端坐标。 以下是对 `Motor` 类的文档说明: # libgx.motor.Motor 类文档 Motor 类用于控制单个电机。 ## 初始化方法 ```python def __init__(self, id, portHandler, packetHandler) -> None: ``` 初始化一个 Motor 对象。 - `id`: 电机的 ID。 - `portHandler`: 用于通信的端口处理器。 - `packetHandler`: 用于处理通信数据包的处理器。 ## 属性 - `unit_scale`: 角度的单位缩放因子,默认为 `0.087891` 度。 - `port_handler`: 通信端口处理器。 - `packet_handler`: 数据包处理器。 - `addr_torq_enable`: 电机使能地址。 - `addr_led`: LED 控制地址。 - `addr_present_pos`: 当前位置地址。 - `addr_present_current`: 当前电流地址。 - `addr_goal_pos`: 目标位置地址。 - `addr_curr_limit`: 电流限制地址。 - `addr_pos_p`: 位置 P 值地址。 - `addr_pos_d`: 位置 D 值地址。 - `addr_vel_limit`: 速度限制地址。 - `addr_home_off`: 归零偏移地址。 - `addr_goal_curr`: 目标电流地址。 - `addr_goal_pwm`: 目标 PWM 地址。 - `addr_operating_mode`: 运行模式地址。 - `curr_operating_mode`: 电流模式标识。 - `vel_operating_mode`: 速度模式标识。 - `pos_operating_mode`: 位置模式标识。 - `extpos_operating_mode`: 扩展位置模式标识。 - `currpos_operating_mode`: 位置力控模式标识(推荐使用)。 - `pwm_operating_mode`: PWM 模式标识。 - `curr_limit`: 最大电流限制,默认为 `500` 毫安。 - `curr_max`: 最大电流值,默认为 `12000` 毫安。 ## 方法 - `led_on()`: 开启电机的 LED。 - `led_off()`: 关闭电机的 LED。 - `torq_on()`: 打开电机使能。 - `torq_off()`: 关闭电机使能。 - `get_pos()`: 获取电机当前位置(单位:度)。 - `set_zero()`: 设置电机位置归零。 - `set_curr_limit(curr)`: 设置电机的最大电流限制(单位:毫安)。 - `pos_force_mode(goal_current, goal_pwm)`: 设置力控位置模式,goal_current影响力的大小,goal_pwm影响速度 - `force_mode()`: 设置电流模式。 - `init_config(curr_limit, goal_current, goal_pwm)`: 初始化电机配置,包括 LED 闪烁、力控位置模式设置以及电机使能。 - `set_pos(pos)`: 设置电机的目标角度(单位:度)。 - `set_curr(cur)`: 设置电机的目标电流(单位:毫安)。