Skip to main content

云擎操作臂Python SDK

1. 介绍

Alicia-M SDK 是一套用于控制 云擎 Alicia-M 系列六轴机械臂(含夹爪)的 Python 开发工具包。该 SDK 基于玄雅自研的 RoboCore 机器人核心库构建,支持通过串口通信实现对机械臂的精确运动控制、夹爪操作,以及机械臂姿态与运行状态等关键数据的实时读取。

1.1 主要特性

核心能力
  • 关节控制:支持设置与读取六个关节的角度,提供平滑插值执行。
  • 多种控制模式:支持 PV(位置-速度)和 MIT(阻抗控制)两种模式,并可动态切换。
  • 逐电机 MIT 参数:支持为每个电机独立设置 kp、kd、torque、vel_ref 阻抗参数。
  • 末端轨迹:支持笛卡尔空间末端姿态轨迹规划。
  • 夹爪控制:夹爪电机(M6)固件锁定 MIT 模式,PV 和 MIT 模式下均可控制。
  • 失能/使能:支持电机力矩的关闭与恢复,实现自由拖动。
  • 状态读取:实时获取关节角、夹爪角、速度、力矩、温度与末端姿态。
  • 自动串口连接:自动搜索串口或手动指定。
  • 遥操作:支持 Alicia-D 示教臂到 Alicia-M 操作臂的实时遥操作,含 URDF 限位映射。
  • 零位标定:支持将当前位置设置为新的零点。
  • 日志系统:支持日志级别过滤,可控制控制台输出详细程度。

2. 安装与配置

2.1 环境要求

  • Python 3.10 及以上版本
  • 支持串口的计算机(USB 转串口芯片已内置于机械臂)

2.2 安装步骤

获取代码及配套 examples 例程:

git clone https://github.com/Synria-Robotics/Alicia-M-SDK.git
cd Alicia-M-SDK

创建 Python 环境(推荐使用 conda):

conda create -n msdk python=3.10
conda activate msdk

方法一:从源码安装(推荐)

pip install -e .

方法二:从 PyPI 安装

pip install alicia_m_sdk

2.3 快速开始

基本使用示例:

import alicia_m_sdk

# 创建机器人实例(自动搜索串口并连接)
robot = alicia_m_sdk.create_robot()

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

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

# 回到初始位置
robot.go_home(speed=40)

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

create_robot() 默认会自动连接机械臂(auto_connect=True)。您也可以通过参数手动指定串口或调整连接行为。

手动指定串口:

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

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

2.4 设置串口权限

在 Linux 系统上,您需要为 USB 串口设备配置访问权限(Windows 和 macOS 用户可略过该步骤)。

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

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

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

2.5 硬件连接与验证

将机械臂通过 USB 连接至计算机。

检查串口是否被系统识别(不同平台下设备名称可能为 COM*ttyUSB*ttyACM*):

  • Linux: ls -l /dev/ttyUSB* /dev/ttyACM*
  • macOS: ls /dev/cu.*
  • Windows: 查看设备管理器

运行版本读取示例以验证连接:

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数值计算
pycrcCRC 校验
robocore运动学和轨迹规划(自动安装)

3. 示例文件说明

examples/ 目录包含了多个演示脚本,用于展示如何使用 Alicia-M SDK 控制机械臂。

3.1 文件结构

examples/
├── 00_demo_read_version.py # 读取版本号
├── 01_demo_diagnostic.py # 自检功能(待开发)
├── 02_demo_read_status.py # 读取模式与使能状态
├── 03_demo_read_states.py # 循环读取关节状态
├── 04_demo_switch_mode.py # 切换控制模式 (PV ↔ MIT)
├── 05_demo_disable_enable.py # 失能/使能交互
├── 06_demo_move_gripper.py # 夹爪控制
├── 07_demo_move_joint.py # 关节空间运动 (PV)
├── 08_demo_move_full_arm.py # 关节+夹爪协同控制 (PV)
├── 09_demo_move_joint_mit.py # 关节空间运动 (MIT)
├── 10_demo_move_full_arm_mit.py # 关节+夹爪协同控制 (MIT)
├── 11_demo_forward_kinematics.py # 正向运动学
├── 12_demo_inverse_kinematics.py # 逆向运动学
├── 13_demo_teleop.py # 遥操作 (Alicia-D → Alicia-M)
├── 14_demo_reset_zero.py # 零位标定
├── 15_demo_teleop_mapped.py # 遥操作 (带 URDF 限位映射)
└── joint_mapping.py # URDF 关节映射工具库

3.2 主要参数说明

大多数示例脚本通过 create_robot() 进行连接,不需要额外的命令行参数。部分脚本支持以下参数:

参数数据类型默认值描述
--speedfloat15 / 30关节运动速度,范围 0-400(PV 示例默认 15,MIT 示例默认 30)
附加说明
  • 所有示例脚本支持在代码中手动指定 port 参数来连接指定串口
  • 夹爪值范围为 0-1000(0 为完全闭合,1000 为完全张开)
  • 关节角度支持度数(deg)和弧度(rad)两种格式
  • 夹爪电机 M6 固件锁定 MIT 模式,无须切换关节控制模式即可控制

3.3 基础功能

00_demo_read_version.py

读取机械臂固件版本号

连接机械臂后,读取并显示固件版本信息,包括序列号、硬件版本、固件版本、产品类别和设备类型。

功能说明:

  • 使用 get_robot_state("version") 查询版本信息
  • 显示完整的设备标识信息
  • 可用于验证连接是否正常

使用方式:

python 00_demo_read_version.py

01_demo_diagnostic.py

自检功能

待开发

底层自检功能尚未更新,当前以占位形式实现。预留接口为 robot.get_robot_state('self_check')

演示自检功能的调用方式。调用 get_robot_state("self_check") 查询各关节电机健康状态。

使用方式:

python 01_demo_diagnostic.py

02_demo_read_status.py

读取机械臂模式与使能状态

查询并显示各电机的控制模式和运行状态。

功能说明:

  • 通过 get_robot_state("control_mode") 查询各电机(M0-M5 和夹爪)的控制模式
  • 通过 get_robot_state("status") 查询运行状态,包括:
    • 关节锁定状态
    • 双臂同步状态
    • 电机错误状态
    • 夹爪力矩锁定状态

使用方式:

python 02_demo_read_status.py

03_demo_read_states.py

循环读取关节状态

持续读取并打印机械臂的全部状态信息,约 5Hz 刷新频率,按 Ctrl+C 退出。

参数说明:

参数数据类型默认值描述
--extendflag-启用扩展查询(需新固件支持)

功能说明:

  • 使用 get_robot_state("all") 获取完整的 JointState 对象
  • 基础状态(默认显示):
    • 关节角度(度数和弧度)
    • 夹爪开合度(0-1000)
    • 关节速度(rad/s)
    • 关节力矩(N·m)
  • 扩展状态(使用 --extend 参数后额外显示,需新固件支持):
    • 位置环增益 Kp
    • 速度环增益 Kd
    • 插补速度(rad/s)
    • 线圈温度(°C)
  • 使用 --extend 参数时,SDK 内部调用 robot.set_extended_polling(True) 将轮询地址从 3 个(pos/vel/torque)扩展到 7 个(pos/vel/torque/kp/kd/linear_vel/temperature)
  • 适用于调试、故障排查和实时状态监控

使用方式:

# 基础状态循环打印(按 Ctrl+C 停止)
python 03_demo_read_states.py

# 启用扩展查询(含 Kp、Kd、插补速度、线圈温度)
python 03_demo_read_states.py --extend

04_demo_switch_mode.py

切换控制模式 (PV ↔ MIT)

演示 PV 和 MIT 模式之间的动态切换。仅切换关节电机 M0-M5 的模式,夹爪电机 M6 固件锁定 MIT 模式不受影响。连接后自动检测当前模式,按 Enter 切换到另一种模式,再按 Enter 切回。

功能说明:

  • 使用 robot.switch_mode("mit")robot.switch_mode("pv") 切换模式
  • 自动检测固件当前控制模式
  • 交互式操作,需用户按 Enter 确认后执行切换
  • 切换安全序列:失能 → 切换模式 → 使能 → 固件初始化目标位置为当前位置

注意事项:

  • 模式切换瞬间固件会短暂失能再使能,机械臂会因重力瞬间下坠
  • 切换到 MIT 后关节可自由活动(无力矩锁定)
  • 切回 PV 后关节在当前位置重新锁定
  • 切换前请确保机械臂周围安全,并用手扶住机械臂

使用方式:

python 04_demo_switch_mode.py

05_demo_disable_enable.py

失能/使能交互

演示失能(卸载力矩,电机自由)和重新使能的流程。使能时会在当前位置恢复控制,确保不突跳到旧位置。

功能说明:

  • 使用 robot.disable_robot() 失能电机,关节可自由拖动
  • 使用 robot.enable_robot() 在当前位置重新使能,无突跳
  • 失能前后分别打印关节角度,方便对比

注意事项:

  • 失能前请用手扶住机械臂,防止突然掉落
  • 失能后可手动拖动机械臂到新位置
  • 使能后机械臂在新位置恢复锁定

使用方式:

python 05_demo_disable_enable.py

3.4 运动控制 (PV 模式)

06_demo_move_gripper.py

夹爪控制

演示夹爪的打开、关闭和半开操作。夹爪电机 M6 固件锁定 MIT 模式,无须切换关节控制模式,PV 和 MIT 下均可运行。MIT 阻抗参数列表的第 7 个元素(索引 6)对应夹爪电机,关节部分保持当前位置不动。

功能说明:

  • 使用 set_robot_state(gripper_value=...) 控制夹爪
  • 传入逐电机 MIT 阻抗参数(7 元素列表:M0-M5 关节 + M6 夹爪):
    MIT_KP = [150.0, 150.0, 150.0, 150.0, 150.0, 150.0, 150.0]
    MIT_KD = [2.0, 2.0, 2.0, 2.0, 2.0, 2.0, 2.0]
    MIT_TORQUE = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
    MIT_VEL_REF = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
  • 演示自动执行序列:半开 (500) → 全开 (1000) → 半开 (500) → 全闭 (0)
  • 支持 wait_for_completion=True 等待夹爪运动完成
  • 结束后读取并打印当前夹爪值

使用方式:

python 06_demo_move_gripper.py

07_demo_move_joint.py

关节空间运动控制 (PV 模式)

使用 PV 模式控制机械臂在关节空间中移动到设定角度。若当前不在 PV 模式,将提示用户确认后自动切换。

参数说明:

参数数据类型默认值描述
--speedfloat15运动速度,范围 0-400

功能说明:

  • 连接后检测当前模式,若非 PV 则提示切换
  • 演示自动执行序列:回零位 → 移动到目标位置 [90, -90, -90, 90, 0, 0] (deg) → 回零位
  • 使用 robot.go_home(speed=...) 回零
  • 使用 robot.set_robot_state(target_joints=..., joint_format="deg") 控制关节
  • 支持 wait_for_completion=True 等待运动完成

使用方式:

# 使用默认速度
python 07_demo_move_joint.py

# 指定运动速度
python 07_demo_move_joint.py --speed 10

08_demo_move_full_arm.py

关节+夹爪协同控制 (PV 模式)

演示关节与夹爪的独立控制及协同控制。若当前不在 PV 模式,将提示用户确认后自动切换。

功能说明:

  • 初始化:回零位 + 夹爪全开 (1000),speed=15gripper_speed=100
  • 演示 1:仅控制关节移动到 POSE_A = [90, -90, -90, 90, 0, 0],夹爪保持不变(gripper_value=None
  • 演示 2:仅控制夹爪关闭 (0),关节保持不变(target_joints=None
  • 演示 3:同时控制关节移动到 POSE_B = [0, -30, -60, 45, 0, 45] 并打开夹爪 (1000)
  • 回零:回零位 + 夹爪闭合

使用方式:

python 08_demo_move_full_arm.py

3.5 运动控制 (MIT 模式)

MIT 模式使用阻抗控制律:tau = kp * (pos_ref - pos_cur) + kd * (vel_ref - vel_cur) + t_ref,支持为每个电机(M0-M5 关节 + M6 夹爪)独立设置阻抗参数。

09_demo_move_joint_mit.py

关节空间运动控制 (MIT 模式)

演示 MIT 模式下关节空间运动控制,展示逐电机 MIT 阻抗参数的设置方式。若当前不在 MIT 模式,将提示用户确认后自动切换。

参数说明:

参数数据类型默认值描述
--speedfloat30运动速度,范围 0-400

功能说明:

  • 演示自动执行序列:回零位 → 移动到目标位置 [90, -90, -90, 90, 0, 0] (deg) → 回零位
  • 使用逐电机 MIT 阻抗参数(7 元素列表:M0-M5 关节 + M6 夹爪):
    robot.set_robot_state(
    target_joints=POSITION,
    joint_format="deg",
    speed=args.speed,
    wait_for_completion=True,
    kp=[150.0, 150.0, 150.0, 150.0, 150.0, 150.0, 150.0],
    kd=[2.0, 2.0, 2.0, 2.0, 2.0, 2.0, 2.0],
    torque=[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
    vel_ref=[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
    )

使用方式:

# 使用默认速度
python 09_demo_move_joint_mit.py

# 指定运动速度
python 09_demo_move_joint_mit.py --speed 20

10_demo_move_full_arm_mit.py

关节+夹爪协同控制 (MIT 模式)

演示 MIT 模式下关节与夹爪的独立控制及协同控制,展示逐电机 MIT 阻抗参数的设置方式。若当前不在 MIT 模式,将提示用户确认后自动切换。

功能说明:

  • 初始化:回零位 + 夹爪全开 (1000),speed=30gripper_speed=100
  • 演示 1:仅控制关节移动到 POSE_A = [90, -90, -90, 90, 0, 0],夹爪保持不变(gripper_value=None
  • 演示 2:仅控制夹爪关闭 (0),关节保持不变(target_joints=None
  • 演示 3:同时控制关节移动到 POSE_B = [0, -30, -60, 45, 0, 45] 并打开夹爪 (1000)
  • 回零:回零位 + 夹爪闭合
  • 所有操作均携带逐电机 MIT 参数(7 元素列表:kp=[150]*7kd=[2.0]*7torque=[0]*7vel_ref=[0]*7

使用方式:

python 10_demo_move_full_arm_mit.py

3.6 运动学求解

11_demo_forward_kinematics.py

正运动学求解

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

功能说明:

  • 当前位姿计算:读取当前关节角度 → 调用 forward_kinematics() → 打印末端位姿
  • 预设角度计算:使用预设关节角度 [90, 0, 0, 0, 0, 0] (deg) → 计算 FK → 打印末端位姿
  • 使用 from alicia_m_sdk import forward_kinematics, RobotModel(底层由 RoboCore 提供)
  • 返回并显示:位置 (m)、欧拉角 XYZ(弧度/角度)、四元数 (xyzw)、旋转矩阵

代码示例:

from alicia_m_sdk import forward_kinematics, RobotModel

robot_model = robot.robot_model
joints_rad = robot.get_robot_state("joint")
T_fk = forward_kinematics(robot_model, joints_rad, return_end=True)

使用方式:

python 11_demo_forward_kinematics.py

12_demo_inverse_kinematics.py

逆运动学求解

根据给定的末端目标位姿,计算关节角度,并可选执行运动。若当前不在 PV 模式,将提示用户确认后自动切换。

功能说明:

  • 当前位姿验证:读取当前末端位姿 → 以当前关节角度为初始猜测求解 IK → 验证 IK 精度
    • IK 参数:method='dls'max_iters=1000pos_tol=1e-2ori_tol=1e-2num_initial_guesses=5
  • 目标位姿求解:给定目标位姿 [0.20, 0, 0.22] + 四元数 [0, 0.707, 0, 0.707] → 使用多起点随机策略求解 IK
    • IK 参数:method='dls'max_iters=500num_initial_guesses=10initial_guess_strategy='random'
  • 显示详细的求解结果:成功/失败、位置误差、姿态误差、计算耗时
  • 求解成功后可交互式选择是否执行运动(输入 y + Enter,以 speed=7 执行)
  • 使用 from alicia_m_sdk import forward_kinematics, inverse_kinematics, RobotModel

代码示例:

from alicia_m_sdk import inverse_kinematics

ik_result = inverse_kinematics(
robot_model, T_target, q_init,
method='dls',
max_iters=500,
pos_tol=1e-2,
ori_tol=1e-2,
num_initial_guesses=10,
initial_guess_strategy='random',
use_analytic_jacobian=True,
)

使用方式:

python 12_demo_inverse_kinematics.py

3.7 高级应用

13_demo_teleop.py

遥操作:Alicia-D (示教臂) → Alicia-M (操作臂)

使用 Alicia-D 伺服示教臂实时控制 Alicia-M 电机操作臂,支持 PV 模式和 MIT 模式(默认 MIT)。MIT 模式支持逐电机设置阻抗参数。

参数说明:

参数数据类型默认值描述
--modestrmit控制模式,可选 pv / mit
--leader-portstr/dev/ttyACM0Leader 串口(Alicia-D 示教臂)
--follower-portstr/dev/ttyACM1Follower 串口(Alicia-M 操作臂)
--follower-versionstrv1_1Alicia-M 硬件版本,可选 v1_0 / v1_1
--frequencyfloat100控制循环频率,范围 10-200 Hz
--speedfloat400Follower 运动速度(0-400,映射到 0-10 rad/s,PV/MIT 均生效)
--homeflag-启动前 Follower 先回零(默认跳过)
--verbose / -vflag-打印遥操作过程中的关节状态

功能说明:

  1. 分别连接 Leader(Alicia-D 示教臂)和 Follower(Alicia-M 操作臂,显式指定 control_aim="follower" 防止端口接反)
  2. 可通过 --home 让 Follower 先回零位(默认跳过回零)
  3. 自动检测并切换到目标控制模式(PV 或 MIT)
  4. 创建 Teleoperation 控制器,使用简单的关节符号翻转映射(joint_signs=[1, 1, -1, -1, 1, -1]
  5. 按 Enter 开始遥操作,拖动 Leader 实时控制 Follower
  6. 按 Ctrl+C 停止

关键代码:

from alicia_m_sdk.control.teleoperation import Teleoperation

teleop = Teleoperation(
leader=leader,
follower=follower,
frequency_hz=100.0,
follower_speed=400.0,
joint_signs=[1.0, 1.0, -1.0, -1.0, 1.0, -1.0],
kp=[150.0]*7, kd=[2.0]*7, torque=[0.0]*7, vel_ref=[0.0]*7,
)
teleop.run_interactive()

注意事项:

caution
  • 本示例使用简单的关节符号翻转映射,要求示教臂零点与操作臂零点一致。 使用前请先通过灵动 SDK 将示教臂的零点调整至与云擎操作臂零点相似的位置。如不想手动校准零点,请使用 15_demo_teleop_mapped.py(URDF 限位映射版本),该版本使用出厂设置/标准零点即可工作。
  • 启动遥操作前确保云擎和灵动都处于零点位置。
  • 遥操启动前手握灵动示教臂,可适当微微上抬,保持该姿势直到进入遥操状态。
  • 若需停止遥操,请先控制云擎到零点位置附近,在终端按 Ctrl+C 终止程序。
  • 确保工作空间安全,遥操过程中避免云擎碰撞。

使用方式:

# MIT 模式遥操作(默认)
python 13_demo_teleop.py

# PV 模式遥操作
python 13_demo_teleop.py --mode pv

# 指定串口
python 13_demo_teleop.py --leader-port /dev/ttyACM0 --follower-port /dev/ttyACM1

# 启动前回零
python 13_demo_teleop.py --home

# 调整频率和速度
python 13_demo_teleop.py --frequency 100 --speed 300

# 打印遥操过程中的关节状态(每秒一次)
python 13_demo_teleop.py --verbose

14_demo_reset_zero.py

零位标定

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

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

功能说明:

  1. 连接机械臂
  2. 提示用户通过机械臂按键切换到 MIT 模式(非重力补偿)
  3. 用户手动将机械臂各关节移动到期望的零点位置,确保夹爪完全闭合
  4. 用户通过机械臂按键切换回 PV 模式
  5. 按 Enter 确认后,SDK 发送零位标定指令(set_zero_position()

适用场景:

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

使用方式:

python 14_demo_reset_zero.py

15_demo_teleop_mapped.py

遥操作(带 URDF 限位映射):Alicia-D → Alicia-M

13_demo_teleop.py 功能相同,但使用 joint_mapping.py 中的 URDF 限位映射代替简单的符号翻转,提供更安全、更精确的关节映射。通过 Teleoperationjoint_mapper 参数传入自定义映射函数。

推荐用于日常遥操作

13_demo_teleop.py 不同,本示例无须手动校准示教臂零点,使用出厂设置或标准零点即可正常工作。URDF 映射会自动将 D 零位对齐到 M 的关节区间中点,并裁剪输出到安全限位范围内。

映射规则:

  • D 零位(0°)对齐到 M 的关节区间中点
  • 1:1 角度映射(M 的 1° = D 的 1°,不缩放)
  • 关节 3(下标 2)特殊处理:先取负,再按 D[-126°, 34.3°] → M[-179.9°, 0°] 做比例缩放
  • 关节 4、6(下标 3、5)方向翻转
  • 所有关节输出裁剪到 M 的 URDF 限位范围

URDF 限位对照:

关节Alicia-D 范围 (°)Alicia-M 范围 (°)映射方式
J1[-157.5, 157.5][-157.5, 157.5]1:1 + 中点对齐
J2[-100.2, 100.2][-179.9, 0]1:1 + 中点对齐
J3[-34.3, 126.0][-179.9, 0]取负 + 比例缩放
J4[-159.8, 159.8][-89.9, 89.9]反向 + 中点对齐
J5[-89.9, 89.9][-89.9, 89.9]1:1 + 中点对齐
J6[-179.9, 179.9][-157.5, 157.5]反向 + 中点对齐

关键代码:

from joint_mapping import convert_joints_deg_from_alicia_d_to_alicia_m

def make_joint_mapper_rad():
def mapper(leader_joints_rad):
leader_deg = [math.degrees(r) for r in leader_joints_rad]
follower_deg = convert_joints_deg_from_alicia_d_to_alicia_m(leader_deg)
return [math.radians(d) for d in follower_deg]
return mapper

teleop = Teleoperation(
leader=leader, follower=follower,
joint_mapper=make_joint_mapper_rad(), # 代替 joint_signs
...
)

参数说明:

13_demo_teleop.py 参数一致(--mode--leader-port--follower-port--follower-version--frequency--speed--home--verbose)。

注意事项:

caution
  • 启动遥操作前确保云擎和灵动都处于零点位置(使用出厂设置或标准零点即可,无须额外校准)。
  • 遥操启动前手握灵动示教臂,可适当微微上抬,保持该姿势直到进入遥操状态。
  • 若需停止遥操,请先控制云擎到零点位置附近,在终端按 Ctrl+C 终止程序。
  • 确保工作空间安全,遥操过程中避免云擎碰撞。
  • 详细指南参考【双臂遥操作-安装与使用指南】一节

使用方式:

# MIT 模式(默认)
python 15_demo_teleop_mapped.py

# PV 模式
python 15_demo_teleop_mapped.py --mode pv

# 指定串口
python 15_demo_teleop_mapped.py --leader-port /dev/ttyACM0 --follower-port /dev/ttyACM1

# 打印映射前后关节对比
python 15_demo_teleop_mapped.py --verbose

3.8 常见参数调整场景

运动控制参数调整:

  • 速度过快:降低 speed(范围:0-400)
  • 运动不流畅:增加轨迹插值点数
  • 移动时间过长:减少 duration(轨迹持续时间)

MIT 阻抗参数调整:

  • 关节太软/跟踪不紧:增大 kp(位置增益,范围 0-500)
  • 关节振荡/抖动:增大 kd(速度增益,范围 0-5)或减小 kp
  • 需要前馈力矩补偿:设置 torque 参数(N·m)

IK 求解参数调整:

  • 求解失败:尝试不同 methoddlspinvtranspose),增加 num_initial_guesses(建议 5-10)
  • 局部最优:使用 initial_guess_strategy='random' 或增加 num_initial_guesses
  • 精度要求高:降低 pos_tol/ori_tol1e-5 或更小,增加 max_iters

4. API 参考文档

4.1 初始化接口:create_robot

import alicia_m_sdk

robot = alicia_m_sdk.create_robot(
port="", # 串口(留空自动查找)
version="v1_1", # 机械臂硬件版本 ("v1_0", "v1_1")
variant=None, # 变体标识(None=自动检测)
control_aim=None, # 控制目标 ("leader"/"follower"/None=自动检测)
control_mode=None, # 控制模式 ("pv"/"mit"/None=检测固件当前模式)
baudrate=1_000_000, # 串口波特率
backend="numpy", # RoboCore 计算后端 ("numpy"/"torch")
debug_mode=False, # 调试模式
auto_connect=True, # 是否自动连接
extended_polling=False, # 扩展轮询(查询 kp/kd/linear_vels/temperatures)
)

4.2 核心方法

连接管理:

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

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

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

运动控制:

  • go_home(speed=40, gripper_speed=100) 移动机械臂到初始位置

  • set_robot_state(target_joints=None, gripper_value=None, joint_format='deg', speed=40, gripper_speed=100, wait_for_completion=True, use_interpolation=True, kp=None, kd=None, torque=None, vel_ref=None) 统一的关节和夹爪目标设置接口。自动根据当前控制模式(PV/MIT)选择对应实现。

    参数:

    • target_joints: 目标关节角度列表(6 个关节),None 时保持当前角度
    • gripper_value: 夹爪值(0-1000),None 时保持当前值
    • joint_format: 角度单位,'deg'(度数)或 'rad'(弧度),默认 'deg'
    • speed: 运动速度(0-400),默认 40
    • gripper_speed: 夹爪速度(0-400),默认 100
    • wait_for_completion: 是否等待到达目标位置,默认 True
    • use_interpolation: MIT 模式下是否使用线性轨迹插值,默认 True
    • kp: 位置增益(0-500),支持 float(广播到所有电机)或 List[7](逐电机设置),None 使用默认值 150
    • kd: 速度增益(0-5),支持 float 或 List[7],None 使用默认值 2.0
    • torque: 前馈力矩(N·m),支持 float 或 List[7],None 使用默认值 0
    • vel_ref: 参考速度(rad/s),支持 float 或 List[7],None 使用默认值 0

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

  • set_pose(target_pose, method='dls', execute=True, speed=7, **ik_params) 通过逆运动学移动末端执行器到目标位姿

    参数:

    • target_pose: 目标位姿(4x4 矩阵或 [x, y, z, qx, qy, qz, qw]
    • method: IK 方法,'dls'/'pinv'/'transpose',默认 'dls'
    • execute: 是否执行运动,默认 True
    • speed: 运动速度,默认 7

    返回值: IK 结果字典

模式与使能控制:

  • switch_mode(mode) 切换控制模式,mode"pv""mit"

  • enable_robot() 使能机器人(含安全序列防止突跳)

  • disable_robot() 失能机器人(卸载力矩,电机自由)

  • torque_control(command, timeout=1.0) 启用或关闭扭矩,command'on''off'

  • set_zero_position() 将当前位姿设置为零位

MIT 专用接口:

  • send_mit_command(joint_params, gripper=None) MIT 全参数直接发送(低延迟)。每帧发送 6 地址 MIT 帧(pos+vel+torque+kp+kd+linear_vel),调用方需自行维持高频发送(≥200Hz)。

    参数:

    • joint_params: 7 个 MitParams 对象的列表,每个包含 pos_ref(rad)、vel_ref(rad/s)、t_ref(N·m)、kp(0-500)、kd(0-5)
    • gripper: 夹爪目标值(0-1000),None 时保持当前值

轨迹规划与执行:

  • plan_joint_trajectory(waypoints, planner_type='b_spline', **kwargs) 规划关节空间轨迹

  • plan_cartesian_trajectory(waypoints, **kwargs) 规划笛卡尔空间轨迹

  • move_joint_trajectory(q_end, duration=2.0, method='cubic', **kwargs) 执行平滑关节轨迹

  • move_cartesian_linear(target_pose, duration=2.0, **kwargs) 执行笛卡尔直线轨迹

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

状态获取:

  • set_extended_polling(enabled) 设置扩展轮询模式。启用后将从 3 地址轮询(pos/vel/torque)扩展到 7 地址轮询(pos/vel/torque/kp/kd/linear_vel/temperature),需新固件支持。

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

    info_type返回类型说明
    "joint"List[float]6 个关节角度(弧度)
    "joint_gripper"dict关节角度 + 夹爪值
    "velocity"List[float]关节速度(rad/s)
    "torque"List[float]关节力矩(N·m)
    "linear_vels"List[float]插补速度(rad/s)※需扩展轮询
    "temperatures"List[float]线圈温度(°C)※需扩展轮询
    "all"JointState完整状态对象(含 angles/gripper/velocities/torques,扩展轮询时还含 kps/kds/linear_vels/temperatures
    "version"VersionInfo版本信息(序列号、硬件版本、固件版本等)
    "status"RobotStatus运行状态(锁定、同步、错误等)
    "control_mode"List[dict]各电机控制模式(通过 0x11 查询)
  • get_pose() 获取当前末端执行器位姿(通过 FK 计算),返回包含 transform, position, rotation, euler_xyz, quaternion_xyzw 的字典

  • print_state(continuous=False, output_format='deg') 打印当前机械臂状态,支持持续打印模式

4.3 控制模式

模式标识说明
pvPV(位置-速度)固件侧加减速插值,适用于点位运动
mitMIT(阻抗控制)全参数逐帧控制,支持逐电机 kp/kd/torque/vel_ref 参数,适用于力控、遥操和精细运动场景

4.4 MIT 阻抗参数

MIT 模式下,可为每个电机(M0-M5 关节 + M6 夹爪)独立设置阻抗参数:

参数范围默认值说明
kp0-500150.0位置增益,值越大位置跟踪越紧
kd0-52.0速度增益(阻尼),抑制振荡
torque-0.0前馈力矩(N·m)
vel_ref-0.0参考速度(rad/s)

参数格式:

  • None:使用安全默认值
  • float:广播到所有 7 个电机(M0-M6)
  • List[6]:仅设置 6 个关节,夹爪使用默认值
  • List[7]:完整设置 6 个关节 + 夹爪(M6)