ROS 簡介
最初 2007 年左右,斯坦福機(jī)器人實驗室的兩個博士生,Eric Berger 和 Keenan Wyrobek 發(fā)現(xiàn)身邊的同學(xué)們對機(jī)器人開發(fā)有一種望而卻步的感覺。因為機(jī)器人本身是一個跨專業(yè)的學(xué)科,做軟件的同學(xué)們不太了解機(jī)械結(jié)構(gòu),不熟悉機(jī)器人的設(shè)計裝配流程;做算法的同學(xué)們又不太了解嵌入式,不太清楚底層傳感器驅(qū)動的工作原理,于是合作起來會碰到很多障礙。為了解決這個問題,他們設(shè)計了最初的 Robot Operating System (ROS),極大地提高了團(tuán)隊合作效率。
由于 ROS 簡單好用上手快,從 2007 年 ROS 發(fā)布第一版并舉行第一屆全球 ROS Conf,到 2012 年底第五屆會議,使用 ROS 的實驗室已經(jīng)遍布全球了。2013 年 ROS 就由 Open Source Robotics Foundation (OSRF) 接手維護(hù)了。
另一方面,2005 年斯坦福拿下 DARPA 無人駕駛挑戰(zhàn)賽冠軍一舉成名,隨后 ROS 也誕生在斯坦福,很快在無人駕駛領(lǐng)域 ROS 也得到了廣泛應(yīng)用,并且 2018 DARPA 無人駕駛挑戰(zhàn)賽專門設(shè)置了 ROS 賽道,參賽隊伍需要在 ROS Gazebo 模擬環(huán)境下測試自己的無人車并得到評分。
雖然 Robot Operating System (ROS) 取名為機(jī)器人操作系統(tǒng),但其實它并不是一個操作系統(tǒng),而是在 Linux 之上開發(fā)的一系列軟件包。為了說明 ROS 開發(fā)的簡單,高效和穩(wěn)定,這里簡單介紹一下 ROS 很重要的4個設(shè)計:
Message (消息):有的時候可能會苦惱傳感器的信息應(yīng)該以什么樣的數(shù)據(jù)結(jié)構(gòu)發(fā)送出去,于是 ROS 定義好了各種常見傳感器的數(shù)據(jù)格式,有了模板只需要填充內(nèi)容就可以了,這樣節(jié)省了自定義數(shù)據(jù)結(jié)構(gòu)的時間。另一方面,也可以自己寫一個 .msg 文件定義新的數(shù)據(jù)結(jié)構(gòu),ROS 就可以自動生成對應(yīng)的頭文件。這和 Google 的 protobuf 非常相似,定義數(shù)據(jù)結(jié)構(gòu),就可以自動生成源碼??偠灾?,ROS 的一個消息 (message) 也就是想要發(fā)送出去的一個數(shù)據(jù)包。
Topic (話題):定義好了數(shù)據(jù)結(jié)構(gòu),如何把數(shù)據(jù)穩(wěn)定的發(fā)送出去,穩(wěn)定接收也是個問題。一對一的發(fā)送可能比較簡單,但是如果多個算法需要同一個傳感器輸入,同一個算法又需要不同傳感器輸入,很快數(shù)據(jù)同步就變得棘手了。于是 ROS 采用了發(fā)布 (publish) - 訂閱 (subscribe) 的模式。
比如用 ROS 預(yù)先定義好的數(shù)據(jù)結(jié)構(gòu)發(fā)送圖像數(shù)據(jù),發(fā)布出去的圖像信息就可以在 /camera 這個話題下找到,所有訂閱了這個話題的節(jié)點(diǎn)都會收到消息。相當(dāng)于我們把消息發(fā)給報社,所有訂了報紙的人就會收到消息,這樣我們只管發(fā)消息就是了,剩下的 ROS 會保證所有節(jié)點(diǎn)都收到同步的消息。
Node (節(jié)點(diǎn)):像前面說的那樣,消息發(fā)布出去后,ROS會保證所有訂閱了這個話題的節(jié)點(diǎn)都會收到同步的消息。于是一個節(jié)點(diǎn)的作用通常就是收一些消息,做一些處理,可能再發(fā)布一些新的消息。比如人臉檢測的節(jié)點(diǎn),可能會訂閱圖像相關(guān)的話題,識別完再告訴其他節(jié)點(diǎn)自己識別的結(jié)果。
通常,一個節(jié)點(diǎn)只完成一件事情,例如人臉識別的節(jié)點(diǎn)就只做人臉識別,不會同時又做摔倒檢測。這樣一個節(jié)點(diǎn)只處理一個比較小的任務(wù),再合作實現(xiàn)更大的目標(biāo)。順便一提,一個節(jié)點(diǎn)不等于一臺電腦,因為一臺電腦如果性能比較強(qiáng),完全可以部署好幾個節(jié)點(diǎn),這樣也充分利用資源。
Service (服務(wù)):一方面節(jié)點(diǎn)可以通過訂閱消息獲得需要的信息,另一方面節(jié)點(diǎn)之間也可以通訊。例如目標(biāo)追蹤的節(jié)點(diǎn),可能先需要調(diào)用目標(biāo)檢測節(jié)點(diǎn)的服務(wù),知道目標(biāo)在哪再去追蹤。所以服務(wù)就是字面上的意思,每個節(jié)點(diǎn)可以提供一些服務(wù)供其他節(jié)點(diǎn)調(diào)用。
于是有了 ROS 之后,做嵌入式的同學(xué)只需要把傳感器信息 (message) 發(fā)布出去,做算法的同學(xué)訂閱自己需要的話題 (topic),作為算法輸入,再發(fā)布對應(yīng)的輸出。這樣每個同學(xué)只用專心維護(hù)自己的節(jié)點(diǎn),確保自己節(jié)點(diǎn)的輸入輸出正確,整個系統(tǒng)就能正常運(yùn)作了。
除了軟件設(shè)計,前面提到的 ROS Gazebo 仿真環(huán)境也極大地加快了迭代過程,在真正的機(jī)械臂加工裝配之前,先在模擬環(huán)境確保可以實現(xiàn)預(yù)期的運(yùn)動,也避免了不必要的試錯過程。
當(dāng)然,Gazebo 也可以和實際的機(jī)器人連接進(jìn)行聯(lián)合調(diào)試 [1]:
RT-Thread 與 ROS
那么問題來了,前面提到 ROS 是在 Linux 上運(yùn)行的一套軟件框架,Linux 本身并不是實時系統(tǒng),機(jī)器人一些對實時性要求比較高的任務(wù)并不太適合用 Linux,而 RT-Thread 雖然是實時操作系統(tǒng)(RTOS),但畢竟 MCU 的資源有限,并不能直接運(yùn)行完整的 ROS。
于是,通常的做法是利用 Linux 豐富的軟件包實現(xiàn)一些頂層算法,而 RT-Thread 則負(fù)責(zé)實時控制相關(guān)的任務(wù),它們之間的通信就是后面會介紹到的 rosserial 和 micro_ros。
rosserial 和 micro_ros 的區(qū)別
它們共同的目標(biāo)都是為了把 MCU 接入 ROS,使得 MCU 能和 ROS 通信,并且在 MCU 上調(diào)用 ROS 的 API,主要區(qū)別就在于 rosserial 是針對 ROS1,而 micro_ros 是針對 ROS2 [2]。
第一代的 ROS 發(fā)展很多年后,當(dāng)然也暴露出很多設(shè)計不合理的地方,比如有多個 ROS 主機(jī)的時候,需要設(shè)置 ROS_MASTER_URI 和 ROS_HOST_NAME 環(huán)境變量,幫助 ROS Master 找到不同的主機(jī)的 IP。
一旦主機(jī)變多,IP 地址又不太固定的時候就會變得很麻煩,如果能讓 ROS 自動發(fā)現(xiàn)主機(jī)就會方便很多。為了解決第一代 ROS 的歷史遺留問題,并且添加新功能,OSRF 發(fā)現(xiàn)這會造成新的 ROS 破壞性地不兼容以前的版本,于是他們干脆就直接宣布進(jìn)入第二代 ROS,重新再開發(fā)一套新的 ROS,這也就是 ROS2。
新一代的 ROS2 使用 Data Distribution Service (DDS) 通信,可以自動發(fā)現(xiàn)主機(jī),這樣分布式的系統(tǒng)設(shè)計就更加方便了,但是 DDS 并不算是一個輕量級的框架,如果要讓 MCU 接入 DDS 必然需要足夠的硬件資源。
然而 ROS2 主要針對的是 64 位的中高端平臺,MCU 并不是 ROS2 的主要支持對象,以至于第一代的 rosserial 到了第二代也基本放棄維護(hù)了。盡管如此,還是有不少開發(fā)者希望能讓 MCU 接入 ROS2,直接在 MCU 上調(diào)用 ROS2 的 API,于是最終還是有了 Micro ROS。
雖然 Micro ROS 借助 Micro XRCE-DDS 實現(xiàn)了輕量級的 DDS,但是至少還是需要一個 32 位的中端 MCU,不像第一代的 rosserial 那樣可以運(yùn)行在 8 位的低端 MCU 上。
RT-Thread 控制 Kobuki 機(jī)器人
前面介紹了 ROS1/ROS2,也介紹了 rosserial (ROS1) 和 micro_ros (ROS2) 的區(qū)別,現(xiàn)在 RT-Thread 已經(jīng)有了 rosserial 和 micro_ros 軟件包分別能和 ROS1/ROS2 通信,同時也有 Kobuki 機(jī)器人底盤軟件包 [5] 和激光雷達(dá) rplidar 軟件包 [6],應(yīng)當(dāng)是可以跳過樹莓派。
直接用 RT-Thread 做一個 SLAM 機(jī)器人。順便一提,rosserial 支持串口和 TCP 通信,micro_ros 則支持串口和 UDP 通信;rosserial 只支持 C++,而 micro_ros 支持 C/C++。
下面就以 RT-Thread 配合 ROS 控制 Kobuki 機(jī)器人為例,分別介紹如何在 RT-Thread 上和 ROS1 (rosserial),ROS2 (micro_ros) 通信,并且下面的例子都是以無線 (Wifi) 為例,這樣就可以不需要樹莓派,運(yùn)行 RT-Thread 的 MCU 直接接入 ROS 了。
順便一提,下面的操作只要確保有3個串口,用什么開發(fā)板都可以。,當(dāng)然,如果不需要 RTT 控制臺就只需要2個了。
RT-Thread 使用 ESP8266 聯(lián)網(wǎng)
無論是 rosserial (ROS1),還是 micro_ros (ROS2),聯(lián)網(wǎng)部分都是一樣的,這里就以 ESP8266 的 AT 固件聯(lián)網(wǎng)為例。當(dāng)然,用以太網(wǎng)也是可以的。
在開始 RT-Thread 開發(fā)之前,需要確保用來聯(lián)網(wǎng)的 ESP8266 是使用的 AT 固件,固件可以在這里下載 (ai-thinker_esp8266_at_firmware_dout_v1.5.4.1-a_20171130.rar):
https://docs.ai-thinker.com/en/固件匯總
把 ESP8266 的串口連接到電腦以后,拉低 GPIO0 復(fù)位進(jìn)入固件下載模式,這樣 ESP8266 就可以處理 AT 指令了:
$ esptool.exe --port com5 erase_flash
$ esptool.exe --port com5 write_flash --flash_mode dout 0 Ai-Thinker_ESP8266_DOUT_8Mbit_v1.5.4.1-a_20171130.bin
把 ESP8266 和自己的開發(fā)板串口 (UART2) 連接上之后,根據(jù)自己的開發(fā)板型號,在 RT-Thread Studio 里新建項目。前面提到我們需要3個串口,所以在 driver/board.h 里需要打開三個串口,一個用作控制臺,一個連接 ESP8266,最后一個和 Kobuki 機(jī)器人通信:
# MSH Console
#define BSP_USING_UART1
#define BSP_UART1_TX_PIN “PA9”
#define BSP_UART1_RX_PIN “PA10”
# ESP8266
#define BSP_USING_UART2
#define BSP_UART2_TX_PIN “PA2”
#define BSP_UART2_RX_PIN “PA3”
# Kobuki Robot
#define BSP_USING_UART3
#define BSP_UART3_TX_PIN “PB10”
#define BSP_UART3_RX_PIN “PB11”
接下來在 RT-Thread Studio 里面添加 AT_Device 軟件包:
并且雙擊軟件包修改配置選項,選擇自己的 wifi 模塊,配置 WIFI SSID 和密碼,選擇 UART2 作為通信接口:
保存配置編譯,如果一切正常的話,RT-Thread 上電后會自動連接 WIFI,并且可以 ping 通外部主機(jī):
| /
- RT - Thread Operating System
/ | 4.0.2 build Jun 14 2021
2006 - 2019 Copyright by rt-thread team
[I/sal.skt] Socket Abstraction Layer initialize success.
[I/at.clnt] AT client(V1.3.0) on device uart2 initialize success.
msh 》[I/at.dev.esp] esp0 device wifi is connected.
[I/at.dev.esp] esp0 device network initialize successfully.
[E/at.clnt] execute command (AT+CIPDNS_CUR?) failed!
[W/at.dev.esp] please check and update esp0 device firmware to support the “AT+CIPDNS_CUR?” cmd.
[E/at.clnt] execute command (AT+CIPDNS_CUR?) failed!
[W/at.dev.esp] please check and update esp0 device firmware to support the “AT+CIPDNS_CUR?” cmd.
[E/at.skt] AT socket (0) receive timeout (2000)!
msh 》ping rt-thread.org
32 bytes from 118.31.15.152 icmp_seq=0 time=242 ms
32 bytes from 118.31.15.152 icmp_seq=1 time=245 ms
32 bytes from 118.31.15.152 icmp_seq=2 time=241 ms
32 bytes from 118.31.15.152 icmp_seq=3 time=245 ms
msh 》
當(dāng)然,這一部分聯(lián)網(wǎng)的操作也可以參照 RT-Thread 官網(wǎng)的文檔:
https://www.rt-thread.org/document/site/#/rt-thread-version/rt-thread-standard/application-note/components/at/an0014-at-client
(請復(fù)制至外部瀏覽器打開)
最后我們把 Kobuki 機(jī)器人的串口和 RT-Thread 開發(fā)板的串口 (UART3) 接上,在 RTT Studio 軟件包里添加 Kobuki:
并雙擊軟件包配置 Kobuki 通信接口為 uart3 就可以準(zhǔn)備對接 ROS 了。
ROS1 (rosserial)
第一代 ROS 支持 串口 和 TCP 通信,這里以 TCP 為例,在 RT-Thread Studio 先添加軟件包:
雙擊軟件包后配置使用 TCP 連接并且添加 Kobuki 機(jī)器人的例程:
完整的代碼在 Github 上面都有,所以這里主要解釋 rosserial 的核心初始化代碼。在 MCU 上的初始化和在 PC 上初始化幾乎是一模一樣的,就是首先 setConnection() 定義 ROS Master 的 IP 地址和端口,接下來 initNode() 初始化節(jié)點(diǎn),最后訂閱 /cmd_vel 用來接收電腦傳過來的控制信息,并且設(shè)置 Kobuki 的速度。
static ros::Subscriber《geometry_msgs::Twist》 sub(“cmd_vel”, messageCb );
static void rosserial_kobuki_thread_entry(void *parameter)
{
// Please make sure you have network connection first
// Set ip address and port
nh.getHardware()-》setConnection(“192.168.199.100”, 11411);
nh.initNode();
nh.subscribe(sub);
while (1)
{
nh.spinOnce();
rt_thread_mdelay(500);
}
}
一旦收到 PC 傳來的控制信息,在回調(diào)函數(shù)里更新線性運(yùn)動的速度,和旋轉(zhuǎn)角速度:
static void messageCb( const geometry_msgs::Twist& twist_msg)
{
linear_x = twist_msg.linear.x;
angular_z = twist_msg.angular.z;
}
當(dāng)然,Kobuki 線程里會不停地發(fā)送控制命令,因為Kobuki 底盤的特點(diǎn)是,一旦一段時間沒有收到命令,機(jī)器人就會停止運(yùn)動,所以我們需要不停地發(fā)送控制命令。
static void kobuki_entry(void *parameter)
{
kobuki_init(&robot);
while(1)
{
rt_thread_mdelay(100);
kobuki_set_speed(linear_x, angular_z);
}
kobuki_close(&robot);
}
當(dāng)然,既然我們是遠(yuǎn)程控制,當(dāng)然不可能用串口連到 RTT 控制臺輸入命令啟動機(jī)器人,所以需要在 main.cpp 里面自動啟動任務(wù)。
#include 《rtthread.h》
#include 《ros.h》
int main(void)
{
extern int rosserial_kobuki_control(int argc, char **argv);
rt_thread_mdelay(10000);
rosserial_kobuki_control(0, 0);
}
需要注意的是,這里主函數(shù)是 main.cpp,因為rosserial 只支持 C++。掐指一算,rosserial 相關(guān)的代碼還不到 10 行,所以這也體現(xiàn)了 ROS 簡單好用的特點(diǎn)。最后還有一點(diǎn),之前 rosserial 有一個 1Hz 的 bug,導(dǎo)致系統(tǒng)響應(yīng)非常緩慢,這里要感謝 zhengyangliu 的 PR, 現(xiàn)在已經(jīng)修復(fù)了,整體 rosserial 使用 串口 和 TCP 都非常穩(wěn)定(然而,ESP8266 本身不是很穩(wěn)定)。
RT-Thread 相關(guān)的代碼就結(jié)束了,當(dāng)然我們還需要啟動 ROS 主節(jié)點(diǎn),這里我就用 docker 鏡像了,把需要的端口映射出來:
$ docker run -p 11411:11411 -it helloysd/rosserial:noetic /bin/bash
在 docker 容器的 bash 里面安裝相關(guān)軟件包并啟動 ROS Serial:
$ apt update
$ apt install curl
$ curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add -
$ apt update
$ apt install ros-noetic-teleop-twist-keyboard ros-noetic-rosserial-python
$ rosrun rosserial_python serial_node.py tcp
如果一切順利的話會看到 RTT 節(jié)點(diǎn)連接上來:
root@29bd821af356:/# rosrun rosserial_python serial_node.py tcp
[INFO] [1624089042.689792]: ROS Serial Python Node
[INFO] [1624089042.693095]: Fork_server is: False
[INFO] [1624089042.693884]: Waiting for socket connections on port 11411
[INFO] [1624089042.694750]: Waiting for socket connection
[INFO] [1624089055.564072]: Established a socket connection from 172.17.0.1 on port 55784
[INFO] [1624089055.565926]: calling startSerialClient
[INFO] [1624089057.674819]: Requesting topics.。。
[INFO] [1624089229.750517]: Note: subscribe buffer size is 512 bytes
[INFO] [1624089229.751418]: Setup subscriber on cmd_vel [geometry_msgs/Twist]
終于可以使用 ROS 的 teleop 軟件包用鍵盤遠(yuǎn)程控制 Kobuki 機(jī)器人了:
$ rosrun teleop_twist_keyboard teleop_twist_keyboard.py
ROS2 (micro_ros)
前面提到,第二代 ROS 主機(jī)之間的通信是建立在 DDS/RTPS 之上的,不過這些不需要自己實現(xiàn),可以直接在 RT-Thread Studio 里面添加 micro_ros 軟件包:
幾乎同樣的流程,雙擊軟件包之后選擇通信方式為 UDP,根據(jù)自己的開發(fā)板選擇不同的架構(gòu),因為 micro_ros 相關(guān)的庫是預(yù)先編譯好為 libmicroros.a 的,并且現(xiàn)在支持的有 Cortex M0,Cortex M3,Cortex M4,Cortex M7。
如果是其他架構(gòu)的話,就需要在 extras/library_generation 下添加相關(guān)的編譯文件,重新編譯對應(yīng)架構(gòu)的庫文件。另一方面,默認(rèn)編譯庫文件用的是 gcc 5.4.1,和 RTT Studio 的編譯器版本一致也是嵌入式最常用的版本,如果是更新版本的 gcc 或者 Keil 等其他編譯器,也需要重新生成 libmicroros.a。
當(dāng)然,選擇了 Kobuki 的例程之后,我們也需要指定 Kobuki 的串口 UART3。
同樣的,例程默認(rèn)是把相關(guān)的任務(wù)導(dǎo)出為命令,我們在機(jī)器人上電后不可能每次都連上串口在 RTT 控制臺下面啟動任務(wù),所以需要在 main.c 里面自動啟動相關(guān)的任務(wù):
#include 《rtthread.h》
int main(void)
{
extern int microros_kobuki_control(int argc, char **argv);
rt_thread_mdelay(10000);
microros_kobuki_control(0, (void*)0);
}
這里介紹一下 micro_ros 的啟動流程,先設(shè)置 micro_ros client 的 IP 地址,UPD 端口號,在啟動注冊相關(guān)的節(jié)點(diǎn),最后訂閱自己需要的話題 (topic),啟動 executor 設(shè)置相關(guān)的回調(diào)函數(shù)就可以了。
set_microros_udp_transports(“192.168.199.100”, 9999);
allocator = rcl_get_default_allocator();
// create init_options
if (rclc_support_init(&support, 0, NULL, &allocator) != RCL_RET_OK)
{
rt_kprintf(“[micro_ros] failed to initialize
”);
return;
};
// create node
if (rclc_node_init_default(&node, “micro_ros_rtt_sub_twist”, “”, &support) != RCL_RET_OK)
{
rt_kprintf(“[micro_ros] failed to create node
”);
return;
}
// create subscriber
rclc_subscription_init_default(
&subscriber,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(geometry_msgs, msg, Twist),
“cmd_vel”);
// create executor
rclc_executor_init(&executor, &support.context, 1, &allocator);
rclc_executor_add_subscription(&executor, &subscriber, &msg, &kobuki_callback, ON_NEW_DATA);
每當(dāng)收到新的消息時候,就會在回調(diào)函數(shù)里更新機(jī)器人的控制信息。
//twist message cb
static void kobuki_callback(const void *msgin) {
const geometry_msgs__msg__Twist * msg = (const geometry_msgs__msg__Twist *)msgin;
linear_x = msg-》linear.x;
angular_z = msg-》angular.z;
}
同樣的,Kobuki 機(jī)器人需要不停地發(fā)送控制命令,一旦一段時間沒有收到控制命令,Kobuki 就會自動停下來,這也是一種保護(hù)機(jī)制。
static void kobuki_entry(void *parameter)
{
kobuki_init(&robot);
while(1)
{
rt_thread_mdelay(100);
kobuki_set_speed(linear_x, angular_z);
}
kobuki_close(&robot);
}
static void microros_kobuki_entry(void *parameter)
{
while(1)
{
rt_thread_mdelay(100);
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
}
}
RT-Thread 開發(fā)完成之后,最后當(dāng)然還是需要在電腦上啟動 micro_ros client,這里我依舊使用 Docker:
$ docker run -it -p 9999:9999/udp --privileged microros/micro-ros-agent:foxy udp4 -p 9999
啟動 client 之后我們就可以讓 RTT 連接上了:
| /
- RT - Thread Operating System
/ | 4.0.4 build Jun 9 2021
2006 - 2021 Copyright by rt-thread team
msh 》
msh 》microros_pub_int32
[micro_ros] node created
[micro_ros] publisher created
[micro_ros] timer created
[micro_ros] executor created
[micro_ros] New thread mr_pubint32
如果一切正常,我們就可以在 client 的輸出里看到客戶端的連接信息:
[1623057529.937043] info | TermiosAgentLinux.cpp | init | running.。。 | fd: 4
[1623057529.937150] info | Root.cpp | set_verbose_level | logger setup | verbose_level: 4
[1623057541.764331] info | Root.cpp | create_client | create | client_key: 0x6F7B427A, session_id: 0x81
[1623057541.764507] info | SessionManager.hpp | establish_session | session established | client_key: 0x1870348922, address: 0
最后當(dāng)然也還是啟動 teleop 用鍵盤來控制 Kobuki 機(jī)器人:
$ rosrun teleop_twist_keyboard teleop_twist_keyboard.py
總結(jié)
總的來看,不得不說 ROS1 的 rosserial 初始化過程還是更加簡單一些。
另一方面,如果希望能在 RT-Thread 上直接運(yùn)行 ROS Master 節(jié)點(diǎn),還要期待 RT-Thread Smart。
編輯:jq
-
機(jī)器人
+關(guān)注
關(guān)注
211文章
28566瀏覽量
207722 -
傳感器驅(qū)動
+關(guān)注
關(guān)注
0文章
3瀏覽量
9081 -
ROS
+關(guān)注
關(guān)注
1文章
279瀏覽量
17042
原文標(biāo)題:【深度好文】MicroROS on RT-Thread
文章出處:【微信號:LinuxDev,微信公眾號:Linux閱碼場】歡迎添加關(guān)注!文章轉(zhuǎn)載請注明出處。
發(fā)布評論請先 登錄
相關(guān)推薦
評論