1.創建功能包
在本文中,將在自己的包中創建自定義的.msg
和.srv
文件,然后在另外的包中使用它們,這兩個包應該在同一個工作空間中。
本文將使用在前面文章中創建的pub/sub和service/client包【可參考前幾篇RO2學習之旅的文章】,請確保處在dev_ws/src
目錄下,然后運行以下命令創建一個新包:
ros2 pkg create --build-type ament_cmake tutorial_interfaces
tutorial_interfaces
是新包的名稱。注意,它是一個CMake包,目前還沒有辦法在純Python包中生成.msg
或.srv
文件。但是,可以在CMake包中創建自定義接口,然后在Python節點中使用它。
將.msg
和.srv
文件保存在自己的包中是一種很好的做法。在dev_ws/src/tutorial_interfaces
目錄下創建:
mkdir msg
mkdir srv
2.創建自定義消息文件
2.1自定義msg文件
在tutorial_interfaces/msg
文件夾下,創建一個名為Num.msg
的新文件,用一行代碼聲明它的數據結構:
int64 num
這是自定義的消息,它傳輸一個名稱為num
的64位整數。
2.2自定義srv文件
在tutorial_interfaces/srv
文件夾下,創建一個名為AddThreeInts.srv
的新文件,並聲明他的請求和響應結構:
int64 a
int64 b
int64 c
---
int64 sum
這是定制的服務,它請求三個名為a、b和c的整數,並以一個名為sum的整數進行響應。
3.CMakeLists.txt
要將自定義的接口(interface)轉換成基於語言的代碼(如C++和Python),以便它們可以在這些語言中使用,請將以下代碼添加到CMakeLists.txt
中:
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/Num.msg"
"srv/AddThreeInts.srv"
)
4.package.xml
因為接口依賴於rosidl_default_generators
來生成基於語言的代碼,所以需要聲明對它的依賴關系。將以下行添加到package.xml
中:
<build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
5.編譯 tutorial_interfaces
包
在工作空間的根目錄(~/dev_ws
)中,運行以下命令:
colcon build --packages-select tutorial_interfaces
現在接口將被其他ROS 2包發現。
6.驗證msg和srv的創建
打開新終端,在dev_ws
下運行:
. install/setup.bash
可以使用ros2 interface show
命令確認接口創建工作:
ros2 interface show tutorial_interfaces/msg/Num
返回:
int64 num
運行:
ros2 interface show tutorial_interfaces/srv/AddThreeInts
返回:
int64 a
int64 b
int64 c
---
int64 sum
7.測試新接口
使用在前面的文章中創建的包,對節點、CMakelist
和package
文件進行一些簡單的修改,就可以使用新的接口。
7.1使用pub/sub測試Num.msg
對前面創建的發布節點進行修改(~/dev_ws/src/cpp_pubsub/src/publisher_member_function.cpp
)。
Publisher:
#include <chrono>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/msg/num.hpp" // CHANGE
using namespace std::chrono_literals;
class MinimalPublisher : public rclcpp::Node
{
public:
MinimalPublisher()
: Node("minimal_publisher"), count_(0)
{
publisher_ = this->create_publisher<tutorial_interfaces::msg::Num>("topic", 10); // CHANGE
timer_ = this->create_wall_timer(
500ms, std::bind(&MinimalPublisher::timer_callback, this));
}
private:
void timer_callback()
{
auto message = tutorial_interfaces::msg::Num(); // CHANGE
message.num = this->count_++; // CHANGE
RCLCPP_INFO(this->get_logger(), "Publishing: '%d'", message.num); // CHANGE
publisher_->publish(message);
}
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<tutorial_interfaces::msg::Num>::SharedPtr publisher_; // CHANGE
size_t count_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalPublisher>());
rclcpp::shutdown();
return 0;
}
對前面創建的訂閱節點進行修改(~/dev_ws/src/cpp_pubsub/src/subscriber_member_function.cpp.cpp
)。
Subscriber:
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/msg/num.hpp" // CHANGE
using std::placeholders::_1;
class MinimalSubscriber : public rclcpp::Node
{
public:
MinimalSubscriber()
: Node("minimal_subscriber")
{
subscription_ = this->create_subscription<tutorial_interfaces::msg::Num>( // CHANGE
"topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
}
private:
void topic_callback(const tutorial_interfaces::msg::Num::SharedPtr msg) const // CHANGE
{
RCLCPP_INFO(this->get_logger(), "I heard: '%d'", msg->num); // CHANGE
}
rclcpp::Subscription<tutorial_interfaces::msg::Num>::SharedPtr subscription_; // CHANGE
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalSubscriber>());
rclcpp::shutdown();
return 0;
}
修改CMakeLists.txt
:
#...
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tutorial_interfaces REQUIRED) # CHANGE
add_executable(talker src/publisher_member_function.cpp)
ament_target_dependencies(talker rclcpp tutorial_interfaces) # CHANGE
add_executable(listener src/subscriber_member_function.cpp)
ament_target_dependencies(listener rclcpp tutorial_interfaces) # CHANGE
install(TARGETS
talker
listener
DESTINATION lib/${PROJECT_NAME})
ament_package()
在package.xml
中添加:
<depend>tutorial_interfaces</depend>
接着,編譯整個包:
colcon build --packages-select cpp_pubsub
打開新終端,source dev_ws
, 並運行:
ros2 run cpp_pubsub talker
ros2 run cpp_pubsub listener
因為Num.msg
只傳遞一個整數,所以它應該只發布整數值,而不是之前發布的字符串:
[INFO] [minimal_publisher]: Publishing: '0'
[INFO] [minimal_publisher]: Publishing: '1'
[INFO] [minimal_publisher]: Publishing: '2'
7.2使用service/client測試AddThreeInts.srv
對前面創建的發布節點進行修改(~/dev_ws/src/cpp_srvcli/src/add_two_ints_server.cpp
)。
Service:
#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/srv/add_three_ints.hpp" // CHANGE
#include <memory>
void add(const std::shared_ptr<tutorial_interfaces::srv::AddThreeInts::Request> request, // CHANGE
std::shared_ptr<tutorial_interfaces::srv::AddThreeInts::Response> response) // CHANGE
{
response->sum = request->a + request->b + request->c; // CHANGE
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Incoming request\na: %ld" " b: %ld" " c: %ld", // CHANGE
request->a, request->b, request->c); // CHANGE
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_three_ints_server"); // CHANGE
rclcpp::Service<tutorial_interfaces::srv::AddThreeInts>::SharedPtr service = // CHANGE
node->create_service<tutorial_interfaces::srv::AddThreeInts>("add_three_ints", &add); // CHANGE
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Ready to add three ints."); // CHANGE
rclcpp::spin(node);
rclcpp::shutdown();
}
對前面創建的發布節點進行修改(~/dev_ws/src/cpp_srvcli/src/add_two_ints_client.cpp
)。
Client:
#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/srv/add_three_ints.hpp" // CHANGE
#include <chrono>
#include <cstdlib>
#include <memory>
using namespace std::chrono_literals;
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
if (argc != 4) { // CHANGE
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "usage: add_three_ints_client X Y Z"); // CHANGE
return 1;
}
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_three_ints_client"); // CHANGE
rclcpp::Client<tutorial_interfaces::srv::AddThreeInts>::SharedPtr client = // CHANGE
node->create_client<tutorial_interfaces::srv::AddThreeInts>("add_three_ints"); // CHANGE
auto request = std::make_shared<tutorial_interfaces::srv::AddThreeInts::Request>(); // CHANGE
request->a = atoll(argv[1]);
request->b = atoll(argv[2]);
request->c = atoll(argv[3]); // CHANGE
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::executor::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_three_ints"); // CHANGE
}
rclcpp::shutdown();
return 0;
}
修改CMakeLists.txt
:
#...
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tutorial_interfaces REQUIRED) # CHANGE
add_executable(server src/add_two_ints_server.cpp)
ament_target_dependencies(server
rclcpp tutorial_interfaces) #CHANGE
add_executable(client src/add_two_ints_client.cpp)
ament_target_dependencies(client
rclcpp tutorial_interfaces) #CHANGE
install(TARGETS
server
client
DESTINATION lib/${PROJECT_NAME})
ament_package()
在package.xml
文件中添加:
<depend>tutorial_interfaces</depend>
編譯包:
colcon build --packages-select cpp_srvcli
打開新終端, source dev_ws
, 並運行:
ros2 run cpp_srvcli server
ros2 run cpp_srvcli client 2 3 1
8.總結
在本文中,學習了如何在自己的包中創建自定義接口,以及如何從其他包中利用這些接口。
如果給您帶來幫助,希望能給點個關注,以后還會陸續更新有關機器人的內容,點個關注不迷路~歡迎大家一起交流學習。
都看到這了,點個推薦再走吧~
未經允許,禁止轉載。