服務(wù)數(shù)據(jù)的定義與使用
自定義服務(wù)數(shù)據(jù)
- 首先創(chuàng)建script文件夾填渠,定義srv文件
建立.srv文件施掏,文件中數(shù)據(jù)分成兩個部分帖烘,中間用---隔開亮曹,---上面是request的內(nèi)容,下面是response的內(nèi)容秘症。
string name
uint8 age
uint8 sex
uint8 unknown=0
uint8 male=1
uint8 female=2
---
string result
- 在package.xml中添加功能包依賴
<build_depend>message_generatiom</build_depend>
<exec_depend>message_runtime</exec_depend>
- 在CMakeLists.txt添加編譯選項
在find_package()中添加了message_genetation
add_service_files(FILES Person.srv)
在catkin_package()中添加message_runtime
- 編譯生成語言相關(guān)文件
實現(xiàn)客戶端和服務(wù)端
- 客戶端
/**
* 該例程將請求/show_person服務(wù)照卦,服務(wù)數(shù)據(jù)類型learning_service::Person
*/
#include <ros/ros.h>
#include "learning_service/Person.h"
int main(int argc, char** argv)
{
// 初始化ROS節(jié)點(diǎn)
ros::init(argc, argv, "person_client");
// 創(chuàng)建節(jié)點(diǎn)句柄
ros::NodeHandle node;
// 發(fā)現(xiàn)/spawn服務(wù)后,創(chuàng)建一個服務(wù)客戶端乡摹,連接名為/spawn的service
ros::service::waitForService("/show_person");
ros::ServiceClient person_client = node.serviceClient<learning_service::Person>("/show_person");
// 初始化learning_service::Person的請求數(shù)據(jù)
learning_service::Person srv;
srv.request.name = "Tom";
srv.request.age = 20;
srv.request.sex = learning_service::Person::Request::male;
// 請求服務(wù)調(diào)用
ROS_INFO("Call service to show person[name:%s, age:%d, sex:%d]",
srv.request.name.c_str(), srv.request.age, srv.request.sex);
person_client.call(srv);
// 顯示服務(wù)調(diào)用結(jié)果
ROS_INFO("Show person result : %s", srv.response.result.c_str());
return 0;
};
- 服務(wù)端
/**
* 該例程將執(zhí)行/show_person服務(wù)役耕,服務(wù)數(shù)據(jù)類型learning_service::Person
*/
#include <ros/ros.h>
#include "learning_service/Person.h"
// service回調(diào)函數(shù),輸入?yún)?shù)req趟卸,輸出參數(shù)res
bool personCallback(learning_service::Person::Request &req,
learning_service::Person::Response &res)
{
// 顯示請求數(shù)據(jù)
ROS_INFO("Person: name:%s age:%d sex:%d", req.name.c_str(), req.age, req.sex);
// 設(shè)置反饋數(shù)據(jù)
res.result = "OK";
return true;
}
int main(int argc, char **argv)
{
// ROS節(jié)點(diǎn)初始化
ros::init(argc, argv, "person_server");
// 創(chuàng)建節(jié)點(diǎn)句柄
ros::NodeHandle n;
// 創(chuàng)建一個名為/show_person的server蹄葱,注冊回調(diào)函數(shù)personCallback
ros::ServiceServer person_service = n.advertiseService("/show_person", personCallback);
// 循環(huán)等待回調(diào)函數(shù)
ROS_INFO("Ready to show person informtion.");
ros::spin();
return 0;
}
- 編譯運(yùn)行同之前的步驟