Skip to main content
Version: 6.1.0 (Latest)

灵动Python SDK使用说明

1. 介绍

Alicia-D SDK 是一个用于控制【灵动 Alicia-D】系列六轴机械臂(带夹爪)的 Python 工具包。它基于 RoboCore 库构建,提供通过串口通信控制机械臂运动、操作夹爪、读取姿态与状态数据等功能。

1.1 主要特性

  • 关节控制:支持设置与读取六个关节的角度,提供平滑插值执行。
  • 末端轨迹:支持笛卡尔空间末端姿态轨迹规划。
  • 夹爪控制:支持精确角度控制或一键开关。
  • 力矩控制:开启或关闭关节电机扭矩,实现自由拖动(示教)。
  • 零点设置:将当前位置设置为新的零点。
  • 状态读取:实时获取关节角、夹爪角与末端姿态。
  • 自动串口连接:自动搜索串口或手动指定。
  • 教学模式:拖动记录姿态点并执行轨迹。
  • 日志系统:支持日志级别过滤,可控制控制台输出详细程度。

2. 安装与配置

2.1 环境要求

  • Python 3.8 及以上版本
  • 支持串口的计算机(USB 转串口芯片已集成在机械臂)

2.2 安装步骤

克隆或下载项目

git clone https://github.com/Synria-Robotics/Alicia-D-SDK.git -b v6.1.0
cd Alicia-D-SDK

创建 Python 环境并安装依赖

使用 Conda 环境(推荐):

conda create -n alicia python=3.10
conda activate alicia

安装SDK:

# Local installation
pip install -e .

2.3 快速开始

基本使用示例:

from alicia_d_sdk import create_robot

# 创建机器人实例(自动搜索串口并连接,auto_connect=True 为默认值)
robot = create_robot()

# 检查连接状态
if robot.is_connected():
print("连接成功!")

# 打印当前状态
robot.print_state()

# 移动到初始位置
robot.set_home()

# 断开连接
robot.disconnect()
else:
print("连接失败,请检查串口")

注意: create_robot() 默认会自动连接(auto_connect=True)。如果不想自动连接,可以设置 auto_connect=False

# 手动控制连接
robot = create_robot(auto_connect=False)
if robot.connect():
# 使用机器人
robot.print_state()
robot.set_home()
robot.disconnect()

手动指定串口:

# Linux
robot = create_robot(port="/dev/ttyACM0")

# Windows
robot = create_robot(port="COM3")

2.4 设置串口权限

在Linux系统上,您需要为USB串口设备配置访问权限。

# 方法1:将用户添加到dialout组(推荐,永久有效)
sudo usermod -a -G dialout $USER
# 注意:需要注销并重新登录以使组权限生效

# 方法2:临时设置串口权限
sudo chmod 666 /dev/ttyACM*

# 方法3:创建udev规则(永久有效)
echo 'KERNEL=="ttyUSB*", MODE="0666"' | sudo tee /etc/udev/rules.d/99-serial.rules
sudo udevadm control --reload-rules
sudo udevadm trigger

2.5 硬件连接与验证

  1. 将机械臂通过USB连接至计算机。
  2. 检查串口是否被系统识别(不同平台有时会将设备识别为 ttyUSB*ttyACM*):
    ls -l  /dev/ttyACM*
  3. 运行版本读取示例以验证连接:
    cd examples
    python3 00_demo_read_version.py
    如果连接成功,终端将显示机械臂的固件版本等信息。

2.6 故障排除

无法连接到机械臂 / 未找到可用串口?
  • 检查硬件:确保USB线已牢固连接且机械臂已上电。
  • 检查权限:确认您的用户有权限访问串口设备。
  • 手动指定端口:如果SDK无法自动找到端口,您可以在启动程序时手动指定:
    python3 00_demo_read_version.py --port /dev/ttyACM0

找不到串口/连接失败

  • 检查 USB 线与电源
  • Linux 用户需确保在 dialout 用户组中:
    sudo usermod -a -G dialout $USER
    # 然后重新登录
  • 运行 00_demo_read_version.py 检测固件版本

权限错误 (Permission denied)

  • 可尝试以 sudo 运行或检查用户串口权限
  • Linux: 确保用户在 dialout 组中
  • 检查串口是否被其他程序占用

固件版本检测失败

  • 多次运行 00_demo_read_version.py
  • 检查串口连接是否稳定

2.7 依赖包说明

主要依赖:

  • pyserial: 串口通信
  • numpy: 数值计算
  • pycrc: CRC校验
  • robocore: 运动学和轨迹规划(自动安装)

3. 示例代码说明

examples/ 目录包含了多个演示脚本,用于展示如何使用 Alicia-D SDK 控制机械臂。所有脚本都支持 --port--baudrate 参数。

3.1 文件结构

examples/
├── 00_demo_read_version.py # 读取版本号
├── 01_torque_switch.py # 扭矩控制
├── 02_demo_zero_calibration.py # 归零校准
├── 03_demo_read_state.py # 读取状态
├── 04_demo_move_gripper.py # 夹爪控制
├── 05_demo_move_joint.py # 关节空间运动
├── 06_demo_forward_kinematics.py # 正向运动学
├── 07_demo_inverse_kinematics.py # 逆向运动学
├── 08_demo_drag_teaching.py # 拖动示教
├── 09_demo_joint_traj.py # 关节空间轨迹规划
├── 10_demo_cartesian_traj.py # 笛卡尔空间轨迹规划
├── 11_demo_sparkvis.py # SparkVis UI 双向同步
├── 12_benchmark_read_joints.py # 关节读取性能测试
└── 13_utmostFPS.py # 最大帧率测试

3.2 主要参数说明

大多数示例脚本共享一套通用的命令行参数,方便您进行配置和调试。

参数数据类型默认值描述
--portstr``指定机械臂连接的串口号,如 /dev/ttyACM0
--gripper_typestr50mm夹爪型号。
附加参数

部分示例脚本还包含特定功能的参数:

  • --format: 角度显示格式,可选 rad(弧度)或 deg(角度),默认为 deg
  • --single: 单次打印状态(仅适用于状态读取脚本)
  • --mode: 拖动示教模式,可选 manualautoreplay_only
  • --save-motion: 动作名称(用于拖动示教功能)
  • --list-motions: 列出所有可用动作(拖动示教功能)
  • --speed_deg_s: 关节运动速度(度/秒),默认 10,范围 5-400
  • --execute: 执行移动到目标位置(逆运动学示例)

3.3 基础功能

00_demo_read_version.py

读取机械臂固件版本号

  • 在使用前务必先运行此脚本检测固件版本

使用方式:

python 00_demo_read_version.py

01_torque_switch.py

切换机械臂所有关节的力矩状态(上电/掉电)

参数说明:

  • --port: 串口端口(可选)

功能说明:

  • 先关力矩后开力矩
  • 关闭扭矩后机械臂可以手动拖动
  • 示教完成后重新开启扭矩

注意事项:

  • 关闭扭矩前请手动托住机械臂以免其突然掉落
  • 示教完成后务必重新开启扭矩

使用方式:

python 01_torque_switch.py

02_demo_zero_calibration.py

将机械臂当前位置设置为新的零点

此操作不可逆,请谨慎使用。

参数说明:

  • --port: 串口端口(可选)

适用场景:

  • 机械臂首次使用或长时间未使用后
  • 关节角度出现偏差时
  • 需要重新建立零点参考时

使用方式:

python 02_demo_zero_calibration.py

03_demo_read_state.py

持续读取并打印机械臂的关节角度、末端姿态和夹爪状态

支持单次或持续打印模式。

参数说明:

  • --port: 串口端口(可选)
  • --robot_version: 机器人版本,默认 v5_6
  • --gripper_type: 夹爪型号,默认 50mm
  • --format: 角度显示格式,可选 rad(弧度)或 deg(角度),默认 deg
  • --single: 单次打印状态,默认持续打印

使用场景:

  • 调试和故障排查
  • 实时监控机械臂状态
  • 验证控制指令执行效果

使用方式:

# 持续打印状态(按 Ctrl+C 停止)
python 03_demo_read_state.py --robot_version v5_6 --gripper_type 50mm

# 单次打印状态
python 03_demo_read_state.py --single

3.4 运动控制

04_demo_move_gripper.py

夹爪控制:控制夹爪张开或闭合到指定角度

夹爪值范围为 0-1000(0为完全闭合,1000为完全张开)。

参数说明:

  • --port: 串口端口(可选)

功能说明:

  • 演示自动执行:完全张开 → 完全闭合 → 半开
  • 使用 set_robot_state(gripper_value=...) 控制夹爪
  • 支持等待夹爪运动完成

使用方式:

python 04_demo_move_gripper.py

05_demo_move_joint.py

使用关节空间运动控制机械臂移动到设定角度

支持度数和弧度输入,自动进行关节角度插值。

参数说明:

  • --port: 串口端口(可选)
  • --speed_deg_s: 关节运动速度(度/秒),默认 10,范围 5-400

功能说明:

  • 演示自动执行:回零 → 移动到目标角度 → 回零
  • 使用统一的关节和夹爪目标接口 set_robot_state()
  • 支持 wait_for_completion=True 等待运动完成

使用方式:

python 05_demo_move_joint.py --speed_deg_s 10


3.5 运动学求解

06_demo_forward_kinematics.py

正运动学求解

根据当前关节角度计算末端执行器的位姿,显示位置、旋转矩阵、欧拉角、四元数等多种表示形式。

参数说明:

  • --port: 串口端口(可选)

功能说明:

  • 使用 RoboCore 库的机器人模型
  • 显示机器人模型信息和运动学链
  • 返回并显示:位置、旋转矩阵、欧拉角(弧度/角度)、四元数、齐次变换矩阵
  • 注意:四元数 q 和 -q 表示相同的旋转

使用方式:

python 06_demo_forward_kinematics.py

07_demo_inverse_kinematics.py

演示逆向运动学求解

根据给定的末端目标位姿,计算并可选地执行关节角度。支持多种IK求解方法和多起点优化。

参数说明:

  • --port: 串口端口(可选)
  • --speed_deg_s: 关节运动速度(度/秒),默认 10
  • --end-pose: 目标位姿(7个浮点数:px py pz qx qy qz qw),默认值已预设
  • --method: IK方法,可选 dls(阻尼最小二乘)、pinv(伪逆)、transpose(雅可比转置),默认 dls
  • --max-iters: 最大迭代次数,默认 100
  • --multi-start: 多起点尝试次数,0表示禁用,建议 5-10
  • --use-random-init: 使用随机初始值(默认使用当前关节角度)
  • --execute: 执行移动到求解的位置

功能说明:

  • 显示详细的求解结果(成功/失败、迭代次数、位置误差、姿态误差)
  • 如果执行移动,会自动返回初始位置
  • 支持多起点优化提高成功率

使用方式:

# 仅计算逆解,不执行动作
python 07_demo_inverse_kinematics.py

# 计算逆解并控制机械臂移动到目标位姿
python 07_demo_inverse_kinematics.py --execute --speed_deg_s 10

# 使用多起点优化提高成功率
python 07_demo_inverse_kinematics.py --execute

3.6 高级应用

08_demo_drag_teaching.py

拖动示教演示

通过手动拖动机械臂来录制一系列轨迹点,并可以回放。支持手动插值、自动快速和仅回放三种模式。

参数说明:

  • --port: 串口端口(可选)
  • --speed_deg_s: 关节运动速度(度/秒),默认 10
  • --mode: 拖动示教模式,可选 manual(手动插值)、auto(自动快速)或 replay_only(仅回放),默认 auto
  • --sample-hz: 自动模式采样频率,默认 300.0 Hz
  • --save-motion: 动作名称(录制模式:新动作名;回放模式:已有动作名)
  • --list-motions: 列出所有可用的动作并退出

功能说明:

  • 关闭扭矩进入示教模式
  • 手动拖动机械臂记录轨迹
  • 支持手动模式(记录关键点)和自动模式(连续采样)
  • 回放记录的轨迹

使用方式:

# 列出所有可用的动作
python 08_demo_drag_teaching.py --list-motions

# 自动模式录制名为 "my_demo" 的轨迹
python 08_demo_drag_teaching.py --mode auto --save-motion my_demo

# 手动模式录制关键点轨迹
python 08_demo_drag_teaching.py --mode manual --save-motion key_points

# 回放已有轨迹 "my_demo"
python 08_demo_drag_teaching.py --mode replay_only --save-motion my_demo

09_demo_joint_traj.py

关节空间轨迹规划与执行

演示如何使用关节空间轨迹规划生成平滑的关节轨迹,并通过多个路径点执行。

参数说明:

  • --port: 串口端口(可选)
  • --gripper_type: 夹爪类型,默认 50mm
  • --base_link: 基座链路名称,默认 base_link
  • --end_link: 末端执行器链路名称,默认 tool0
  • --no-record: 禁用记录模式
  • --save-file: 保存记录的路径点文件路径
  • --waypoints-file: 从JSON文件加载路径点
  • --num-waypoints: 随机生成的路径点数量,默认 6
  • --planner: 规划器类型,可选 b_splinemulti_segment,默认 b_spline
  • --duration: 轨迹持续时间(B-Spline),默认 2.0 秒
  • --num-points: 轨迹点数(B-Spline),默认 800
  • --bspline-degree: B-Spline 度数,可选 3 或 5,默认 5
  • --speed-deg-s: 关节运动速度(度/秒),默认 20
  • --plot: 禁用轨迹可视化

功能说明:

  • 支持手动记录路径点或从文件加载
  • 使用 B-Spline 或 Multi-Segment 规划器生成平滑轨迹
  • 支持夹爪轨迹插值
  • 可视化轨迹(可选)

使用方式:

# 使用默认参数运行
python 09_demo_joint_traj.py

# 从文件加载路径点
python 09_demo_joint_traj.py --waypoints-file waypoints.json

# 使用 Multi-Segment 规划器
python 09_demo_joint_traj.py --planner multi_segment

10_demo_cartesian_traj.py

笛卡尔空间轨迹规划与执行

演示如何使用笛卡尔空间样条轨迹规划生成平滑的末端执行器轨迹,并通过逆运动学求解执行。

参数说明:

  • --port: 串口端口(可选)
  • --gripper_type: 夹爪类型,默认 50mm
  • --base_link: 基座链路名称,默认 base_link
  • --end_link: 末端执行器链路名称,默认 tool0
  • --no-record: 禁用记录模式
  • --save-file: 保存记录的路径点文件路径
  • --waypoints-file: 从JSON文件加载路径点
  • --num-waypoints: 随机生成的路径点数量,默认 2
  • --duration: 轨迹持续时间(秒),默认 1.0
  • --num-points: 轨迹点数,默认 10
  • --method: IK方法,可选 dlspinvtranspose,默认 dls
  • --max-iters: 最大IK迭代次数,默认 100
  • --pos-tol: 位置容差(米),默认 1e-2
  • --ori-tol: 姿态容差(弧度),默认 1e-2
  • --num-inits: 初始猜测数量,默认 5
  • --init-strategy: 初始猜测策略,默认 current
  • --speed-deg-s: 关节运动速度(度/秒),默认 20
  • --plot: 禁用轨迹可视化

功能说明:

  • 支持手动记录笛卡尔路径点或从文件加载
  • 使用样条曲线生成平滑的笛卡尔轨迹
  • 批量求解逆运动学(确保连续性)
  • 验证路径点是否被准确通过
  • 可视化轨迹和IK结果(可选)

使用方式:

# 使用默认参数运行
python 10_demo_cartesian_traj.py

# 从文件加载路径点
python 10_demo_cartesian_traj.py --waypoints-file cartesian_waypoints.json

# 增加轨迹点数以提高平滑度
python 10_demo_cartesian_traj.py --num-points 100

12_benchmark_read_joints.py

关节读取性能测试

测试关节角度读取的API调用频率和实际数据更新频率。

参数说明:

  • --port: 串口端口(可选)
  • --gripper_type: 夹爪类型,默认 50mm
  • --duration: 测试持续时间(秒),默认 5.0
  • --fast: 启用快速模式(设置更新间隔为1ms)

功能说明:

  • 测试API读取频率(从Python内存读取缓存数据的速度)
  • 测试数据更新频率(从机器人实际接收新数据的速率)
  • 显示串口统计信息(处理的帧数、丢弃的帧数等)

使用方式:

# 基本测试(5秒)
python 12_benchmark_read_joints.py

# 快速模式测试
python 12_benchmark_read_joints.py --fast --duration 10

13_utmostFPS.py

最大帧率测试

测试串口通信的最大发送和接收帧率。

功能说明:

  • 测试串口通信的极限性能
  • 显示发送帧率、接收帧率和同步率
  • 适用于性能优化和硬件测试

注意: 此脚本包含硬编码的串口路径,需要根据实际环境修改。


3.7 常见参数调整场景

运动控制参数调整:

新固件(6.1.0及以上)

  • 速度过快:降低 speed_deg_s(范围:5-400度/秒)
  • 运动不流畅:增加 num_points(轨迹插值点数)
  • 移动时间过长:减少 move_duration(每个路径点的移动时间)

IK 求解参数调整:

  • 求解失败:尝试不同 methoddlspinvtranspose),增加 multi_start(建议 5-10)
  • 局部最优:使用 use_random_init=True 或增加 multi_start
  • 精度要求高:降低 tolerance 到 1e-5 或更小,增加 max_iters
  • 速度要求高:使用 method='pinv'method='transpose'

拖动示教参数调整:

  • 采样频率:调整 --sample-hz(默认 300.0 Hz),更高频率记录更详细但文件更大
  • 模式选择manual 模式适合记录关键点,auto 模式适合连续轨迹

4. API 参考文档

本节介绍 Alicia-D SDK 的核心类与方法接口。

4.1 初始化接口:create_robot

from alicia_d_sdk import create_robot

robot = create_robot(
port="", # 串口(留空自动查找)
gripper_type=None, # 夹爪类型("50mm" 或 "100mm"),None 时从缓存文件读取或默认 "50mm"
debug_mode=False, # 调试模式
auto_connect=True, # 自动连接
base_link="base_link", # 基座链路名称
end_link="tool0" # 末端执行器链路名称
)

4.2 控制接口:SynriaRobotAPI

from alicia_d_sdk import create_robot

robot = create_robot()

连接管理:

  • connect()
    连接机械臂并检测固件版本

  • disconnect()
    断开机械臂连接并停止更新线程

  • is_connected()
    检查机械臂是否连接

运动控制:

  • set_home(speed_deg_s=10)
    移动机械臂到初始位置

  • set_robot_state(target_joints=None, gripper_value=None, joint_format='rad', speed_deg_s=10, tolerance=0.1, timeout=10.0, wait_for_completion=True)
    统一的关节和夹爪目标设置接口,支持同时设置关节角度和夹爪位置

    参数:

    • target_joints: 可选的目标关节角度列表(弧度或度数)。如果为 None,保持当前角度
    • gripper_value: 可选的夹爪值(0-1000,0为完全闭合,1000为完全张开)。如果为 None,保持当前值
    • joint_format: 关节角度单位格式,'rad'(弧度)或 'deg'(度数),默认 'rad'
    • speed_deg_s: 关节运动速度(度/秒),范围 0-360,默认 10
    • tolerance: 关节目标容差(弧度),默认 0.1
    • timeout: 最大等待时间(秒),默认 10.0
    • wait_for_completion: 如果为 True,等待到达目标位置,默认 True

    返回值: 成功返回 True,失败返回 False

  • set_pose(target_pose, backend='numpy', method='dls', display=True, tolerance=1e-4, max_iters=100, multi_start=0, use_random_init=False, speed_deg_s=10, execute=True)
    使用逆运动学移动末端执行器到目标位姿

    参数:

    • target_pose: 目标位姿,格式为 [x, y, z, qx, qy, qz, qw](位置 + 四元数)
    • backend: 计算后端,'numpy' 或 'torch',默认 'numpy'
    • method: IK 求解方法,'dls'(阻尼最小二乘)、'pinv'(伪逆)或 'transpose'(转置),默认 'dls'
    • display: 是否显示求解详情,默认 True
    • tolerance: 位置和姿态容差,默认 1e-4
    • max_iters: 最大迭代次数,默认 100
    • multi_start: 多起点尝试次数,0 表示禁用,默认 0
    • use_random_init: 是否使用随机初始猜测,默认 False(使用当前关节角度)
    • speed_deg_s: 运动速度(度/秒),默认 10
    • execute: 如果为 True,执行运动,默认 True

    返回值: 包含 success, q, iters, pos_err, ori_err, message 的字典

轨迹规划:

  • plan_joint_trajectory(waypoints, planner_type='b_spline', duration=None, num_points=800, ...)
    规划关节空间轨迹,支持 B-Spline 和多段轨迹规划器

  • plan_cartesian_trajectory(waypoints, duration=None, num_points=100, backend='numpy')
    规划笛卡尔空间样条轨迹

  • solve_ik_for_trajectory(target_poses, q_init=None, method='dls', ...)
    为一系列笛卡尔位姿批量求解逆运动学

状态获取:

  • get_robot_state(info_type="joint_gripper", timeout=1.0)
    统一的机器人状态获取接口,根据 info_type 返回不同类型的数据:

    参数:

    • info_type: 信息类型,可选值:
      • "joint_gripper": 返回 JointState 对象(默认),包含:
        • angles: 六个关节角度列表(弧度)
        • gripper: 夹爪开合度(0-1000,0为完全闭合,1000为完全张开)
        • timestamp: 时间戳(秒)
        • run_status_text: 运行状态文本("idle", "locked", "sync", "sync_locked", "overheat", "overheat_protect", "unknown")
      • "joint": 仅返回关节角度列表 List[float](弧度)
      • "gripper": 仅返回夹爪值 float(0-1000)
      • "version": 返回版本信息字典,包含 serial_number, hardware_version, firmware_version
      • "temperature": 返回舵机温度列表 List[float](摄氏度)
      • "velocity": 返回舵机速度列表 List[float](度/秒)
      • "self_check": 返回自检状态字典,包含 raw_mask, bits, timestamp
      • "gripper_type": 返回夹爪类型字符串(如 "50mm" 或 "100mm"),失败时返回 None
    • timeout: 最大等待时间(秒),默认 1.0

    返回值: 根据 info_type 返回相应类型的数据,失败返回 None

  • get_pose()
    获取当前末端执行器位置与姿态,返回字典包含 transform, position, rotation, euler_xyz, quaternion_xyzw

  • print_state(continuous=False, output_format='deg')
    打印当前机械臂信息,可持续打印,支持角度/弧度格式。包含关节角度、夹爪状态、末端位姿、温度、速度等信息

夹爪控制:

  • set_robot_state(gripper_value=...)
    通过统一接口控制夹爪,gripper_value 范围 0-1000(0为完全闭合,1000为完全张开)

    示例:

    # 打开夹爪
    robot.set_robot_state(gripper_value=1000)

    # 关闭夹爪
    robot.set_robot_state(gripper_value=0)

    # 同时设置关节和夹爪
    robot.set_robot_state(target_joints=[0.1, 0.2, 0.3, 0.4, 0.5, 0.6], gripper_value=500)

系统控制:

  • torque_control(command)
    启用或关闭扭矩('on' 或 'off')

  • zero_calibration()
    执行归零校准流程:关闭扭矩 → 手动拖动 → 重启扭矩 → 记录零点


4.3 RoboCore 集成

SDK 集成了 RoboCore 库,提供高性能运动学和轨迹规划功能:

运动学功能(来自 robocore.kinematics):

  • forward_kinematics(robot_model, q, backend='numpy', return_end=True)
  • inverse_kinematics(robot_model, pose, q_init, backend='numpy', method='dls', ...)
  • jacobian(robot_model, q, backend='numpy', method='analytic')