背景
使用的開發(fā)板為大疆的 RoboMaster-C 型開發(fā)板,基礎(chǔ)工程為 rt-thread>bsp>stm32f407-robomaster-c
MSG模塊開發(fā)
MSG 模塊主要應(yīng)用于應(yīng)用層線程間通訊,實(shí)現(xiàn)一種發(fā)布者發(fā)布話題,訂閱者訂閱話題的通訊方式。接下來主要討論開發(fā) MSG 模塊的初衷,以及與其他線程間通訊方式的對(duì)比。
開發(fā)的初衷是受 ROS 及其他學(xué)校的如吉林大學(xué)的軟總線中心,湖南大學(xué)的消息中心模塊的啟發(fā),(主要還是苦全局變量久矣),開發(fā)一套簡單易用、線程安全、模塊解耦、邏輯清晰的線程間通訊機(jī)制顯得尤為重要。
但是 RTOS 中不是已經(jīng)提供了諸如:郵箱,消息隊(duì)列、信號(hào)(軟中斷,這里不具體討論)的線程間通信機(jī)制,為什么不直接用呢?接下來就對(duì)各個(gè)通信方式進(jìn)行對(duì)比分析:
郵箱:郵箱中的每一封郵件只能容納固定的 4 字節(jié)內(nèi)容,當(dāng)需要傳輸更大的數(shù)據(jù)時(shí),可以將指針作為郵件的內(nèi)容進(jìn)行傳輸。但使用郵箱有一個(gè)問題:接收郵件,就會(huì)將郵件取出,也就是說,發(fā)出去的信只有一份,被一個(gè)線程接收后,其他的線程就收不到這封信了,因此面對(duì)多個(gè)消費(fèi)者的情況時(shí)就會(huì)出現(xiàn)問題。而且郵箱的機(jī)制是必須要現(xiàn)有生產(chǎn)者發(fā)出一封郵件,對(duì)應(yīng)的消費(fèi)者才有郵件可讀,也就是說,每次讀取其實(shí)是阻塞性質(zhì)的,生產(chǎn)者的郵件發(fā)出之前,消費(fèi)者是讀不到數(shù)據(jù)的,也不能讀取使用上一次的歷史數(shù)據(jù),因此只要生成者發(fā)送郵件不及時(shí)就容易出現(xiàn)問題。
但是在機(jī)器人的開發(fā)中,經(jīng)常會(huì)面對(duì)多個(gè)消費(fèi)者,以及當(dāng)數(shù)據(jù)更新不及時(shí)但為了維持控制頻率就先延用上一次數(shù)據(jù)的情況(當(dāng)然,長時(shí)間數(shù)據(jù)未更新的情況下沿用歷史數(shù)據(jù)是絕對(duì)不行的!輕則抖動(dòng),重則失控!例如遙控器、電機(jī)離線等,對(duì)于這些情況也有相應(yīng)的離線檢測和處理機(jī)制)。
消息隊(duì)列:消息隊(duì)列是郵箱的擴(kuò)展,傳輸?shù)臄?shù)據(jù)就包括指向消息的指針和消息的長度,便于數(shù)據(jù)解析獲取。但上述郵箱通訊方式的弊端依舊存在。
全局變量:全局變量讀寫直接快速,使用簡單,但其如果在 RTOS 中濫用,其危害性就很恐怖了,我們應(yīng)該盡量避免使用全局變量,具體的影響和危害就不展開講了。
MSG模塊:msg 模塊主要解決的就是上述郵箱及消息隊(duì)列面對(duì)多個(gè)消費(fèi)者等問題,以及避免全局變量滿天飛的情況。msg 模塊較為輕量化,是對(duì) ROS 通訊機(jī)制的拙略模仿,模仿其話題、發(fā)布者、訂閱者之間的通訊機(jī)制。訂閱者讀取話題,并不會(huì)取出及改動(dòng)話題的數(shù)據(jù),不會(huì)影響到其他訂閱者對(duì)話題的讀取。并且訂閱者讀取話題時(shí)不是阻塞的,不需要發(fā)布者先更新話題,訂閱者和發(fā)布者之間并沒有先后順序。而且其是線程安全的,使用信號(hào)量進(jìn)行保護(hù),不過讀寫速度肯定不如直接使用全局變量快,但基本可以忽略,利遠(yuǎn)大于弊。
代碼實(shí)現(xiàn)
這是對(duì)話題、訂閱者、發(fā)布者這幾個(gè)重要對(duì)象的定義。話題對(duì)象包含名字(訂閱和發(fā)布的話題主要就通過名字判斷和聯(lián)系起來)、指向數(shù)據(jù)的指針、提供安全性的信號(hào)量;發(fā)布者和訂閱者包含話題名稱、指向話題的指針、消息的長度。這里需要注意,話題中 msg 示例的數(shù)據(jù)格式,需要發(fā)布者和訂閱者都知道才能正確解析,和 ROS 中的 msg 類似。
/**
- @brief 話題類型
/
typedef struct topic
{
char name[MSG_NAME_MAX];
void msg; // 指向msg實(shí)例的指針
rt_sem_t sem;
} topic_t;
/
@brief 訂閱者類型.每個(gè)發(fā)布者擁有發(fā)布者實(shí)例,并且可以通過鏈表訪問所有訂閱了自己發(fā)布的話題的訂閱者
*/
typedef struct sublisher
{
const char topic_name;
topic_t tp; // 話題的指針
uint8_t len; // 消息類型長度
} subscriber_t;
/
@brief 發(fā)布者類型.每個(gè)發(fā)布者擁有發(fā)布者實(shí)例,并且可以通過鏈表訪問所有訂閱了自己發(fā)布的話題的訂閱者
*/
typedef struct publisher
{
const char *topic_name;
topic_t *tp; // 話題的指針
uint8_t len; // 消息類型長度
} publisher_t;
以下是訂閱者和發(fā)布者注冊(cè)的函數(shù),其注冊(cè)不需要分先后順序:
/**
@brief 注冊(cè)成為消息發(fā)布者
@param name 發(fā)布者發(fā)布的話題名稱(話題)
@param len 消息類型長度,通過sizeof()獲取
@return publisher_t* 返回發(fā)布者實(shí)例
*/
publisher_t *pub_register(char *name, uint8_t len){
uint8_t check_num = check_topic_name(name);
publisher_t *pub = (publisher_t *)rt_malloc(sizeof(publisher_t));
if(!check_num){ // 如果不存在重名的話題實(shí)例
topic_obj[idx] = (topic_t )rt_malloc(sizeof(topic_t));
rt_memset(topic_obj[idx], 0, sizeof(topic_t));
if(topic_obj[idx] == NULL){
LOG_E("malloc failed!");
return NULL;
}
topic_obj[idx]->msg = (void )rt_malloc(len);
if(topic_obj[idx]->msg == NULL){
LOG_E("malloc failed!");
return NULL;
}
topic_obj[idx]->sem = rt_sem_create(name, 1, RT_IPC_FLAG_PRIO);
rt_strcpy(topic_obj[idx]->name, name);
pub->tp = topic_obj[idx];
pub->topic_name = topic_obj[idx]->name;
pub->len = len;
idx++;
}
else{
pub->tp = topic_obj[check_num - 1];
pub->topic_name = topic_obj[check_num - 1]->name;
pub->len = len;
}
return pub;
}
/
@brief 訂閱name的話題消息
@param name 話題名稱
@param data 消息長度,通過sizeof()獲取
@return subscriber_t* 返回訂閱者實(shí)例
*/
subscriber_t *sub_register(char *name, uint8_t len){
// 和發(fā)布者同樣的流程,直接調(diào)用發(fā)布者的注冊(cè)函數(shù)
subscriber_t *sub = (subscriber_t *)pub_register(name, len);
return sub;
}
注冊(cè)時(shí)通過傳入的話題名稱和消息長度創(chuàng)建對(duì)應(yīng)的話題,會(huì)先檢查目前已有的話題中是否有同樣名稱的話題,如有則返回已有的話題地址,如果沒有那就創(chuàng)建新的話題。
因此,話題的名稱很重要,如果訂閱者和發(fā)布者創(chuàng)建時(shí)名稱差了一個(gè)字符就會(huì)對(duì)不上,推薦話題的名稱直接使用宏定義進(jìn)行管理,避免出錯(cuò) (否則出錯(cuò)了很難查的)
以下是訂閱者和發(fā)布者處理話題的簡單實(shí)現(xiàn):
/**
- @brief 發(fā)布消息
- @param pub 發(fā)布者實(shí)例指針
- @param data 數(shù)據(jù)指針,將要發(fā)布的消息放到此處
- @return uint8_t 返回值為0說明發(fā)布失敗,為1說明發(fā)布成功
*/
uint8_t pub_push_msg(publisher_t pub, void data){
if(rt_sem_take(pub->tp->sem, RT_WAITING_NO)){
LOG_W("take sem failed!");
return 0;
}
rt_memcpy(pub->tp->msg, data, pub->len);
rt_sem_release(pub->tp->sem);
return 1;
}
/
@brief 獲取消息
@param sub 訂閱者實(shí)例指針
@param data 數(shù)據(jù)指針,接收的消息將會(huì)放到此處
@return uint8_t 返回值為1說明獲取到了新的消息
*/
uint8_t sub_get_msg(subscriber_t *sub, void *data){
rt_memcpy(data, sub->tp->msg, sub->len);
return 1;
}
可以看出目前是十分簡陋的(輕量化(不是),只有在發(fā)布者更新話題時(shí)使用信號(hào)量進(jìn)行了保護(hù),從而保證寫入的完整性。但訂閱者獲取消息是沒有保護(hù)的,因?yàn)橹灰WC了發(fā)布者更新數(shù)據(jù)的完整性,訂閱讀取話題是沒有問題的。
但其也是還有許多需要完善的地方,魯棒性仍需加強(qiáng),例如 rt_memcpy 并不保證原子性。這里主要就是提供一個(gè)解決思路,拋磚引玉。
使用示例
/* 首先需要在.h文件中定義話題的數(shù)據(jù)格式 /
struct msg_test{
uint8_t id;
uint8_t data[5];
}
/ 在發(fā)布者的.c文件中 */
publisher_t pub;
stuct msg_test msg_p;
pub = pub_register("msg_test", sizeof(struct msg_test));
msg_p.id = 1;
for(uint8_t i = 0, i < 5, i++){
msg_p.data[0] = i;
}
pub_push_msg(pub, &msg_p);
/ 在訂閱者的.c文件中 */
subscriber_t *sub;
stuct msg_test msg_s;
sub = sub_register("msg_test", sizeof(struct msg_test));
sub_get_msg(sub, &msg_s);
-
機(jī)器人
+關(guān)注
關(guān)注
211文章
28562瀏覽量
207698 -
RTOS
+關(guān)注
關(guān)注
22文章
817瀏覽量
119766 -
STM32F407
+關(guān)注
關(guān)注
15文章
188瀏覽量
29562 -
RT-Thread
+關(guān)注
關(guān)注
31文章
1301瀏覽量
40265 -
ROS
+關(guān)注
關(guān)注
1文章
279瀏覽量
17041
發(fā)布評(píng)論請(qǐng)先 登錄
相關(guān)推薦
評(píng)論