重要參考:
課程鏈接:https://www.bilibili.com/video/BV1Ci4y1L7ZZ
講義鏈接:Introduction · Autolabor-ROS機器人入門課程《ROS理論與實踐》零基礎教程
10.4 nodelet
ROS通信是基于Node(節點)的,Node使用方便、易于擴展,可以滿足ROS中大多數應用場景,但是也存在一些局限性,由于一個Node啟動之后獨占一根進程,不同Node之間數據交互其實是不同進程之間的數據交互,當傳輸類似于圖片、點云的大容量數據時,會出現延時與阻塞的情況,比如:
現在需要編寫一個相機驅動,在該驅動中有兩個節點實現:其中節點A負責發布原始圖像數據,節點B訂閱原始圖像數據并在圖像上標注人臉。如果節點A與節點B仍按照之前實現,兩個節點分別對應不同的進程,在兩個進程之間傳遞容量可觀圖像數據,可能就會出現延時的情況,那么該如何優化呢?
ROS中給出的解決方案是:Nodelet,通過Nodelet可以將多個節點集成進一個進程。
概念
nodelet軟件包旨在提供在同一進程中運行多個算法(節點)的方式,不同算法之間通過傳遞指向數據的指針來代替了數據本身的傳輸(類似于編程傳值與傳址的區別),從而實現零成本的數據拷貝。
nodelet功能包的核心實現也是插件,是對插件的進一步封裝:
- 不同算法被封裝進插件類,可以像單獨的節點一樣運行;
- 在該功能包中提供插件類實現的基類:Nodelet;
- 并且提供了加載插件類的類加載器:NodeletLoader。
作用
應用于大容量數據傳輸的場景,提高節點間的數據交互效率,避免延時與阻塞。
另請參考:
-
nodelet - ROS Wiki
-
nodelet/Tutorials/Running a nodelet - ROS Wiki
-
common_tutorials/nodelet_tutorial_math at noetic-devel · ros/common_tutorials · GitHub
10.4.1 使用演示
在ROS中內置了nodelet案例,我們先以該案例演示nodelet的基本使用語法,基本流程如下:
- 案例簡介;
- nodelet基本使用語法;
- 內置案例調用。
1.案例簡介
以“ros- [ROS_DISTRO] -desktop-full”命令安裝ROS時,nodelet默認被安裝,如未安裝,請調用如下命令自行安裝:
sudo apt install ros-<<ROS_DISTRO>>-nodelet-tutorial-math
在該案例中,定義了一個Nodelet插件類:Plus,這個節點可以訂閱一個數字,并將訂閱到的數字與參數服務器中的 value 參數相加后再發布。
需求:再同一線程中啟動兩個Plus節點A與B,向A發布一個數字,然后經A處理后,再發布并作為B的輸入,最后打印B的輸出。
2.nodelet 基本使用語法
使用語法如下:
nodelet load pkg/Type manager - Launch a nodelet of type pkg/Type on manager manager
nodelet standalone pkg/Type - Launch a nodelet of type pkg/Type in a standalone node
nodelet unload name manager - Unload a nodelet a nodelet by name from manager
nodelet manager - Launch a nodelet manager node
3.內置案例調用
1.啟動roscore
roscore
2.啟動manager
rosrun nodelet nodelet manager __name:=mymanager
__name:= 用于設置管理器名稱。
3.添加nodelet節點
添加第一個節點:
rosrun nodelet nodelet load nodelet_tutorial_math/Plus mymanager __name:=n1 _value:=100
添加第二個節點:
rosrun nodelet nodelet load nodelet_tutorial_math/Plus mymanager __name:=n2 _value:=-50 /n2/in:=/n1/out
PS: 解釋
rosrun nodelet nodelet load nodelet_tutorial_math/Plus mymanager __name:=n1 _value:=100
- rosnode list 查看,nodelet 的節點名稱是: /n1;
- rostopic list 查看,訂閱的話題是: /n1/in,發布的話題是: /n1/out;
- rosparam list查看,參數名稱是: /n1/value。
rosrun nodelet nodelet standalone nodelet_tutorial_math/Plus mymanager __name:=n2 _value:=-50 /n2/in:=/n1/out
- 第二個nodelet 與第一個同理;
- 第二個nodelet 訂閱的話題由 /n2/in 重映射為 /n1/out。
優化:也可以將上述實現集成進launch文件:
<launch><!-- 設置nodelet管理器 --><node pkg="nodelet" type="nodelet" name="mymanager" args="manager" output="screen" /><!-- 啟動節點1,名稱為 n1, 參數 /n1/value 為100 --><node pkg="nodelet" type="nodelet" name="n1" args="load nodelet_tutorial_math/Plus mymanager" output="screen" ><param name="value" value="100" /></node><!-- 啟動節點2,名稱為 n2, 參數 /n2/value 為-50 --><node pkg="nodelet" type="nodelet" name="n2" args="load nodelet_tutorial_math/Plus mymanager" output="screen" ><param name="value" value="-50" /><remap from="/n2/in" to="/n1/out" /></node></launch>
4.執行
向節點n1發布消息:
rostopic pub -r 10 /n1/in std_msgs/Float64 "data: 10.0"
打印節點n2發布的消息:
rostopic echo /n2/out
最終輸出結果應該是:60。
10.4.2 nodelet實現
nodelet本質也是插件,實現流程與插件實現流程類似,并且更為簡單,不需要自定義接口,也不需要使用類加載器加載插件類。
需求:參考 nodelet 案例,編寫 nodelet 插件類,可以訂閱輸入數據,設置參數,發布訂閱數據與參數相加的結果。
流程:
-
準備;
-
創建插件類并注冊插件;
-
構建插件庫;
-
使插件可用于ROS工具鏈;
-
執行。
1.準備
新建功能包,導入依賴:?roscpp、nodelet;
2.創建插件類并注冊插件
#include "nodelet/nodelet.h"
#include "pluginlib/class_list_macros.h"
#include "ros/ros.h"
#include "std_msgs/Float64.h"namespace nodelet_demo_ns {
class MyPlus: public nodelet::Nodelet {public:MyPlus(){value = 0.0;}void onInit(){//獲取 NodeHandleros::NodeHandle& nh = getPrivateNodeHandle();//從參數服務器獲取參數nh.getParam("value",value);//創建發布與訂閱對象pub = nh.advertise<std_msgs::Float64>("out",100);sub = nh.subscribe<std_msgs::Float64>("in",100,&MyPlus::doCb,this);}//回調函數void doCb(const std_msgs::Float64::ConstPtr& p){double num = p->data;//數據處理double result = num + value;std_msgs::Float64 r;r.data = result;//發布pub.publish(r);}private:ros::Publisher pub;ros::Subscriber sub;double value;};
}
PLUGINLIB_EXPORT_CLASS(nodelet_demo_ns::MyPlus,nodelet::Nodelet)
3.構建插件庫
CMakeLists.txt配置如下:
...
add_library(mynodeletlibsrc/myplus.cpp
)
...
target_link_libraries(mynodeletlib${catkin_LIBRARIES}
)
編譯后,會在??工作空間/devel/lib/?
生成文件:libmynodeletlib.so。
4.使插件可用于ROS工具鏈
4.1配置xml
新建 xml 文件,名稱自定義(比如:my_plus.xml),內容如下:
<library path="lib/libmynodeletlib"><class name="demo04_nodelet/MyPlus" type="nodelet_demo_ns::MyPlus" base_class_type="nodelet::Nodelet" ><description>hello</description></class>
</library>
4.2導出插件
<export><!-- Other tools can request additional information be placed here --><nodelet plugin="${prefix}/my_plus.xml" />
</export>
5.執行
可以通過launch文件執行nodelet,示例內容如下:
<launch><node pkg="nodelet" type="nodelet" name="my" args="manager" output="screen" /><node pkg="nodelet" type="nodelet" name="p1" args="load demo04_nodelet/MyPlus my" output="screen"><param name="value" value="100" /><remap from="/p1/out" to="con" /></node><node pkg="nodelet" type="nodelet" name="p2" args="load demo04_nodelet/MyPlus my" output="screen"><param name="value" value="-50" /><remap from="/p2/in" to="con" /></node></launch>
運行launch文件,可以參考上一節方式向 p1發布數據,并訂閱p2輸出的數據,最終運行結果也與上一節類似。