#
博客:
使用示教器和API控制灵巧手##RM_ARM+协议-使用示教器控制灵巧手
###硬件链接
机器人与示教器连接
参照机器人接线与开机指南,完成机器人系统上电,并建立示教器连接。
灵巧手与机械臂连接
使用专用航插线连接灵巧手与机械臂接口。关键步骤:确保接头的红色/蓝色标识点精确对准,以完成电气与信号的正确对接。
![]() | ![]() |
|---|
###参数配置
通过示教器完成灵巧手作为末端工具的通信与供电配置,步骤如下:
在示教器主界面,导航至 扩展 > 末端控制。
在末端控制界面中,配置以下核心参数:
工具端电源输出:根据灵巧手规格,选择
24V或12V供电。通信波特率:建议优先设置为
115200 bps以确保通信稳定性。通信协议:启用
RM_ARM+协议。
配置完成后,可在同一界面验证设备连接状态、查看基础信息并进行初步控制测试。
###设备控制
灵巧手提供两种直观的运动控制模式,用户可根据应用场景选择:
目标位置控制
目标角度控制
操作方式:在对应控制模式界面下,实时拖动指定自由度的滑动条,灵巧手将即刻响应并执行相应动作,实现“所见即所得”的实时操控。

###末端工具动作
为简化复杂抓取或操作流程的编程,系统支持将一系列控制指令保存为可复用的“末端动作”。
####创建新动作
在动作管理界面点击新增,进入扩展>末端页面。用户可自定义灵巧手的目标位置、目标角度等信息,最终保存为一个独立的动作文件。
####管理动作库
系统提供完整的动作文件管理功能,支持对已保存的动作进行:
动作查询
动作修改
动作导出
动作删除
...

####在图形化编程中调用动作
此功能极大提升了编程效率:
在图形化编程界面,将 末端工具 节点拖入编程画布。
选中该节点,在右侧设置面板中,直接从下拉菜单选择已预先配置好的动作文件。

##RM_ARM+协议-使用 API2 控制灵巧手
提醒
- 三代控制器版本 >= 1.7.0及以上
- 四代控制器版本 >= 1.0.4及以上
- API2版本 >= 1.0.7及以上
###环境配置
搭建环境:安装Visual Studio和unbuntu,搭建运行环境。
获取开发资源:访问 Realman 官网 ,下载 Demo文件。
工程配置:在 Visual Studio 中,打开已下载的 Demo 文件夹作为项目根目录。
###核心 API 接口详解
####设置灵巧手角度跟随控制rm_set_hand_follow_angle()
控制维度:
灵巧手提供 6个主动自由度 的跟随角度控制,最高50Hz的控制频率:
自由度 1:大拇指弯曲
自由度 2:食指
自由度 3:中指
自由度 4:无名指
自由度 5:小指
自由度 6:大拇指旋转
角度值定义(int16):
| 供应商 | 角度值计算方式 |
|---|---|
| 傲意 | 第一指关节1的角度*100。 |
| 因时 | 0-1000,通过联系技术支持得到驱动器行程与角度关系表。 |
注意
使用此功能前,必须联系生态厂商技术支持发送定制的灵巧手固件升级包。
####设置灵巧手位置跟随控制rm_set_hand_follow_pos()
控制维度:
灵巧手提供 6个主动自由度 的跟随位置控制,最高50Hz的控制频率:
自由度 1:大拇指弯曲
自由度 2:食指
自由度 3:中指
自由度 4:无名指
自由度 5:小指
自由度 6:大拇指旋转
注意
使用此功能前,必须联系生态厂商技术支持发送定制的灵巧手固件升级包。
###参数说明
设置灵巧手角度跟随控制
rm_set_hand_follow_angle()int rm_set_hand_follow_angle(rm_robot_handle *handle, const int *hand_angle, bool block);参数 类型 说明 handle 输入参数 机械臂句柄。 hand_angle 输入参数 设置灵巧手各手指动作,hand_angle表示手指角度数组,按照灵巧手厂商定义的角度做控制。
例如:因时的角度范围为0到+1000;傲意的角度范围为-32768到+32767。block 输入参数 true:表示非阻塞模式,发送成功后返回;
false:表示阻塞模式,接收设置成功指令后返回。设置灵巧手位置跟随控制
rm_set_hand_follow_pos()int rm_set_hand_follow_pos(rm_robot_handle *handle, const int *hand_pos, bool block);参数 类型 说明 handle 输入参数 机械臂句柄。 hand_pos 输入参数 设置灵巧手各手指动作,hand_pos表示手指位置数组,按照灵巧手厂商定义的角度做控制。
例如:因时的位置范围为0-2000;傲意的位置范围为0-65535。block 输入参数 true:表示非阻塞模式,发送成功后返回;
false:表示阻塞模式,接收设置成功指令后返回。返回值
rm_set_hand_follow_angle和rm_set_hand_follow_pos的API2错误代码。参数 类型 说明 处理建议 0 int 成功。 - 1 int 控制器返回false,传递参数错误或机械臂状态发生错误。 检查机械臂状态:查看机械臂控制器或日志中的实时报错信息(如硬件故障、超限等),根据提示复位、校准或排查硬件问题。
修正问题后重新发送指令,检查控制器返回的状态码及业务数据是否正常。-1 int 数据发送失败,通信过程中出现问题。 检查网络连通性:使用ping/telnet等工具检测与控制器的通信链路是否正常。 -2 int 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 - 检查网络连通性:使用ping/telnet等工具检测与控制器的通信链路是否正常。
- 校验版本兼容性:①核对控制器固件版本是否支持当前API功能,具体版本配套关系请参考版本变更说明。②若版本过低需升级控制器或使用适配的API版本。
- 调用ModbusTCP接口:仅在读写控制器ModbusTCP设备时适用,创建机械臂控制句柄后,必须调用rm_set_modbustcp_mode()接口,否则无法接收到返回值。-3 int 返回值解析失败,接收到的数据格式不正确或不完整。 校验版本兼容性:
①核对控制器固件版本是否支持当前API功能,具体版本配套关系请参考版本变更说明。②若版本过低需升级控制器或使用适配的API版本。-4 int 当前到位设备校验失败,即当前到位设备不为关节/升降机构/夹爪/灵巧手。 - 检测多设备并发控制:检查是否有其他设备给机械臂发送运动指令:包括机械臂、夹爪、灵巧手、升降机的运动;
- 实时监听指令事件:注册回调函数 rm_get_arm_event_call_back:①捕获设备到位事件(如运动完成、超时等);②通过回调参数 device 判断触发事件的具体设备类型。-5 int 单线程阻塞模式超时未接收到返回,请确保超时时间设置合理。 - 检查超时时长设置:单线程阻塞模式下,支持配置等待设备运动完成的超时时间,务必确保设置超时时间大于设备运动时间;
- 检查网络连通性:使用ping/telnet等工具检测与控制器的通信链路是否正常。-6 int 机械臂停止运动规划,外部发送了停止运动指令。 排查外部急停指令:
排查是否存在外部调用急停指令,例如发送急停json协议、触发io急停或者在示教器触发急停。
###具体操作
####C语言示例
灵巧手角度跟随控制
使用VS打开
RMDemo_RMArmPlusProtocol文件工程后编辑main.c文件如下:即可控制灵巧手。
#include <stdio.h>
#include "rm_interface.h"
// Windows-specific headers and definitions
#ifdef _WIN32
#define SLEEP_MS(ms) Sleep(ms)
#define SLEEP_S(s) Sleep((s) * 1000)
#define usleep(us) Sleep((us) / 1000) // No usleep, use Sleep instead
// Linux-specific headers and definitions
#else
#include <unistd.h>
#include <sys/time.h>
#define SLEEP_MS(ms) usleep((ms) * 1000)
#define SLEEP_S(s) sleep(s)
#endif
void custom_api_log(const char* message, va_list args) {
if (!message) {
fprintf(stderr, "Error: message is a null pointer\n");
return;
}
char buffer[1024];
vsnprintf(buffer, sizeof(buffer), message, args);
printf(" %s\n", buffer);
}
int main(int argc, char* argv[]) {
int result = -1;
rm_set_log_call_back(custom_api_log, 3);
result = rm_init(RM_TRIPLE_MODE_E);
if (result != 0) {
printf("Initialization failed with error code: %d.\n", result);
return -1;
}
char* api_version = rm_api_version();
printf("API Version: %s.\n", api_version);
const char* robot_ip_address = "192.168.1.18";
int robot_port = 8080;
rm_robot_handle* robot_handle = rm_create_robot_arm(robot_ip_address, robot_port);
if (robot_handle == NULL) {
printf("Failed to create robot handle.\n");
return -1;
}
else {
printf("Robot handle created successfully: %d\n", robot_handle->id);
}
rm_arm_software_version_t software_info;
result = rm_get_arm_software_info(robot_handle, &software_info);
if (result == 0) {
printf("================== Arm Software Information ==================\n");
printf("Arm Model: %s\n", software_info.product_version);
printf("Algorithm Library Version: %s\n", software_info.algorithm_info.version);
printf("Control Layer Software Version: %s\n", software_info.ctrl_info.version);
printf("Dynamics Version: %s\n", software_info.dynamic_info.model_version);
printf("Planning Layer Software Version: %s\n", software_info.plan_info.version);
printf("==============================================================\n");
}
rm_robot_info_t arm_info;
result = rm_get_robot_info(robot_handle, &arm_info);
if (result != 0)
{
return -1;
}
const int angle[6] = { 1200,1400,200,300,400,100 };
bool block = true;
rm_set_hand_follow_angle(robot_handle, angle, block);
int ret = rm_set_hand_follow_angle(robot_handle, angle, block);
if (ret == 0) {
printf("灵巧手运行完毕\n");
}
else {
printf("灵巧手运行失败\n");
}
}灵巧手位置跟随控制
使用VS打开
RMDemo_RMArmPlusProtocol文件工程后编辑main.c文件如下:即可控制灵巧手。
#include <stdio.h>
#include "rm_interface.h"
// Windows-specific headers and definitions
#ifdef _WIN32
#define SLEEP_MS(ms) Sleep(ms)
#define SLEEP_S(s) Sleep((s) * 1000)
#define usleep(us) Sleep((us) / 1000) // No usleep, use Sleep instead
// Linux-specific headers and definitions
#else
#include <unistd.h>
#include <sys/time.h>
#define SLEEP_MS(ms) usleep((ms) * 1000)
#define SLEEP_S(s) sleep(s)
#endif
void custom_api_log(const char* message, va_list args) {
if (!message) {
fprintf(stderr, "Error: message is a null pointer\n");
return;
}
char buffer[1024];
vsnprintf(buffer, sizeof(buffer), message, args);
printf(" %s\n", buffer);
}
int main(int argc, char* argv[]) {
int result = -1;
rm_set_log_call_back(custom_api_log, 3);
result = rm_init(RM_TRIPLE_MODE_E);
if (result != 0) {
printf("Initialization failed with error code: %d.\n", result);
return -1;
}
char* api_version = rm_api_version();
printf("API Version: %s.\n", api_version);
const char* robot_ip_address = "192.168.1.18";
int robot_port = 8080;
rm_robot_handle* robot_handle = rm_create_robot_arm(robot_ip_address, robot_port);
if (robot_handle == NULL) {
printf("Failed to create robot handle.\n");
return -1;
}
else {
printf("Robot handle created successfully: %d\n", robot_handle->id);
}
rm_arm_software_version_t software_info;
result = rm_get_arm_software_info(robot_handle, &software_info);
if (result == 0) {
printf("================== Arm Software Information ==================\n");
printf("Arm Model: %s\n", software_info.product_version);
printf("Algorithm Library Version: %s\n", software_info.algorithm_info.version);
printf("Control Layer Software Version: %s\n", software_info.ctrl_info.version);
printf("Dynamics Version: %s\n", software_info.dynamic_info.model_version);
printf("Planning Layer Software Version: %s\n", software_info.plan_info.version);
printf("==============================================================\n");
}
rm_robot_info_t arm_info;
result = rm_get_robot_info(robot_handle, &arm_info);
if (result != 0)
{
return -1;
}
const int pos[6] = { 1000,100,200,300,400,1000 };
bool block = true;
rm_set_hand_follow_pos(robot_handle, pos, block);
int ret = rm_set_hand_follow_pos(robot_handle, pos, block);
if (ret == 0) {
printf("灵巧手运行完毕\n");
}
else {
printf("灵巧手运行失败\n");
}
}####Python示例
Robotic_Arm
获取第二代睿尔曼机械臂Python版本二次开发包。
安装
可以通过pip来安装这个包:
pip install Robotic_Arm灵巧手角度跟随控制
from Robotic_Arm.rm_robot_interface import *
import time
# 实例化RoboticArm类
arm = RoboticArm(rm_thread_mode_e.RM_TRIPLE_MODE_E)
# 创建机械臂连接,打印连接id
handle = arm.rm_create_robot_arm("192.168.1.18", 8080)
print("handle.id",handle.id)
# 灵巧手角度跟随控制
hand_angle = [0,0,0,0,0,0]
print("rm_set_hand_follow_angle result: ", arm.rm_set_hand_follow_angle(hand_angle, True))
# time.sleep(1)
for j in range(6):
for _ in range(200):
hand_angle[j] += 50
arm.rm_set_hand_follow_angle(hand_angle, True)
time.sleep(0.005) # 5 ms
for _ in range(200):
hand_angle[j] -= 50
arm.rm_set_hand_follow_angle(hand_angle, True)
time.sleep(0.005)
arm.rm_delete_robot_arm()- 灵巧手位置跟随控制
from Robotic_Arm.rm_robot_interface import *
import time
# 实例化RoboticArm类
arm = RoboticArm(rm_thread_mode_e.RM_TRIPLE_MODE_E)
# 创建机械臂连接,打印连接id
handle = arm.rm_create_robot_arm("192.168.1.18", 8080)
print("handle.id",handle.id)
# 灵巧手角度跟随控制
hand_pos = [0,0,0,0,0,0]
print("rm_set_hand_follow_pos result: ", arm.rm_set_hand_follow_pos(hand_pos, True))
# time.sleep(1)
for j in range(6):
for _ in range(200):
hand_pos[j] += 50
arm.rm_set_hand_follow_pos(hand_pos, True)
time.sleep(0.005) # 5 ms
for _ in range(200):
hand_pos[j] -= 50
arm.rm_set_hand_follow_pos(hand_pos, True)
time.sleep(0.005)
arm.rm_delete_robot_arm()


