ROS - 服務通訊
第二章 ROS的通訊機制(重點)
第二節 服務通訊
服務通訊時基於請求響應模式的,是一種應答機制。也就是一個節點A向另外一個節點B傳送請求,B接收處理請求併產生相應結果返回給A。比如下面的應用場景:
機器人巡邏過程中,控制系統分析感測器資料發現可疑物體或人... 此時需要拍攝照片並留存。
在上述場景中,就使用到了服務通訊。一個節點需要向相機節點發送拍照請求,相機節點處理請求,並返回處理結果。
與上述應用類似的,服務通訊更適用於對實時性有要求、具有一定邏輯處理的應用場景。
2.2.1 理論模型
模型中包含3個角色:
- Master ---> 管理者
- Server ---> 服務端
- Client ---> 客戶端
框圖:
graph RL r1([Master]) r2([Server]) r3([Client]) r2 -- 1釋出服務訊息 --> r1 r3 -- 2查詢服務 --> r1 r1 -- 3匹配話題 --> r3 r3 -- 4請求資料 --> r2 r2 -- 5產生相應 --> r3其主要流程如下:
- 服務端註冊自身資訊;
- 客戶端請求服務;
- 管理者匹配話題,並把服務端的地址給客戶端;
- 客戶端與客戶端建立連線,請求資料;
- 服務端產生相應。
注意:
- 保證順序,客戶端發起請求時,服務端必須已啟動。
- 客戶端和服務端都可以存在多個。
關注點:
- 流程已經被封裝了,直接呼叫就可以了;
- 話題;
- 服務端;
- 客戶端;
- 資料載體。
2.2.2 一個案例
需求:編寫服務通訊,客戶端提交兩個整數至服務端,服務端求和並響應結果到客戶端。
2.2.3 編寫 srv 檔案
- 為案例建立一個功能包:
這個不多介紹了。
- 在功能包下建立一個
srv
資料夾,並在其中建立xxx.srv
檔案。
- 修改配置檔案:
在package.xml
中新增srv
(也是msg
)相關的編譯依賴和執行依賴:
<build_depend>message_generation</build_depend> <exec_depend>message_runtime</exec_depend>
在CMakeLists.txt
中新增srv
相關配置:
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)
# 需要加入 message_generation,必須有 std_msgs
add_service_files(
FILES
AddInts.srv
)
generate_messages(
DEPENDENCIES
std_msgs
)
- 編譯檔案:
編譯後在(.../工作空間/devel/include/包名/xxx.h)路徑下會自動生成一些中間檔案。
到這裡,我們自定義的一個srv
就完成了。
2.2.4 編寫服務端節點
- 編寫服務端節點:
#include "ros/ros.h"
#include "plumbing_server_client/Addints.h"
/*
服務端實現:解析客戶端提交的資料,並運算再產生響應
1. 包含標頭檔案;
2. 初始化ROS節點;
3. 建立節點控制代碼;
4. 建立一個服務物件;
5. 處理請求併產生相應;
6. spin()
*/
bool doNums(plumbing_server_client::Addints::Request &request,
plumbing_server_client::Addints::Response &response)
{
// 1. 處理請求
int num1 = request.num1;
int num2 = request.num2;
ROS_INFO("收到的資料是:num1 = %d, num2 = %d", num1, num2);
// 2. 組織響應
int sum = num1 + num2;
response.sum = sum;
ROS_INFO("求和結果是:sum = %d", sum);
return true;
}
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
// 2. 初始化ROS節點;
ros::init(argc,argv,"Heishui"); // 節點名稱需要保證唯一
// 3. 建立節點控制代碼;
ros::NodeHandle nh;
// 4. 建立一個服務物件;
ros::ServiceServer server = nh.advertiseService("Addints",doNums);
ROS_INFO("伺服器啟動");
// 5. 處理請求併產生相應;
// 6. spin()
ros::spin();
return 0;
}
- 修改
CMakeLists.txt
:
老生常談的修改方式,把節點和功能包新增到CMakeList.txt
- 編譯 + 執行:
ctrl
+ shift
+ B
編譯。然後執行節點。
首先roscore
然後開啟一個新的終端,執行服務端節點:
source ./devel/setup.bash
rosrun plumbing_server_client demo01_service
- 使用ROS指令來接收服務:
首先,右擊terminal
將其頁面分割成兩個,方便我們同時檢視客戶端和服務端。
然後,在新的terminal
中輸入:
source ./devel/setup.bash
rosservice call Addints [tab]
上面的程式碼中Addints
是我命名的服務端節點,輸入完按鍵盤上的tab
鍵自動補齊,然後就出現了我們的請求服務端是需要輸入的兩個數字。
終端裡可以的兩個數字可以自行修改(Ubuntu的終端不能直接用滑鼠點,需要用鍵盤的左右方向鍵)
看到這個,我們就可以確定服務端編寫成功!
2.2.5 編寫客戶端節點
- 編寫使用者端:
對照著服務端進行編寫就可以了:
#include "ros/ros.h"
#include "plumbing_server_client/Addints.h"
/*
客戶端:提交兩個整數,並處理相應的結果。
1. 包含標頭檔案;
2. 初始化ROS節點;
3. 建立節點控制代碼;
4. 建立一個客戶端物件;
5. 提交請求並處理響應;
*/
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
// 2. 初始化ROS節點;
ros::init(argc,argv,"Dabao");
// 3. 建立節點控制代碼;
ros::NodeHandle nh;
// 4. 建立一個客戶端物件;
ros::ServiceClient client = nh.serviceClient<plumbing_server_client::Addints>("Addints");
// 5. 提交請求並處理響應;
plumbing_server_client::Addints ai;
// 5-1. 組織請求
ai.request.num1 = 100;
ai.request.num2 = 200;
// 5-2. 處理響應
bool flag = client.call(ai);
if (flag)
{
ROS_INFO("響應成功!");
// 獲取結果
ROS_INFO("兩數之和是:%d",ai.response.sum);
}
else
ROS_INFO("處理失敗!");
return 0;
}
-
修改
CMakeLists.txt
: -
編譯 + 執行:
這裡之間放執行結果:
2.2.5 優化客戶端節點
- 要讓命令輸入的時候可以傳參,就要用到
main()
括號中的argc, argv
了那麼我們在客戶端主函式體的最前面寫入:
// 優化實現,獲取命令中的引數:
if(argc != 3)
{
ROS_INFO("提交的引數數量不正確!");
return 1;
}
這一部分是要求命令必須傳入3個引數,否則之間就返回了。著三個引數分別是: 節點名,num1
和num2
。
寫完後,我們把後面的組織請求處修改一下:
// 5-1. 組織請求
ai.request.num1 = atoi(argv[1]);
ai.request.num2 = atoi(argv[2]);
讓請求的ai
的兩個值分別傳入兩個引數。
我們輸入下次命令,看一下結果:
rosrun plumbing_server_client demo01_client 1 5
和
rosrun plumbing_server_client demo01_client
- 我們之前說過,在服務通訊的方式中,一定要先啟動伺服器,但是有時我們使用
launch
啟動一堆節點的時候,先後順序也許就不對了,為了避免之間報錯,我們需要再次優化客戶端節點
在ROS中,有2個函式可以做到讓客戶端啟動後掛起,等待伺服器啟動。
// 函式1
client.waitForExistence();
// 函式2
ros::service::waitForService("伺服器的節點名稱");
這兩個函式選擇其中一個就可以了,位置是放在判斷響應之前。那麼這個完整的伺服器函式就如下:
#include "ros/ros.h"
#include "plumbing_server_client/Addints.h"
/*
客戶端:提交兩個整數,並處理相應的結果。
1. 包含標頭檔案;
2. 初始化ROS節點;
3. 建立節點控制代碼;
4. 建立一個客戶端物件;
5. 提交請求並處理響應;
實現引數的動態提交:
1. 格式: rosrun xxx xxx 12 32
2. 節點執行時,需要獲取命令中的引數,並組織進 request
問題:
如果先啟動客戶端,那麼就會請求異常
需求:
如果先啟動客戶端,不要直接丟擲異常,而是掛起,等在伺服器啟動後再正常請求
解決:
ROS中的內建函式可以讓客戶端啟動後掛起,等待伺服器啟動。
*/
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
// 優化實現,獲取命令中的引數:
if(argc != 3)
{
ROS_INFO("提交的引數數量不正確!");
return 1;
}
// 2. 初始化ROS節點;
ros::init(argc,argv,"Dabao");
// 3. 建立節點控制代碼;
ros::NodeHandle nh;
// 4. 建立一個客戶端物件;
ros::ServiceClient client = nh.serviceClient<plumbing_server_client::Addints>("Addints");
// 5. 提交請求並處理響應;
plumbing_server_client::Addints ai;
// 5-1. 組織請求
ai.request.num1 = atoi(argv[1]);
ai.request.num2 = atoi(argv[2]);
// 5-2. 處理響應
// 呼叫判斷伺服器狀態的函式
// 函式1
//client.waitForExistence();
// 函式2
ros::service::waitForService("Addints");
bool flag = client.call(ai);
if (flag)
{
ROS_INFO("響應成功!");
// 獲取結果
ROS_INFO("兩數之和是:%d",ai.response.sum);
}
else
ROS_INFO("處理失敗!");
return 0;
}
當我們先啟動客戶端後啟動服務端的結果是: