项目背景及功能
受国际形势复杂多变的影响,工业控制领域长期以来以国外产品及系统为主导的格局正在发生转变。当下国家大力倡导国产自主可控的发展方向,为响应这一战略转变,对原有控制系统进行重构升级,以契合国产化替代的潮流。
本项目所构建的是一个原型系统,核心功能架构如下:Web 端采用 Three.js 技术栈,实现机械臂运行状态的 3D 可视化展示;系统通过 MQTT 协议与睿擎派进行高效数据交互,形成上下层通信链路。睿擎派采用双总线控制架构:其一通过 EtherCat 总线驱动伺服系统,实现电机的精准闭环控制,进而带动机械臂完成预设动作;其二通过 Modbus RTU 总线对接 IO 模块,实现各类灯具的开关状态管控。
RT-Thread使用情况
采用以RT-Thread为核心的睿擎工业平台进行开发,开发环境为RuiChing Studio。硬件主控模块采用了睿擎派。
该平台是为工业场景设计的软硬件一体化开发方案,全栈自主可控,整合了数据采集、通信、控制、工业协议、AI、显示六大核心功能。
本系统糅合了三个官方典型示例工程完成了本系统嵌入式系统的开发,所使用的示例工程如下:

(1)03_network_mqtt
(2)06_bus_modbus_rtu_master
(3)06_bus_ethercat_master_csp
硬件相关说明
(1) 主控系统:睿擎派

(2) 伺服系统:汇川IS620NS1R6I

(3) 伺服电机:汇川ISMH1 20B30CB

(4)路继电器模块:叶帆科技 YF3210-Q4物联网智能模块

(5)LED灯泡:12V-24V

硬件连接拓扑图

通信协议约定
WEB前端和睿擎派设备通过MQTT协议进行通信,主要功能就是,前端页面可以远程操作伺服电机的启停,速度,还有运转方向。另外还可以远程开灯。所以我们定义一个南向的控制信息帧(JSON格式):
{
cmd: “state”,
argv: 0
}
cmd和argv对应的命令和参数如下:
“state” – 电机状态 argv: 0 – 停止 1 – 运行
“dir” – 运转方向 0 – 逆时针 1 – 顺时针
“pos” – 运转步长(脉冲数) argv: 建议 1000 ~ 10000 之间变化
“led” - 灯的状态 argv:0 – 关闭 1 – 打开
对应的topic为: /mqtt/command
北向状态信息帧(每秒上传一次):
{
state: 0, //电机状态
dir:0, //运转方向
pos: 1000, //目标每秒运转步长(脉冲)
led:0, //灯的状态
error_wrod: 0, //故障字
status_word: 0, //伺服运行状态字
cur_pos: 0, // 电机当前位置 (脉冲)
cur_speed:0, //电机当前最大限速 (脉冲/秒)
cur_torque: 0, //电机当前转矩
voltage:0.0, //母线电压
current:0.0, //相电流
temp:0.0, //电机温度
speed: //实际点击转速(rpm)
}
status_word:
0x0023:伺服已上电,处于就绪状态;
0x0027:伺服准备运行;
0x0037:伺服正在运行;
0x0080:伺服故障。
对应的topic为: /mqtt/message
软件开发
一、 睿擎派嵌入系统开发
(1)新建项目
由于EtherCAT总线驱动伺服相对复杂,所以我们基于06_bus_ethercat_master_csp示例工程创建我们的项目YFMechPilot,额外再添加MQTT和Modbus功能。

另外我们的网段和默认的开发板不同,所以我们需要修改网口0的IP地址等相关信息,并部署到睿擎派。

(3)拷贝文件
我们从06_bus_modbus_rtu_master项目和03_network_mqtt项目里拷贝modbus_rtu_master_example.c 和 paho_mqtt_example.c 文件到YFMechPilot项目里,并且分别改名为 modbus_rtu_master.c 和 paho_mqtt.c。

(4)修改代码
1、modbus_rtu_master.c代码修改
4路继电器模块,我们使用第二路来控制LED灯的亮灭,所以增加如下函数,来控制灯的状态,0-灭,1-亮
intled_control(intstate){ modbus_t*ctx; intrc; led_status = state; ctx =modbus_new_rtu("/dev/uart5",9600,'N',8,1); if(ctx ==NULL) { rt_kprintf("Unable to create the libmodbus context\n"); return-1; } modbus_set_slave(ctx,1); modbus_set_response_timeout(ctx,1,0); modbus_rtu_set_serial_mode(ctx, MODBUS_RTU_RS485); modbus_rtu_set_rts(ctx, RS485_RTS_PIN, MODBUS_RTU_RTS_UP); if(modbus_connect(ctx) ==-1) { rt_kprintf("Connection failed\n"); modbus_free(ctx); return-1; } //控制第二路继电器的开和关 rc =modbus_write_bit(ctx,1,state); if(rc ==-1) { rt_kprintf("Failed to modbus_write_bit\n"); modbus_close(ctx); modbus_free(ctx); return-1; } rt_kprintf("modbus_write_bit rc=%d\n", rc); modbus_close(ctx); modbus_free(ctx); return0; }
2、paho_mqtt.c代码修改
MQTT_URI根据实际进行填写(也可以采用默认的”tcp://broker.emqx.io:1883”),
值得说明的是,EMQ 提供的公共 MQTT 服务有两个接入点:
broker.emqx.io (全球节点,部署于 AWS 美国俄勒冈)
broker-cn.emqx.io (中国节点,部署于腾讯云上海)
这些服务器由 EMQX 集群组成,每个集群包含 2 个节点,为全球用户提供免费的 MQTT服务,主要用于测试和学习场景。
发送和订阅的Topic进行如下修改。
#defineMQTT_SUBTOPIC"/mqtt/command"#defineMQTT_PUBTOPIC"/mqtt/message"
在mqtt_sub_callback函数里,处理南向发下的控制帧,代码如下:
staticvoidmqtt_sub_callback(MQTTClient *c, MessageData *msg_data){ *((char*)msg_data->message->payload + msg_data->message->payloadlen) ='\0'; char*json_str = (char*)msg_data->message->payload; LOG_D("Topic: %.*s 接收消息: %s", msg_data->topicName->lenstring.len, msg_data->topicName->lenstring.data, json_str); //消息解析 // 步骤1:解析JSON数据 cJSON *root =cJSON_Parse(json_str); if(root == RT_NULL) // JSON格式错误 { LOG_E("JSON解析失败!无效格式: %s", json_str); return; } // 步骤2:提取cmd和argv字段,校验字段存在性 cJSON *cmd_item =cJSON_GetObjectItem(root,"cmd"); cJSON *argv_item =cJSON_GetObjectItem(root,"argv"); if(cmd_item == RT_NULL || !cJSON_IsString(cmd_item)) { LOG_E("JSON缺少有效cmd字段!"); cJSON_Delete(root); return; } if(argv_item == RT_NULL || !cJSON_IsNumber(argv_item)) { LOG_E("JSON缺少有效argv字段!"); cJSON_Delete(root); return; } // 步骤3:获取字段值 constchar*cmd = cmd_item->valuestring; intargv = argv_item->valueint; // 适配argv为整数(状态/步长/LED均为整数) LOG_I("云端指令:cmd=%s, argv=%d", cmd, argv); // 步骤5:根据cmd分支处理业务逻辑 if(strcmp(cmd,"state") ==0) // 电机状态控制 { servo_run = argv; } elseif(strcmp(cmd,"dir") ==0) // 运转方向 { servo_dir = argv; } elseif(strcmp(cmd,"pos") ==0) // 电机步长设置(脉冲数) { // 校验步长范围(1000~10000) if(argv >=1000&& argv <= 10000) { motor_v = argv; // 赋值给全局步长变量(EtherCAT代码中使用) } } else if (strcmp(cmd, "led") == 0) // LED状态控制 { if (argv == 0 || argv == 1) { led_control(argv); // 调用LED控制函数(需你实现Modbus RTU逻辑) } else { LOG_W("无效的led argv值!仅支持 0(关闭)/1(打开)"); } } else // 未知指令 { LOG_W("未知cmd指令:%s", cmd); } cJSON_Delete(root); // 必须释放,避免内存泄漏 return;}
3、ethercat_csp.c代码修改
由于我们WEB网页要显示很多信息,比如要显示母线电压,相电流,电机温度,实际转速等内容,所以我们扩展tpdo_csp定义如下:
structtpdo_csp{ uint16_terror_word; uint16_tstatus_word; int32_tcur_pos; int32_tcur_speed; int16_tcur_torque; // 新增:与PDO条目顺序一致 uint16_tvoltage; // 母线电压(单位:0.1V) int16_t current; // 相电流(单位:0.1A) uint16_ttemp; // 电机温度(单位:1℃) int16_t speed; // 实际转速 rpm};
同时slave1_input_pdo_entries的结构也要扩展。
staticec_pdo_entry_info_tslave1_input_pdo_entries[] = { {0x603F,0x00,16},// 603Fh(error) {0x6041,0x00,16},// 6041h(status) {0x6064,0x00,32},// 6064h(current postion) {0x606C,0x00,32},// 606Ch(current speed) {0x6077,0x00,16},// 6077h(current torque) // 新增 {0x200B,0x1B,16},// voltage(母线电压,16位) {0x200B,0x19,16},// current(相电流,16位) {0x200B,0x1C,16},// temp(电机温度,16位) {0x200B,0x38,16},// speed(实际电机转速,16位)};
slave_pdos定义的个数也要对应调整
ec_pdo_info_tslave_pdos[] = { {0x1600,5, slave1_output_pdo_entries }, {0x1a00,9, slave1_input_pdo_entries }, //5条修改为9条 {0x1600,5, slave1_output_pdo_entries }, {0x1a00,9, slave1_input_pdo_entries }, //5条修改为9条};
另外我们除了电机的启停外,还需要调整速度,我们通过调整步长pos的值来控制电机转的快慢。我们定义了一个motor_v变量。
rmap->dest_pos += motor_v;
为了把伺服器获取的实时数据发送到MQTT服务器,也就是tmap里面的内容。
tmap = servo_tpdo_get(&csp_master, slave_counts, slave);
我们增加如下代码:
//1秒发送一次 if(rt_tick_get() - last_ms > 1000) { last_ms =rt_tick_get(); // 1. 分配邮箱消息内存(动态分配,从任务释放) servo_status_msg_t*msg =rt_malloc(sizeof(servo_status_msg_t)); if(msg == RT_NULL) { LOG_E("分配消息内存失败!"); continue; } // 2. 拷贝数据到消息(关中断保护,避免数据竞争) rt_enter_critical(); msg->servo_run = servo_run; msg->servo_dir = servo_dir; msg->motor_v = motor_v; msg->led_status = led_status; msg->error_word = tmap->error_word; msg->status_word = tmap->status_word; msg->cur_pos = tmap->cur_pos; msg->cur_speed = tmap->cur_speed; msg->cur_torque = tmap->cur_torque; msg->voltage = tmap->voltage; msg->current = tmap->current; msg->temp = tmap->temp; msg->speed = tmap->speed; rt_exit_critical(); // 3. 发送消息到邮箱(非阻塞,不影响主任务) err =rt_mb_send(status_mailbox, (rt_ubase_t)msg); if(err != RT_EOK) { LOG_E("邮箱发送失败!"); rt_free(msg);// 发送失败释放内存 } }
需要注意的是,直接mqtt推送的代码不能放在这个代码逻辑里面,因为一旦放入,那电机将会停止旋转。所以需要我们新开一个任务,通过邮箱的方式传递数据,然后再发送到MQTT服务器。
/*** 新增:从任务 - 接收邮箱消息,生成JSON并发布MQTT*/staticvoidservo_status_task(void*param){ servo_status_msg_t*msg = RT_NULL; rt_err_terr; while(1) { // 等待邮箱消息(RT_WAITING_FOREVER:永久等待,直到有消息) err =rt_mb_recv(status_mailbox, (rt_ubase_t*)&msg, RT_WAITING_FOREVER); if(err != RT_EOK || msg == RT_NULL) { rt_thread_mdelay(100); continue; } // 1. 消息转JSON char*json_str =msg_to_json(msg); if(json_str !=NULL) { // 2. MQTT发布(耗时操作在从任务执行) mq_publish(json_str); // 3. 可选:打印日志(不影响主任务) LOG_D("伺服状态JSON:%s", json_str); // 4. 释放JSON内存 rt_free(json_str); } // 5. 释放邮箱消息内存 rt_free(msg); }}
二、 WEB前端开发
1. 概述
电机机械臂前端系统是一个基于 WebGL 的实时可视化应用,结合 Vue 3、Three.js 与 MQTT 协议,实现可视化三维演示 + 远程指令控制 + 实时状态监控的一体化体验。系统主要目标如下:
(1). 直观呈现伺服电机与工业机械臂的协同运行状态;
(2). 提供人机交互界面,保障启停、方向、速度、灯光等操作的远程执行;
(3). 通过 MQTT 获取设备实时数据,驱动动画、灯光及数据面板联动,确保画面与实际工况同步;
(4). 遇到通信异常或设备故障时及时反馈并自动进入安全状态。
2. 功能说明
2.1 三维场景展示
基于 Three.js 构建统一场景,内含伺服电机、工业机械臂、灯泡及地面网格等对象;
通过 AnimationMixer 控制电机与机械臂动画,实现启动、停止、正反转、速度变化等效果;
灯泡模型配合点光源呈现开关效果,强化联动体验。
2.2 实时状态联动
订阅 /mqtt/message,实时解析 state、status_word、dir、pos、led、speed 等字段;
根据状态自动调整动画、灯光及数据面板,保障前端显示与真实设备一致;
当 status_word 表示运行/就绪/准备/故障等不同阶段时,界面给出对应文字提示。
2.3 远程控制能力
左侧设备控制面板提供启动、停止、正/反转、加/减速、灯光开关等命令按钮;
点击按钮后,通过 sendMqttCommand 将 { cmd, argv } JSON 消息发送至 /mqtt/command,驱动后端或真实设备执行;
加减速按钮将步进值 pos 在 1000~10000 范围内调整,并同步更新动画播放速度。
2.4 数据监控面板
右侧数据监控面板展示电机名称、实时转速、扭矩、电流、电压、温度、步进值等;
status_word 被转换为伺服正在运行 / 伺服准备运行 / 伺服故障等中文描述,降低理解门槛。
2.5 异常与安全处理
每秒接收一次 /mqtt/message,超过 3 秒未收到或 MQTT 连接断开时,自动停止电机与机械臂动画并关闭灯光;
状态即时切换为停止,并在控制台记录告警日志,便于追踪问题;
支持 error_word 的拓展,可与后端约定错误码字典,后续用于更细粒度的异常提示。
3. 架构介绍
3.1 技术栈与模块划分
前端框架: Vue 3 (script setup) ,负责 UI 组织、状态管理与生命周期控制
三维渲染: Three.js + FBXLoader + OrbitControls,构建 3D 场景、加载模型、处理交互
消息通信:mqtt.js (WebSocket),与 MQTT 服务器交互,订阅设备状态、发送控制指令
UI 组件: 自定义控制面板 / 数据面板,提供操作入口与实时数据展示
3.2 数据流
下行数据:设备通过 MQTT 服务器推送 /mqtt/message 前端 handleMqttMessage 更新 motorData、控制动画和灯光。
上行指令:用户点击控制按钮 sendMqttCommand 发布至 /mqtt/command 设备执行并反馈结果。
3.3 状态管理
motorData:存放电机实时参数(转速、扭矩、电流、电压、温度、status_word、pos 等);
obotArmData:存放机械臂展示数据(角度、伸展、负载等,当前用于界面展示);
其余用于存放动画速度、方向、灯光状态、面板显隐等。
3.4 安全机制
startMqttTimeoutCheck + handleMqttTimeout:负责检测消息超时并触发停机逻辑;
mqttClient.on(‘close’|’offline’):连接断开立即执行停机;
getStatusWordText:对伺服状态码进行解析和人性化提示。
4. 代码结构说明(src/App.vue)
4.1 主要函数
场景相关:initMainScene、createLightBulb、 oggleLightBulb、startRobotArmLoop、stopRobotArmAnimation 等;
MQTT 相关:initMqttClient、sendMqttCommand、handleMqttMessage、getStatusWordText、startMqttTimeoutCheck;
控制指令:playMotorAnimationLoop、stopMotorAnimation、speedUpMotor、slowDownMotor、setMotorForward、setMotorReverse、 urnOnLight、 urnOffLight。
4.2 生命周期
(1). onMounted
处理 viewport 兼容逻辑;
初始化 Three.js 场景与动画循环;
加载机械臂、电机模型及灯泡;
建立 MQTT 连接并启动超时检测;
监听窗口尺寸变化,保持画面自适应。
(2). onUnmounted
清理 ResizeObserver、动画帧、Three.js 控制器与渲染器;
断开 MQTT 连接,停止超时检测,释放资源。
4.3 状态码与动画联动
当 status_word 标记为运行时,自动播放电机动画并按照 speed/5.5 的比例调整 timeScale;机械臂同步以 1.0 速度循环;
当状态变为就绪/准备/故障/停止时,停止相关动画并更新 UI;
dir 控制 timeScale 的正负,led 控制灯泡明灭,pos 在加速/减速时更新。
演示效果


程序部署到睿擎派后,在命令行进行程序启动。

(1) 先输入mqtt_init命令,初始化mqtt服务连接。
(2) 然后输入ect_csp命令,初始化伺服器设备
(3) 在浏览器输入WEB前端url连接,打开WEB页面。

进行对应的操作电机的启动,停止,调速,更换方向,开灯和关灯灯操作。
演示视频地址

https://www.bilibili.com/video/BV1WfUBBTEZn/?buvid=XU9CDD99373E71FEACD8BC8A212D50C9F810A&is_story_h5=false&mid=SFXHz1RtesqlFJvcrtgcvA%3D%3D&plat_id=504&share_from=ugc&share_medium=android&share_plat=android&share_source=WEIXIN&share_tag=s_i&spmid=dt.dt.0.0×tamp=1764226777&unique_k=MvqTW1S&up_id=1024128963
代码地址
(1) 睿擎派嵌入式代码
https://gitee.com/yfiot_project/yfmech-pilot
(2) WEB前端代码
链接:https://pan.baidu.com/s/12om9JQTkz0cdjhXSPivL7w?pwd=mmsw
提取码:mmsw
————————————————
版权声明:本文为RT-Thread论坛用户「yefanqiu」的原创文章,遵循CC 4.0 BY-SA版权协议,转载请附上原文出处链接及本声明。
原文链接:
https://club.rt-thread.org/ask/article/a1219d6e4a12983f.html
-
控制系统
+关注
关注
41文章
6893浏览量
113563 -
运动控制
+关注
关注
5文章
792浏览量
34263 -
机械臂
+关注
关注
13文章
582浏览量
25967
发布评论请先 登录
基于睿擎派的工业FOC无刷电机控制系统与WEB推流监看系统| 技术集结
CANopen转Profinet是一种构建于控制局域网设备之上的协议网关
睿擎EtherCAT多轴控制技术:如何实现低抖动高精度运动控制 | 深度解析
睿擎UVC-AI方案:基于YOLO的人脸检测系统开发|技术集结
睿擎混合部署方案:基于QT的电机驱动系统开发|技术集结
EtherCAT转Profinet协议转换网关实现PLC与机械臂通讯的配置案例
基于睿擎派轻松玩转Modbus工业通信
AioneMotor_DSC28034_L3F驱控一体板现货库存
睿擎平台极简开发重要实践—— PinMux 配置工具 | 睿擎派试用名单公示

【睿擎派】云端一体,多种通信协议构建机械臂运动控制系统| 技术集结
评论