項目背景及功能
受國際形勢復雜多變的影響,工業控制領域長期以來以國外產品及系統為主導的格局正在發生轉變。當下國家大力倡導國產自主可控的發展方向,為響應這一戰略轉變,對原有控制系統進行重構升級,以契合國產化替代的潮流。
本項目所構建的是一個原型系統,核心功能架構如下: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文章
6952瀏覽量
114084 -
運動控制
+關注
關注
5文章
821瀏覽量
34534 -
機械臂
+關注
關注
14文章
596瀏覽量
26120
發布評論請先 登錄
睿擎派3562快速上手體驗
基于睿擎派的工業FOC無刷電機控制系統與WEB推流監看系統| 技術集結
睿擎EtherCAT多軸控制技術:如何實現低抖動高精度運動控制 | 深度解析
睿擎UVC-AI方案:基于YOLO的人臉檢測系統開發|技術集結
睿擎混合部署方案:基于QT的電機驅動系統開發|技術集結
EtherCAT轉Profinet協議轉換網關實現PLC與機械臂通訊的配置案例
基于睿擎派輕松玩轉Modbus工業通信
睿擎平臺極簡開發重要實踐—— PinMux 配置工具 | 睿擎派試用名單公示
【睿擎派】云端一體,多種通信協議構建機械臂運動控制系統| 技術集結
評論