當節點使用服務進行通訊時,傳送資料請求的節點稱為客戶節點,響應請求的節點稱為服務節點。請求和響應的結構由.srv
檔案決定。
本文的例子是一個簡單的整數加法系統:一個節點請求兩個整數的和,另一個節點響應結果。
1.建立功能包
在開始之前,確保ROS2的環境變數正確配置。
其次,包應該在src
目錄下,不是在工作空間的根目錄下。所以,導航到dev_ws
下,並建立一個新的包:
ros2 pkg create --build-type ament_cmake cpp_srvcli --dependencies rclcpp example_interfaces
終端將返回一條訊息,驗證cpp_srvcli
包及其所有必需的檔案和資料夾的建立。
going to create a new package
package name: cpp_srvcli
destination directory: /home/**/dev_ws/src
package format: 3
version: 0.0.0
description: TODO: Package description
maintainer: ['** <**@todo.todo>']
licenses: ['TODO: License declaration']
build type: ament_cmake
dependencies: ['rclcpp', 'example_interfaces']
creating folder ./cpp_srvcli
creating ./cpp_srvcli/package.xml
creating source and include folder
creating folder ./cpp_srvcli/src
creating folder ./cpp_srvcli/include/cpp_srvcli
creating ./cpp_srvcli/CMakeLists.txt
--dependencies
引數將自動將必要的依賴項新增到package.xml
和CMakeLists.txt
。example_interfaces
是包含.srv
檔案的包,通過此來構造請求和響應:
int64 a
int64 b
---
int64 sum
前兩行是請求的引數,破折號下面是響應的引數。在以後的專案中,往往會自己編寫.srv
檔案。
1.1更新package.xml
由於在包建立過程中使用了--dependencies
選項,所以不必手動向package.xml
或CMakeLists.txt
新增依賴項。
但是,與往常一樣,請確保將描述、維護人員電子郵件和名稱以及許可資訊新增到package.xml
。
<description>C++ client server tutorial</description>
<maintainer email="you@email.com">Your Name</maintainer>
<license>Apache License 2.0</license>
2.編寫服務節點
在dev_ws/src/cpp_srvcli/src
資料夾下,建立一個名為add_two_ints_server.cpp
的新檔案(可以使用touch
命令),並將以下程式碼貼上到其中:
#include "rclcpp/rclcpp.hpp"
#include "example_interfaces/srv/add_two_ints.hpp"
#include <memory>
void add(const std::shared_ptr<example_interfaces::srv::AddTwoInts::Request> request,
std::shared_ptr<example_interfaces::srv::AddTwoInts::Response> response)
{
response->sum = request->a + request->b;
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Incoming request\na: %ld" " b: %ld",
request->a, request->b);
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "sending back response: [%ld]", (long int)response->sum);
}
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_two_ints_server");
rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr service =
node->create_service<example_interfaces::srv::AddTwoInts>("add_two_ints", &add);
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Ready to add two ints.");
rclcpp::spin(node);
rclcpp::shutdown();
}
2.1審閱程式碼
前兩個#include
語句是包的依賴項。
add
函式從請求中獲取兩個整數,並將其和提供給響應,同時使用日誌通知控制檯其狀態。
void add(const std::shared_ptr<example_interfaces::srv::AddTwoInts::Request> request,
std::shared_ptr<example_interfaces::srv::AddTwoInts::Response> response)
{
response->sum = request->a + request->b;
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Incoming request\na: %ld" " b: %ld",
request->a, request->b);
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "sending back response: [%ld]", (long int)response->sum);
}
main
函式的實現如下,逐行執行:
- 初識化ROS2 C++庫:
rclcpp::init(argc, argv);
- 建立一個名為
add_two_ints_server
的節點:
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_two_ints_server");
- 為該節點建立一個名為
add_two_ints
的服務,並通過&add
方法自動在網路上釋出它:
rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr service =
node->create_service<example_interfaces::srv::AddTwoInts>("add_two_ints", &add);
- 當節點準備好時,列印log資訊:
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Ready to add two ints.");
- 啟動節點,使得節點可用:
rclcpp::spin(node);
2.2新增可執行程式
add_executable
巨集生成一個可以使用ros2 run
執行的可執行檔案。將以下程式碼塊新增到CMakeLists.txt
中,建立一個名為server
的可執行檔案:
add_executable(server src/add_two_ints_server.cpp)
ament_target_dependencies(server rclcpp example_interfaces)
為了讓ros2 run
可以找到可執行檔案,在檔案末尾ament_package()
之前新增以下程式碼:
install(TARGETS
server
DESTINATION lib/${PROJECT_NAME})
至此,server
建立完畢。
3.編寫客戶節點
在dev_ws/src/cpp_srvcli/src
資料夾中,建立一個名為add_two_ints_client.cpp
的新檔案,並將以下程式碼貼上到其中:
#include "rclcpp/rclcpp.hpp"
#include "example_interfaces/srv/add_two_ints.hpp"
#include <chrono>
#include <cstdlib>
#include <memory>
using namespace std::chrono_literals;
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
if (argc != 3) {
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "usage: add_two_ints_client X Y");
return 1;
}
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_two_ints_client");
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client =
node->create_client<example_interfaces::srv::AddTwoInts>("add_two_ints");
auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
request->a = atoll(argv[1]);
request->b = atoll(argv[2]);
while (!client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Interrupted while waiting for the service. Exiting.");
return 0;
}
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "service not available, waiting again...");
}
auto result = client->async_send_request(request);
// Wait for the result.
if (rclcpp::spin_until_future_complete(node, result) ==
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Sum: %ld", result.get()->sum);
} else {
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to call service add_two_ints");
}
rclcpp::shutdown();
return 0;
}
3.1審閱程式碼
與服務節點類似,以下程式碼行建立客戶節點:
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_two_ints_client");
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client =
node->create_client<example_interfaces::srv::AddTwoInts>("add_two_ints");
接下來,建立請求。它的結構由前面提到的.srv
檔案定義。
auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
request->a = atoll(argv[1]);
request->b = atoll(argv[2]);
while
迴圈給客戶節點1秒的時間來搜尋網路中的服務節點。如果找不到,它就會繼續等待。
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "service not available, waiting again...");
如果客戶節點被取消(例如,在終端中輸入Ctrl+C),它將返回一個錯誤日誌訊息,說明它被中斷了。
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Interrupted while waiting for the service. Exiting.");
return 0;
然後客戶節點傳送它的請求,啟動節點直到收到響應,或者失敗。
3.2新增可行性程式
返回CMakeLists.txt
為新節點新增可執行檔案和目標。從自動生成的檔案中刪除一些不必要的資訊後,整體的CMakeLists.txt
應該是這樣的:
cmake_minimum_required(VERSION 3.5)
project(cpp_srvcli)
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(example_interfaces REQUIRED)
add_executable(server src/add_two_ints_server.cpp)
ament_target_dependencies(server
rclcpp example_interfaces)
add_executable(client src/add_two_ints_client.cpp)
ament_target_dependencies(client
rclcpp example_interfaces)
install(TARGETS
server
client
DESTINATION lib/${PROJECT_NAME})
ament_package()
4.編譯和執行
回到工作空間的根目錄,並編譯包:
colcon build --packages-select cpp_srvcli
開啟一個新的終端,導航到dev_ws
,source配置檔案:
. install/setup.bash
接下來執行服務節點:
ros2 run cpp_srvcli server
此時,終端返回:
[INFO] [rclcpp]: Ready to add two ints.
開啟另一個終端,再次從dev_ws
中source配置檔案。啟動客戶端節點,後面跟著以空格分隔的任意兩個整數:
ros2 run cpp_srvcli client 2 3
此時,終端返回:
[INFO] [rclcpp]: Sum: 5
返回服務節點正在執行的終端,將看到收到請求以及它發回的響應:
[INFO] [rclcpp]: Incoming request
a: 2 b: 3
[INFO] [rclcpp]: sending back response: [5]
5.總結
本文建立了兩個節點來進行服務請求和響應資料,並將它們的依賴項和可執行檔案新增到包配置檔案中,以便編譯和執行它們,並檢視工作中的服務/客戶機系統。
如果給您帶來幫助,希望能給點個關注,以後還會陸續更新有關機器人的內容,點個關注不迷路~歡迎大家一起交流學習。
都看到這了,點個推薦再走吧~
未經允許,禁止轉載。