ROS2与C++入门教程-进程内(intra_process)话题发布和订阅演示2
ROS2与C++入门教程-进程内(intra_process)话题发布和订阅演示2
说明:
- 介绍ros2下实现进程内(intra_process)话题发布和订阅
- 在同一进程内的不同节点,可以通过共享指针方式实现内容读取,减少消息的拷贝开销
- 对于图像之类数据量比较大的节点间处理的效率和性能将大大提高
- 本演示实现两个话题循环处理
步骤:
- 新建一个包cpp_intra_process_topic2
cd ~/dev_ws/src
ros2 pkg create --build-type ament_cmake cpp_intra_process_topic2
- 进入src目录,新建文件cyclic_pipeline.cpp
cd ~/dev_ws/src/cpp_intra_process_topic2/src
touch cyclic_pipeline.cpp
- 内容如下:
#include <chrono>
#include <cinttypes>
#include <cstdio>
#include <memory>
#include <string>
#include <utility>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/int32.hpp"
using namespace std::chrono_literals;
// This node receives an Int32, waits 1 second, then increments and sends it.
struct IncrementerPipe : public rclcpp::Node
{
IncrementerPipe(const std::string & name, const std::string & in, const std::string & out)
: Node(name, rclcpp::NodeOptions().use_intra_process_comms(true))
{
// Create a publisher on the output topic.
pub = this->create_publisher<std_msgs::msg::Int32>(out, 10);
std::weak_ptr<std::remove_pointer<decltype(pub.get())>::type> captured_pub = pub;
// Create a subscription on the input topic.
sub = this->create_subscription<std_msgs::msg::Int32>(
in,
10,
[captured_pub](std_msgs::msg::Int32::UniquePtr msg) {
auto pub_ptr = captured_pub.lock();
if (!pub_ptr) {
return;
}
printf(
"Received message with value: %d, and address: 0x%" PRIXPTR "\n", msg->data,
reinterpret_cast<std::uintptr_t>(msg.get()));
printf(" sleeping for 1 second...\n");
if (!rclcpp::sleep_for(1s)) {
return; // Return if the sleep failed (e.g. on ctrl-c).
}
printf(" done.\n");
msg->data++; // Increment the message's data.
printf(
"Incrementing and sending with value: %d, and address: 0x%" PRIXPTR "\n", msg->data,
reinterpret_cast<std::uintptr_t>(msg.get()));
pub_ptr->publish(std::move(msg)); // Send the message along to the output topic.
});
}
rclcpp::Publisher<std_msgs::msg::Int32>::SharedPtr pub;
rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr sub;
};
int main(int argc, char * argv[])
{
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor executor;
// Create a simple loop by connecting the in and out topics of two IncrementerPipe's.
// The expectation is that the address of the message being passed between them never changes.
auto pipe1 = std::make_shared<IncrementerPipe>("pipe1", "topic1", "topic2");
auto pipe2 = std::make_shared<IncrementerPipe>("pipe2", "topic2", "topic1");
rclcpp::sleep_for(1s); // Wait for subscriptions to be established to avoid race conditions.
// Publish the first message (kicking off the cycle).
std::unique_ptr<std_msgs::msg::Int32> msg(new std_msgs::msg::Int32());
msg->data = 42;
printf(
"Published first message with value: %d, and address: 0x%" PRIXPTR "\n", msg->data,
reinterpret_cast<std::uintptr_t>(msg.get()));
pipe1->pub->publish(std::move(msg));
executor.add_node(pipe1);
executor.add_node(pipe2);
executor.spin();
rclcpp::shutdown();
return 0;
}
- 编译package.xml
- 在<buildtool_depend>ament_cmake</buildtool_depend>后增加
<build_depend>rclcpp</build_depend>
<build_depend>std_msgs</build_depend>
- 编译CMakelist.txt
- 在find_package(ament_cmake REQUIRED)后增加
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
- 生成执行文件
include_directories(include)
add_executable(cyclic_pipeline
src/cyclic_pipeline.cpp)
target_link_libraries(cyclic_pipeline
rclcpp::rclcpp
${std_msgs_TARGETS})
- 安装相关库文件和执行文件
install(TARGETS
cyclic_pipeline
DESTINATION lib/${PROJECT_NAME})
- 编译包
colcon build --symlink-install --packages-select cpp_intra_process_topic2
- 加载工作空间
. install/setup.bash
- 测试:
ros2 run cpp_intra_process_topic2 cyclic_pipeline
- 效果如下:
$ ros2 run cpp_intra_process_topic2 cyclic_pipeline
Published first message with value: 42, and address: 0x55DBCB77E6F0
Received message with value: 42, and address: 0x55DBCB77E6F0
sleeping for 1 second...
done.
Incrementing and sending with value: 43, and address: 0x55DBCB77E6F0
Received message with value: 43, and address: 0x55DBCB77E6F0
sleeping for 1 second...
done.
Incrementing and sending with value: 44, and address: 0x55DBCB77E6F0
Received message with value: 44, and address: 0x55DBCB77E6F0
sleeping for 1 second...
done.
Incrementing and sending with value: 45, and address: 0x55DBCB77E6F0
Received message with value: 45, and address: 0x55DBCB77E6F0
sleeping for 1 second...
done.
参考:
获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号