实时模式注意事项和常见问题
1 使用注意事项
1.1 指令规划的要求
用户下发的运动指令需要满足建议条件和必要条件。建议条件是为了让机器人运动更加平稳,性能最优。必要条件则是必须满足的,若不满足,机器人将会停止。建议条件若不满足,运动中可能会出现抖动、电机异响等情况。
1.1.1 轴空间运动
1.必要条件
轴空间轨迹平滑,至少保证速度是连续可导的:
2.建议条件
力矩指令不超限:
运动开始时:
运动结束时:
1.2 笛卡尔空间运动
1. 必要条件
不处于奇异位且在工作空间内:
2. 建议条件
力矩指令不超限:
运动开始时:
运动结束时:
1.1.3 力矩直接控制
1.必要条件
力矩指令不超限且连续:
1.1.4 运动限制条件
xMateER3 Pro、xMateER7 Pro、xMateER3、xMateER7笛卡尔空间运动限制条件:
| 参数 | 平移 | 旋转 |
|---|---|---|
| 速度 | ||
| 加速度 | ||
| 加加速度 |
xMateER3 Pro 和 xMateER7 Pro 轴空间运动限制条件:
| 参数 | 一轴 | 二轴 | 三轴 | 四轴 | 五轴 | 六轴 | 七轴 | 单位 |
|---|---|---|---|---|---|---|---|---|
| 限位上限 | 170 | 120 | 170 | 120 | 170 | 120 | 360 | ° |
| 限位下限 | -170 | -120 | -170 | -120 | -170 | -120 | -360 | ° |
| 速度上限 | 2.175 | 2.175 | 2.175 | 2.175 | 2.610 | 2.610 | 2.610 | |
| 加速度上限 | 15 | 7.5 | 10 | 10 | 15 | 15 | 20 | |
| 加加速度上限 | 5000 | 3500 | 5000 | 5000 | 7500 | 7500 | 7500 |
xMate3 和 xMate7 轴空间运动限制条件:
| 参数 | 一轴 | 二轴 | 三轴 | 四轴 | 五轴 | 六轴 | 单位 |
|---|---|---|---|---|---|---|---|
| 限位上限 | 170 | 120 | 120 | 170 | 120 | 360 | ° |
| 限位下限 | -170 | -120 | -120 | -170 | -120 | -360 | ° |
| 速度上限 | 2.175 | 2.175 | 2.175 | 2.610 | 2.610 | 2.610 | |
| 加速度上限 | 15 | 7.5 | 10 | 15 | 15 | 20 | |
| 加加速度上限 | 5000 | 3500 | 5000 | 7500 | 7500 | 7500 |
xMateER3 Pro 和 xMateER7 Pro 直接力矩控制限制条件
| 参数 | 一轴 | 二轴 | 三轴 | 四轴 | 五轴 | 六轴 | 七轴 | 单位 |
|---|---|---|---|---|---|---|---|---|
| 力矩上限 | 85 | 85 | 85 | 85 | 36 | 36 | 36 | |
| 力矩微分上限 | 1500 | 1500 | 1500 | 1500 | 1000 | 1000 | 1000 |
xMate3 和 xMate7 直接力矩控制限制条件
| 参数 | 一轴 | 二轴 | 三轴 | 四轴 | 五轴 | 六轴 | 单位 |
|---|---|---|---|---|---|---|---|
| 力矩上限 | 85 | 85 | 85 | 36 | 36 | 36 | |
| 力矩微分上限 | 1500 | 1500 | 1500 | 1000 | 1000 | 1000 |
1.2 DH参数
xMateER3 Pro DH 参数表:
| Joint | A(mm) | Alpha(rad) | D(mm) | Theta(rad) |
|---|---|---|---|---|
| 1 | 0 | -pi/2 | 341.5 | 0 |
| 2 | 0 | pi/2 | 0 | 0 |
| 3 | 0 | -pi/2 | 394.0 | 0 |
| 4 | 0 | pi/2 | 0 | 0 |
| 5 | 0 | -pi/2 | 366 | 0 |
| 6 | 0 | pi/2 | 0 | 0 |
| 7 | 0 | 0 | 250.3 | 0 |
xMateER7 Pro DH 参数表:
| Joint | A(mm) | Alpha(rad) | D(mm) | Theta(rad) |
|---|---|---|---|---|
| 1 | 0 | -pi/2 | 404.0 | 0 |
| 2 | 0 | pi/2 | 0 | 0 |
| 3 | 0 | -pi/2 | 437.5 | 0 |
| 4 | 0 | pi/2 | 0 | 0 |
| 5 | 0 | -pi/2 | 412.5 | 0 |
| 6 | 0 | pi/2 | 0 | 0 |
| 7 | 0 | 0 | 275.5 | 0 |
xMate3 DH 参数表:
| Joint | A(mm) | Alpha(rad) | D(mm) | Theta(rad) |
|---|---|---|---|---|
| 1 | 0 | -pi/2 | 341.5 | 0 |
| 2 | 394 | 0 | 0 | 0 |
| 3 | 0 | pi/2 | 0 | 0 |
| 4 | 0 | -pi/2 | 366 | 0 |
| 5 | 0 | pi/2 | 0 | 0 |
| 6 | 0 | 0 | 250.3 | 0 |
xMate7 DH 参数表:
| Joint | A(mm) | Alpha(rad) | D(mm) | Theta(rad) |
|---|---|---|---|---|
| 1 | 0 | -pi/2 | 404 | 0 |
| 2 | 437.5 | 0 | 0 | 0 |
| 3 | 0 | pi/2 | 0 | 0 |
| 4 | 0 | -pi/2 | 412.5 | 0 |
| 5 | 0 | pi/2 | 0 | 0 |
| 6 | 0 | 0 | 275.5 | 0 |
1.3 兼容RCI客户端
对于原 RCI 客户端的用户,可以在控制器升级到v1.7及之后的版本后直接使用 xCoreSDK。
1.3.1 首次使用
1.确保RobotAssist-通信-RCI设置是关闭的状态,也可通过状态栏中间的机器人状态确认;
2.调用 setMotionControlMode(RtCommand)接口来打开 RCI 功能,若打开成功,机器人状态变为 RCI,状态栏的图标也显示 RCI :
3.之后就可通过上述接口或 RobotAssist 打开关闭 RCI 功能。需要注意的是,如果进行了抹除配置操作,那么同样视为首次使用,需要再通过 SDK 的接口打开 RCI。
1.3.2 切换到使用RCI客户端
在用过 SDK 后,RCI 客户端就无法同时使用了。如果想切换回去,需调用 useRciClient(true),调用前按照函数说明,确保 RCI 是关闭的状态。然后再通过 RobotAssist 打开关闭 RCI 功能。
2 常见问题
2.1 网络连接问题
实时运动指令和状态信息都通过 UDP 协议单播发送。在初次使用时,可能会遇到UDP网络相关的报错。
2.1.1 UDP socket打开失败
抛出的异常显示“提供了一个无效的参数”或“请求的地址无效”,基本是因为没有填写本机地址,或者本机地址错误。
1. 本机地址查看方法
Ubuntu系统可以用ifconfig命令查看,找到连接机器人的网络设备,IP地址应该和机器人在同网段下

Windows可以在设置-网络和Internet中找到

也可以用ipconfig命令查看

2. 如何正确填入本机地址
int main() {
// 假设机器人地址是10.0.2.160, SDK程序运行在我的Windows PC上, 本机地址就是10.0.2.121
rokae::xMateRobot robot("10.0.2.160", "10.0.2.121");
// 或者连接到机器人时填入
rokae::xMateRobot robot;
robot.connectToRobot("10.0.2.160", "10.0.2.121");
}
2.1.2 超时前未收到机器人状态反馈
如果出现“超时前未收到机器人状态反馈”的实时状态异常,说明IP设置都是对的,但是UDP消息被拦截。
1. Windows系统
Windows系统请检查防火墙设置,UDP 入站规则是否是允许的状态。
在首次运行SDK程序时,可能会出现防火墙弹窗,务必要点允许。

此外,可以在高级安全Windows Defener防火墙中检查运行的程序的入站规则

2. Linux系统
本节仅供参考,具体的系统版本对应的指令如果不适配,可自行搜索替换。
Linux较少出现防火墙拦截问题。先用如下方法测试机器人发送的消息是否能收到:打开终端,输入命令 nc -vul -p 1337 ,然后再任意运行一个实时模式控制的示例程序,查看是否有来自机器人地址的端口连接过来,并且收到了数据。
如果上位机1337端口 (实时状态数据是1338端口) 始终没有接收到数据,可以排查Linux防火墙的限制问题。
常见的Linux系统防火墙有:UFW、firewall、iptables,其中,UFW是Debian系列的默认防火墙,firewall 是红帽系列7及以上的防火墙(如CentOS7.x),iptables是红帽系列6及以下(如CentOS6.x)的防火墙。
2.1 UFW 防火墙
- 确定防火墙状态。在终端中执行命令:
sudo ufw status如果输出显示为 “Status: active”,则表示防火墙已开启;若显示 “Status: inactive”,则表示防火墙未开启(如果ufw防火墙未开启则直接去检查其他防火墙问题)。 - 检查 UDP 端口 1337 和 1338 是否允许通信
如果UFW防火墙开启,执行上述查看状态的命令后,会列出已配置的规则。查看规则列表中是否有允许 UDP 端口 1337 和 1338 的规则,类似如下:

- 开放 UDP 端口 1337 和 1338 如果规则列表中没有允许这两个端口的规则,可以使用以下命令开放:
sudo ufw allow 1337/udp
sudo ufw allow 1338/udp
最后再次执行 sudo ufw status 确认规则已添加。
4. 关闭防火墙
如果上述操作无效,可以直接使用指令关闭防火墙:sudo ufw disable
2.2 firewalld防火墙
- 确定防火墙状态
可以使用指令来查看防火墙状态:
sudo systemctl status firewalld或者sudo firewall-cmd --state如果输出为 "running“,则表示防火墙正在运行;若输出为 ”not running“ 或类似信息,则表示防火墙未运行。 - 检查 UDP 端口 1337 和 1338 是否允许通信
执行以下命令查看当前允许的端口列表:
sudo firewall-cmd --list-ports查看输出中是否包含 1337/udp 和 1338/udp。 - 开放 UDP 端口 1337 和 1338 使用以下命令临时开放端口(重启后规则失效):
sudo firewall-cmd --add-port=1337/udp
sudo firewall-cmd --add-port=1338/udp
若要永久开放端口,需要添加 --permanent 参数,并重新加载防火墙规则:
sudo firewall-cmd --permanent --add-port=1337/udp
sudo firewall-cmd --permanent --add-port=1338/udp
sudo firewall-cmd --reload
- 关闭防火墙
如果上述操作无效,可以直接使用指令关闭防火墙。
临时性关闭
systemctl stop firewalld;永久性关闭systemctl disable firewalld
2.3 iptables防火墙
-
确定防火墙状态 执行命令查看 iptables 规则:
sudo iptables -L如果输出有很多规则,说明防火墙正在起作用;若输出为空或者只有少量默认规则,可能防火墙没有进行额外的过滤配置。 -
检查 UDP 端口 1337 和 1338 是否允许通信 在上述命令的输出中,查找是否有允许 UDP 端口 1337 和 1338 的规则,规则类似如下:

-
开放 UDP 端口 1337 和 1338 使用以下命令添加允许规则:
sudo iptables -A INPUT -p udp --dport 1337 -j ACCEPT
sudo iptables -A INPUT -p udp --dport 1338 -j ACCEPT
要使规则在重启后仍然生效,需要保存规则。在不同的发行版中保存规则的方法可能不同,例如在 CentOS 系统中可以使用:sudo service iptables save
在 Ubuntu 等系统中,可以使用 "iptables-persistent" 工具来保存规则。
4. 关闭防火墙
如果上述操作无效,可以直接使用指令关闭防火墙(CentOS/RHEL):
临时关闭防火墙:sudo systemctl stop iptables
禁止防火墙开机自启:sudo systemctl disable iptables
或者清空防火墙规则(Ubuntu/Debian):sudo iptables -F
2.2 实时模式运动报错
实时模式运动中出错,控制器会下电处理。本节介绍如何获取报错,和处理错误的方法。
2.2.1 如何捕获运动报错
void funRTControl() {
try {
auto rtCon = robot.getRtMotionController().lock();
rtCon->startMove(RtControllerMode::jointPosition);
// 调用方式一:阻塞运行,运动中报错会抛出异常
rtCon->startLoop(true);
// 调用方式二:非阻塞运行,运动中如果出错,stopLoop时会抛出异常
rtCon->startLoop(false);
rtCon->stopLoop();
} catch(const std::exception &e) {
// error handler
std::cerr << e.what();
}
}
2.2.2 报错原因及处理
实时模式一共有20个错误类型
2.2.2.1 报错kInstabilityDetection
如果常出现kInstabilityDetection,可以调高网络阈值。在实时模式关闭的状态下,调用setRtNetworkTolerance,阈值到60%以上。
2.2.2.2 速度/加速度超出阈值
- 如果发生在一段运动开始时,也就是说刚开始startMove就停止了,那么大概率是给的起始位置不是当前位置。如何正确设置起始位置见下一节
- 如果发生在运动中,且运行SDK的示例程序,那么可能和上位机实时性和网络波动都有关系。最好是调整上位机程序运行环境
- 如果是自己写轨迹规划,那么大概率确实存在位置指令差距过大的情况,需要改进规划
- 如果网络连接复杂,用到了交换机等,那么会有丢包的情况,需要改成直连
2.2.2.3 如何正确设置起始位置
比如 MoveJ(start_pos, target_pos, speed), start_pos如何给出?有三种方法:
- 最推荐:用posture()/jointPos()读
std::array<double, 16> init_position {};
Utils::postureToTransArray(robot.posture(rokae::CoordinateType::flangeInBase, ec), init_position);
- 循环调用updateRobotState直到更新到当前最新的数据。调用一次更新一帧数据,所以只调用一次的话,很可能读的是旧数据
// 接收状态数据的队列不会自动覆盖旧数据,可以通过循环读取的方法清除旧数据
while (robot.updateRobotState(chrono::steady_clock::duration::zero()));
- 回调第一次运行时,更新起始位置
std::function<CartesianPosition()> callback = [&, rtCon]() {
if(init) {
// 读取起始位置
robot.getStateData(RtSupportedFields::tcpPose_m, init_pos);
init = false;
}
};
// 因为callback中用到了getStateData(), 所以参数useStateDataInLoop=true
rtCon->setControlLoop(callback, 0, true);
2.2.2.4 位置控制过程中发生异响
- 发生在运行SDK示例程序
- 设置滤波,平滑指令:setFilterFrequency,setFilterLimit。频率越低平滑效果越好
- 上位机实时性不好,多见于Windows。一般Windows运行都需要设置滤波。
- 网络情况也有影响,建议用直连的方式,减少网络波动
- 和上位机设备网卡也有关系,一般realtek网卡 基本上能保证同步,intel的网卡经常超时
- 发生在自己做轨迹规划
- 上述4条全部排查一遍
- 回调代码超时,一个周期耗时大于1ms
- 如都不能解决,那就需要调整规划了,异响就是因为相邻指令之间位置差过大。比如将位置指令差分到速度,查看速度曲线是否平滑
2.2.2.5 示教器上各项运动、安全设置,实时模式是否生效
大部分都不生效,包括加速度等等设置项。可以理解为,机器人变成一个单纯的执行器,发的指令ok就执行,不ok就下电报错处理,没有额外的约束。生效的有:
- 碰撞检测:发生碰撞后下电停止。无回退、柔顺停止等行为
- 关节限位
- 基座标系
- 力控参数,阻抗控制下生效
2.2.2.6 回调实时性问题
回调内部一个周期执行的操作: 接收一次控制器发送的数据反馈 -> 发送一条指令。 控制器是实时发送状态数据的。但是下位机端并不要求在实时线程执行,所以可能不是严格的1ms 。执行周期是间接受控制器发送数据的周期控制
2.2.2.7 实时模式直接力矩控制下坠问题
力矩控制和机械臂硬件状态有关系,可以做如下验证,两种方式二选一:
- 打开拖动,按住拖动按键时候机械臂是否可以维持不动的状态,不会上飘或下坠
- 运行RL力控相关指令,是否能正常使用 如果上述两条验证不正常的话,那么存在力控模型误差;
解决方法:
- 如果存在力控模型误差,进行如下操作纠正误差:
- 设置准确的负载质量和质心,不可大致估计
- 设置好负载后,执行力传感器标定
- 如果力控本身没问题,那么就是发送的力矩值不合适。建议在第一次使用力矩控制时候,先全部发送0,正常情况下机械臂应静止不动。
2.2.2.8 点位跟随示例无法编译
实时模式示例程序follow_joint_position 和 torque_control 都用到了xMate模型库,模型库不是每个系统和架构都支持,所以设置了宏定义,需要将对应CMake选项设置为ON,以Visual Studio为例:

用命令行就是(此处省略其它cmake命令参数):
cmake -DXCORE_USE_XMATE_MODEL=ON
如果不是CMake工程的,则在工程配置中加上 XMATEMODEL_LIB_SUPPORTED 这项宏定义。
2.2.2.9 实时模式运动慢了
-
问题 1 :在用SDK开环下发控制指令的时候(1ms调用),发现下发的指令和实际执行之间会差大概20ms的滞后
-
问题2:跟随慢了
解决办法:
实时模式接收状态数据默认的等待超时时间是 1ms ,根据现场实际的网络情况,可以在可执行文件同目录下,增加配置文件 xcoresdk_config.json来设置超时时间,以适应实际情况和优化实时效果。若设备网络情况较好,并出现控制一段时间后,发送的运动指令有延迟执行的现象,可适当将超时时间调大,设置范围为 1∼4ms ,具体的 json 文件格式如下:
{
"rt":{
"_timeout_": 2
}
}
2.2.2.10 丢包导致下电
客户现场提供的日志经常可以看到丢包导致了下电,
- 一般就是网卡类型为Intel I219-LM容易导致丢包,建议上位机换成Realtek
- 设置网络阈值:一般设置20,30,超过50就要排查是否是网络的问题
robot.setRtNetworkTolerance(20, ec);
- 客户经常会再封装珞石的SDK接口,在通信的时候可能 使用了同一端口1337,这样造成网络拥塞,上位机的数据包到不了控制系统,形成丢包
2.2.2.11 sdk接口报通信协议错误 xCore最低版本要求2.3.0.0
一般是Inter型号网卡引起的问题,此网卡的缓存转发机制导致实时模式收不到数据包,现象表示就是有丢包,建议客户更换Realtek型号网卡
2.2.2.12 运动超时,UDP打开失败
使用最新的1124版本或者主干最新的版本3.1.3可以解决
通过日志可以看到启动startMove时显示运动超时:

上位机报的错误:

2.2.9 报网络连接错误
错误类型:realtime: Failed to create RT controller.network: network connection
请检查下设置的工具工件坐标系,还有startMove、 startLoop接口的调用顺序
2.3 AR臂的使用
2.3.1 前提说明
- AR机型主要包括两款,十字腕和SR类型的,分左右臂(L:左臂,R:右臂),一般客户会选择侧装的方式

- 版本要求
控制版本:3.0.1.6.AR1124
SDK版本:librokae-v0.5.1.ar_9和xcoresdk_python-v0.5.1.ar_9

-
安装方式
左右臂一般会选择侧装的安装方式(基座左臂和世界坐标不重合),注意:左右臂的侧装参数不一样,如下是左臂:

2.3.2 DEMO使用
目前客户大部分使用AR机型都是遥操作,灵巧手,夹东西的业务场景,客户对机器人实时控制的场景要求比较高,一般会基于笛卡尔位置和关节控制,规划轨迹特别重要,因此,在轨迹规划过程中需重点考虑运动平滑性与实时性,建议采用样条插值或梯形速度曲线进行路径优化。同时,结合AR机型的逆解求解特性,确保每一步目标点位于工作空间内,避免奇异位形。对于遥操作延迟问题,设置丢包网络阈值。对于机械臂响应慢的情况设置timeout的方式
2.3.2.1 实时模式-笛卡尔位置控制
参照demo:cartesian_impedance_control.cpp实现,
注意事项
- 删除如下代码
// 设置力控坐标系为工具坐标系, 末端相对法兰的坐标系
std::array<double, 16> toolToFlange = {0, 0, 1, 0, 0, 1, 0, 0, -1, 0, 0, 0, 0, 0, 0, 1};
rtCon->setFcCoor(toolToFlange, FrameType::tool, ec);
// 设置笛卡尔阻抗系数
rtCon->setCartesianImpedance({1200, 1200, 0, 100, 100, 0}, ec);
// 设置X和Z方向3N的期望力
rtCon->setCartesianImpedanceDesiredTorque({3, 0, 3, 0, 0, 0}, ec);
- 提供的Demo初始化类是6轴的,所以代码跑不起来,AR是7轴的,需要定义如下类,第一个参数是机器人的IP,第二个参数是上位机的IP
rokae::xMateErProRobot robot(ip, "192.168.2.190");
回调接口实时更新笛卡尔位置,客户可以从外部传入,注意回调接口不要有任何的阻塞任务、耗时任务,比如socket通信,打印日志,写文件,只是单一的赋值、简要的计算即可,保证1ms可以执行完的任务
std::function<CartesianPosition(void)> callback =[&,rtCon]()->CartesianPosition{
time+=0.001;
output.pos = init_position;
output.pos[7]+=delta_z;
std::array<double, 6> xyzabc;
print(std::cout,"位置:",xyzabc)
if(time > 0.01){
std::cout<<"运动结束:"<<deltaz<<std::endl;
output.setFinished();
stopManually.store(false);//loop为非阻塞,和主线程同步停止状态
return output;
}
}
代码流程
- 构造类
rokae::xMateErProRobot
- 设置参数,自动模式,实时模式,上电,先要切换自动模式,才能上电
robot.setOperateMode(rokae::OperateMode::automatic,ec);
robot.setMotionControlMode(MotionControlMode::RtCommand, ec);
robot.setPowerState(true, ec);
- 如果用户末端安装了工具工件,也需要要设置工具工件坐标
具体参照接口
//设置手持工具坐标系,Rv旋转90
Toolsettoolset1:
toolset1.end.rpvl1l= MPt.2:
robot.setToolset(toolset1.ec)
- 移动到拖动姿态(客户可能不需要),AR的拖动姿态关节角需要修改
std::array<double,7> q_drag_xm7p = {0,M_PI/6,0,M_PI/3,0,0,0};
rtCon->MoveJ(0.5, robot.jointPos(ec), q_drag_xm7p);
- 如果客户使用过程中丢包比较多,需要设置网络阈值,一般建议20-30
robot.setRtNetworkTolerance(50, ec);
- 回调实现:保证回调里面实现的内容的单一性,不要加延迟任务,阻塞任务,耗时任务,否则影响控制器的调度,使机械臂调度慢,出现异响,运动延迟等不可预见的错误。
给的笛卡尔点是4*4的矩阵,是基于基坐标系的,如需转换请参照utility.h文件提供的接口实现
std::function<CartesianPosition(void)> callback = [&, rtCon]()->CartesianPosition{
time += 0.001;
constexpr double kRadius = 0.1;
double angle = M_PI / 4 * (1 - std::cos(M_PI / 2 * time));
double delta_z = kRadius * (std::cos(angle) - 1);
CartesianPosition output{};
output.pos = init_position;
output.pos[7] += delta_z;
if(time > 0.01){
std::cout << "运动结束:"<<delta_z <<std::endl;
output.setFinished();
stopManually.store(false); // loop为非阻塞,和主线程同步停止状态
}
return output;
};
- 启动实时模式
rtCon->setControlLoop(callback, 0, true);
//开始运动前先设置为笛卡尔空间位置控制
rtCon->startMove(RtControllerMode::cartesianPosition);
rtCon->startLoop(true);
2.3.2.2 实时模式-关节控制
参照demo:joint_position_control.cpp
注意事项
- 参照上面章节“注意事项”的第2点,
代码流程
- 前5个点参照上述2.3.2.1.2的前五点
- 回调函数,赋值的是关节角,以弧度为单位,上位机坐规划的时候大部分是规划世界坐标系的笛卡尔点,所以使用utility.h定位的转换接口坐转换
std::function<JointPosition()> callback = [&, rtCon]() {
time += 0.001;
double delta_angle = M_PI / 20.0 * (1 - std::cos(M_PI / 2.5 * time));
JointPosition cmd = {{jntPos[0] + delta_angle, jntPos[1] + delta_angle, jntPos[2] - delta_angle,
jntPos[3] + delta_angle, jntPos[4] - delta_angle, jntPos[5] + delta_angle,
jntPos[6] - delta_angle}};
if (time > 60)
{
cmd.setFinished(); // 60秒后结束
}
return cmd;
};
- 启动实时模式:关节控制
// 设置回调函数
rtCon->setControlLoop(callback);
// 更新起始角度为当前角度
jntPos = robot.jointPos(ec);
// 开始轴空间位置控制
rtCon->startMove(RtControllerMode::jointPosition);
// 阻塞loop,开始运动
rtCon->startLoop(true);
2.3.2.3 正逆解
流程和代码说明,步骤和代码说明,为了防止奇异点算不出正逆解,验证的过程首先要在HMI示教点位,在HMI上通过MOVL或者movj能正常到达,sdk接口调用的时候就没问题
-
连接机器人
注意项:
- IP地址不要搞反了和写错了,否则是连接失败
- 初始化的类是xMateErProRobot,这是7轴机器人的类
xMateErProRobot robot("192.168.2.160", "192.168.2.110"); // 使用xMateErProRobot以匹配7轴
-
设置自动模式并上电
robot.setOperateMode(OperateMode::automatic, ec);
if (ec) {
cout << "设置自动模式失败: " << ec.message() << endl;
return -1;
}
robot.setPowerState(true, ec);
if (ec) {
cout << "上电失败: " << ec.message() << endl;
return -1;
}
-
设置工具工件坐标
如有必要,需要设置工具工件坐标,
Toolset toolset1;
toolset1 = robot.toolset(ec);
print(std::cout, "从控制器读取的工具工件坐标系:", toolset1);
-
获取关节角
用于做正解计算
// 获取当前机器人关节角度
auto current_joints = robot.jointPos(ec);
if (ec) {
cout << "获取关节角度失败: " << ec.message() << endl;
return -1;
}
-
获取末端姿态
用于计算逆解,特别注意截图的参数,一般的情况下法兰是会安装工具的,如果没有安装的话这个值就是法兰的位姿
// 获取控制器报告的当前末端位姿
auto current_cartesian_from_robot = robot.cartPosture(CoordinateType::endInRef, ec);
if (ec) {
cout << "获取末端位姿失败: " << ec.message() << endl;
return -1;
}
-
设置不要轴配置参数计算逆解
这个值默认是不需要设置的,默认是关闭,有些客户直接使用skd的接口,没有通过HMI操作,所以最好设置
//设置不要轴配置参数计算逆解
robot.setDefaultConfOpt(false, ec);
-
计算正解
使用的值是步骤3里面获取的关节角
auto fk_cartesian = robot.model().calcFk(current_joints, toolset1, ec);
if (ec) {
cout << "正解算失败: " << ec.message() << endl;
}
查看打印的数据是否正确,并与HMI上的界面的数据做比较,如果一致,就是正确的
-
计算逆解
使用的是步骤5获取到的数据,如果计算失败可以采用正解的计算出来的位姿传入做计算,
如果还失败,则说明控制器有问题 。找对应的技术人员解决
auto ik_joints_m1 = robot.model().calcIk(endPos, toolset1, ec);
与HMI上显示的关节角对比
-
新增接口参数说明:增加臂角精度值
搜索臂角的精度,如果不设置臂角或者臂角的搜索精度会导致计算出来的值不准确,差异较大
auto ik_joints_m1 =robot.model().calcIk_SearchElbow(endPos,toolset1,5,ec)
2.3.2.4 基于模型库的正逆解
采用此方式,可以是逆解提速,目前发布的控制器版本不是所以的机型都支持,目前针对AR机型的控制版本支持AR机型,其他的机型要使用话,请选择3.1.2及以上的版本

-
连接机器人
rokae::xMateErProRobot robot(“192.168.0.160”);
-
初始化关节角
std::array<double, 7> zeros = {0, 0, 0, 0, 0, 0, 0},
//初始化关节角
jointPos_in = Utils::degToRad(array<double,7>({5, 46, -10, 91, 1, -105, 11})),
jointVel_in = {0.3, 0.2, 0.5, 0.4, 0.1, 0.1, 0.1},
jointAcc_in = {1.3, 3.1, 4.1, 1.5, 1.6, 4.1, 8.1},
jointInit = Utils::degToRad(array<double,7>({6, 45, -9, 92, 0, -103, 10})),
array1 {}, array2 {}, array3 {}, array4 {};
-
计算正解
/**
* @brief 获取笛卡尔空间位置
* @param[in] jntPos 需要计算笛卡尔位姿的关节角度
* @param[in] nr 指定坐标系, 缺省值为flange
* @return 向量化4x4位姿矩阵,行优先.
*/
std::array<double, 16> getCartPose(const std::array<double, DoF> &jntPos, SegmentFrame nr = SegmentFrame::flange);
auto pos = model.getCartPose(jointPos_in);
- 计算逆解
根据输入的臂角的搜索精度得到关节角
/**
* @brief 目标比较从[-PI,PI]之间进行遍历,得到其中最近的逆解
* @param[in] cartPos 法兰笛卡尔空间位姿
* @param[in] psi_accuracy 臂角求解精度,单位度(例如1、10、20),精度越高,求解时间越长
* @param[in] elbow 臂角 原接口扩展,暂时无用
* @param[in] jntInit 初始关节角度
* @param[out] jntPos 关节空间位置
* @return 计算逆解结果 -
* 1) -1, -2, -3: 无解,原因是cartPos超出机器人工作空间或无解
* 2) -4, -5: jntPos与jntInit相差较大,一般认为jntInit代表机器人当前位置,jntPos与jntInit之差可以等效为电机转速。
* 若超过机器人轴额定转速,则返回-4或-5;
* 3) -6, -7: jntPos超过软限位;
* 4) -8: 机器人奇异;
*/
int getJointPosSearchPsi(const std::array<double, 16> &cartPos, const double& psi_accuracy, double elbow,const std::array<double, DoF> &q_init, std::array<double, DoF> &q);
增加了臂角遍历的输入
double psi = Utils::degToRad(-7.177);
double psi2 = Utils::degToRad(0);
array<int, 8> confData = {0, 0, 0, 0, 0, 0, 0,0};
gettimeofday(&start, NULL);
auto ret = model.getJointPos(pos, psi, jointInit, array1);
auto ret = model.getJointPosSearchPsi(pos,1, psi2, jointInit, array1);
2.3.3 新增接口-臂角遍历
增加了逆解接口中搜索臂角精度的设置,取值大于0即可
-
通用
增此逆解决接口一般需要42ms以上的时间获取到结果
请见 2.3.2.4 章节demo的实现
/**
* @brief 根据位姿计算逆解。并自动遍历臂角,搜索范围-PI-PI
* @param[in] posture 机器人末端位姿,相对于外部参考坐标系。参考的坐标系是通过setToolset()设置的
* @param[in] elb_accuracy 臂角精度 大于0即可,值越小,搜索精度越高,计算时间越长,建议值大于10,
* @param[out] ec 错误码
* @return 轴角度, 单位:弧度
*/
std::array<double, DoF> calcIk_SearchElbow(CartesianPosition posture, double elb_accuracy, error_code &ec) noexcept;
/**
* @brief 根据位姿计算给定工具工件坐标系下逆解。并自动遍历臂角,搜索范围-180-180°
* @param[in] posture 机器人末端位姿,相对于外部参考坐标系
* @param[in] tool_set 工具工件坐标系
* @param[in] elb_accuracy 臂角精度 大于0即可,值越小,搜索精度越高,计算时间越长
* @param[out] ec 错误码
* @return 轴角度, 单位:弧度
*/
std::array<double, DoF> calcIk_SearchElbow(CartesianPosition posture,const Toolset &tool_set, double elb_accuracy, error_code& ec) noexcept;
- 模型库逆解
增加了臂角的遍历,满足逆解提速的要求
/**
* @brief 目标比较从[-PI,PI]之间进行遍历,得到其中最近的逆解
* @param[in] cartPos 法兰笛卡尔空间位姿
* @param[in] psi_accuracy 臂角求解精度,单位度(例如1、10、20),值越小,精度越高,求解时间越长
* @param[in] elbow 臂角 接口扩展使用,暂时无用
* @param[in] jntInit 初始关节角度
* @param[out] jntPos 关节空间位置
* @return 计算逆解结果 -
* 1) -1, -2, -3: 无解,原因是cartPos超出机器人工作空间或无解
* 2) -4, -5: jntPos与jntInit相差较大,一般认为jntInit代表机器人当前位置,jntPos与jntInit之差可以等效为电机转速。
* 若超过机器人轴额定转速,则返回-4或-5;
* 3) -6, -7: jntPos超过软限位;
* 4) -8: 机器人奇异;
*/
int getJointPosSearchPsi(const std::array<double, 16> &cartPos, const double& psi_accuracy, double elbow, const std::array<double, DoF> &q_init, std::array<double, DoF> &q);
2.4 实时模式下AR臂常见问题
2.4.1 左右臂运动不一致,一个快一个慢
如果是同版本,同配置的情况下,两个臂运动不一致,查看HMI上如下开关是否开启

2.4.2 求正逆解失败
-
在HMI上确认如下参数是否关闭

-
调用接口关闭conf
设置不要轴配置参数计算逆解
robot.setDefaultConfOpt(false, ec);