1. 程式人生 > 其它 >ROS實踐筆記6

ROS實踐筆記6

服務通訊實現

srv檔案

服務通訊是基於請求和響應,因此服務通訊的訊息載體需要包含“請求”和“響應”兩個部分,預設的資料結構不能滿足,所以需要自定義資料載體srv檔案。
srv檔案可用的資料型別與msg檔案一致,且實現流程與msg檔案類似。
實現流程:
    1. 在功能包目錄下建立srv資料夾,並建立xxx.srv檔案檔案
    2. 修改package.xml檔案
    3. 修改CMakeLists.txt檔案
package.xml檔案

新增

<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
CMakeLists.txt檔案
find_package(catkin REQUIRED COMPONENTS
  roscpp
  rospy
  std_msgs
)
# 改為
find_package(catkin REQUIRED COMPONENTS
  roscpp
  rospy
  std_msgs
  message_generation
)
## Generate services in the 'srv' folder
# add_service_files(
#   FILES
#   Service1.srv
#   Service2.srv
# )
# 改為
## Generate services in the 'srv' folder
 add_service_files(
   FILES
   information.srv
 )
# generate_messages(
#   DEPENDENCIES
#   std_msgs
# )
# 註釋放開
catkin_package(
#  INCLUDE_DIRS include
#  LIBRARIES hellovscode
#  CATKIN_DEPENDS roscpp rospy std_msgs
#  DEPENDS system_lib
)
# 改為
catkin_package(
#  INCLUDE_DIRS include
#  LIBRARIES plumbing_server_client
  CATKIN_DEPENDS roscpp rospy std_msgs message_runtime
#  DEPENDS system_lib
)

編譯後生成的檔案路徑與msg檔案類似
將生成的檔案配置進msg生成檔案相同的位置

c++

Server的實現

服務端實現:解析客戶端提交的資料。運算後產生響應:
    1. 包含標頭檔案
    2. 初始化ROS節點
    3. 建立節點控制代碼
    4. 建立服務物件
    5. 處理請求併產生響應
    6. spin()

編寫完成後在CMakeList.txt檔案中需要額外配置:

 add_dependencies(server ${PROJECT_NAME}_gencpp)

服務端程式碼

# include"ros/ros.h"
# include"plumbing_server_client/information.h"


bool doNums(plumbing_server_client::information::Request &request,
plumbing_server_client::information::Response &response)
{
    response.sum=request.num1+request.num2;
    return response.sum==request.num1+request.num2;
}

int main(int argc, char  *argv[])
{
    ros::init(argc,argv,"Server_c");
    ros::NodeHandle nh;
    ros::ServiceServer server=nh.advertiseService("Server",doNums);
    ros::spin();
    return 0;
}

Client的實現

客戶端實現:提交資料並處理響應結果
    1. 包含標頭檔案
    2. 初始化ROS節點
    3. 建立節點控制代碼
    4. 建立一個客戶端物件
    5. 提交請求並處理響應

客戶端程式碼:

# include"ros/ros.h"
# include"plumbing_server_client/information.h"

int main(int argc, char *argv[])
{
    setlocale(LC_ALL,"");
    ros::init(argc,argv,"Client_c");
    ros::NodeHandle nh;
    ros::ServiceClient client=nh.serviceClient<plumbing_server_client::information>("Service");
    plumbing_server_client::information t;
    /*

    //通過命令輸入引數
    //rosrun plumbing_server_client client_c num1 num2
    //用數字代替num1和num2
    //argv[0]可能是檔名,argc代表輸入的引數個數
    t.request.num1=atoi(argv[1]);
    t.request.num2=atoi(argv[2]);

    */
    std::cin>>t.request.num1>>t.request.num2;
    //判斷服務端狀態,如果服務端未啟動則掛起
    //client.waitForExistence(); //函式1
    ros::service::waitForService("Service");//函式2

    if(client.call(t))
        //std::cout<<t.response.sum<<std::endl;
        ROS_INFO("響應結果=%d\n",t.response.sum);
    else
        ROS_INFO("處理失敗!!!");
    
    return 0;
}

python

服務端程式碼如下

#! /usr/bin/env python

import rospy
from plumbing_server_client.srv import information,informationRequest,informationResponse
#from plumbing_server_client.srv import *
#引數封裝了請求資料
#返回值是響應資料
def doNum(request):
    response=informationResponse()
    response.sum=request.num1+request.num2
    return response

if __name__=="__main__":
    rospy.init_node("Server_p")
    server=rospy.Service("Service",information,doNum)
    rospy.spin()

客戶端程式碼實現

#! /usr/bin/env python

import rospy
import sys # 用於傳參
#from plumbing_server_client.srv import information,informationRequest,informationResponse
from plumbing_server_client.srv import *

if __name__=="__main__":
    if len(sys.argv) !=3:
        rospy.logerr("傳參錯誤!")
        sys.exit(1)
    rospy.init_node("Client_p")
    client=rospy.ServiceProxy("Service",information)
    num1=int(sys.argv[1])
    num2=int(sys.argv[2])
    #客戶端等待服務端函式
    #client.wait_for_service() #函式1
    rospy.wait_for_service("Service") #函式2
    response = client.call(num1,num2)
    rospy.loginfo("響應的資料為 %d",response.sum)

可以通過命令

rosservice call Sevice
# server是節點名
# 輸入完成後再輸入一個空格後Tab補齊

測試伺服器端是否正常