编写一个简单的发布者和订阅者(C++)
目标: 使用C++创建并运行发布者和订阅者节点。
教程级别: 初学者
背景
节点 是在 ROS 图中进行通信的可执行进程。在本教程中,节点将以字符串消息的形式相互传递信息,通过一个 主题。这里使用的示例是一个简单的 "talker" 和 "listener" 系统;一个节点发布数据,另一个节点订阅该主题以接收数据。
这些示例中使用的代码可以在 这里 找到。
任务
1 创建一个包
在一个新的终端中 源化你的 ROS 2 安装,这样 ros2
命令才能正常工作。
进入在 上一个教程 中创建的 ros2_ws
目录。
记住,包应该创建在 src
目录中,而不是工作空间的根目录。所以,进入 ros2_ws/src
目录,并运行包创建命令:
ros2 pkg create --build-type ament_cmake cpp_pubsub
终端会返回一条消息,确认已创建名为 cpp_pubsub
的包及其所有必要的文件和文件夹。
进入 ros2_ws/src/cpp_pubsub/src
目录。请注意,这是任何 CMake 包中包含可执行文件的源文件所在的目录。
2 编写发布者节点
通过输入以下命令下载示例 talker 代码:
wget -O publisher_member_function.cpp https://raw.githubusercontent.com/ros2/examples/humble/rclcpp/topics/minimal_publisher/member_function.cpp
wget -O publisher_member_function.cpp https://raw.githubusercontent.com/ros2/examples/humble/rclcpp/topics/minimal_publisher/member_function.cpp
在 Windows 命令行提示符中:
curl -sk https://raw.githubusercontent.com/ros2/examples/humble/rclcpp/topics/minimal_publisher/member_function.cpp -o publisher_member_function.cpp
或者在powershell中执行:
curl https://raw.githubusercontent.com/ros2/examples/humble/rclcpp/topics/minimal_publisher/member_function.cpp -o publisher_member_function.cpp
现在会有一个名为``publisher_member_function.cpp``的新文件。使用您喜欢的文本编辑器打开该文件。
#include <chrono>
#include <functional>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
using namespace std::chrono_literals;
/* This example creates a subclass of Node and uses std::bind() to register a
* member function as a callback from the timer. */
class MinimalPublisher : public rclcpp::Node
{
public:
MinimalPublisher()
: Node("minimal_publisher"), count_(0)
{
publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
timer_ = this->create_wall_timer(
500ms, std::bind(&MinimalPublisher::timer_callback, this));
}
private:
void timer_callback()
{
auto message = std_msgs::msg::String();
message.data = "Hello, world! " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
publisher_->publish(message);
}
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
size_t count_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalPublisher>());
rclcpp::shutdown();
return 0;
}
2.1 检查代码
代码的开头包含了您将要使用的标准C++头文件。标准C++头文件之后是``rclcpp/rclcpp.hpp``的包含部分,它允许您使用ROS 2系统中最常见的组件。最后是``std_msgs/msg/string.hpp``,它包含了您将用于发布数据的内置消息类型。
#include <chrono>
#include <functional>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
using namespace std::chrono_literals;
这些行表示节点的依赖关系。请记住,依赖关系必须添加到``package.xml``和``CMakeLists.txt``中,在下一节中您将进行这些操作。
下一行通过从``rclcpp::Node``继承来创建节点类``MinimalPublisher``。代码中的每个``this``都是指向该节点。
class MinimalPublisher : public rclcpp::Node
公共构造函数将节点命名为``minimal_publisher``,并将``count_``初始化为0。在构造函数内部,使用``String``消息类型、主题名称``topic``以及必要的队列大小来初始化发布者。接下来,初始化了``timer_``,它导致``timer_callback``函数每秒执行两次。
public:
MinimalPublisher()
: Node("minimal_publisher"), count_(0)
{
publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
timer_ = this->create_wall_timer(
500ms, std::bind(&MinimalPublisher::timer_callback, this));
}
``timer_callback``函数是设置消息数据并实际发布消息的地方。``RCLCPP_INFO``宏确保每个发布的消息都会打印到控制台。
private:
void timer_callback()
{
auto message = std_msgs::msg::String();
message.data = "Hello, world! " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
publisher_->publish(message);
}
最后是定时器、发布者和计数器字段的声明。
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
size_t count_;
下面是``MinimalPublisher``类的定义,接着是``main``函数,其中节点实际执行。``rclcpp::init``用于初始化ROS 2,``rclcpp::spin``则开始处理来自节点的数据,包括定时器的回调函数。
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalPublisher>());
rclcpp::shutdown();
return 0;
}
2.2 添加依赖项
返回到``ros2_ws/src/cpp_pubsub``目录,这是``CMakeLists.txt``和``package.xml``文件所在的目录。这些文件已经为您创建好。
用文本编辑器打开``package.xml``文件。
如在:doc:之前的教程 <./Creating-Your-First-ROS2-Package>`中提到的,确保填写``<description>`
, ``<maintainer>``和``<license>``标签:
<description>Examples of minimal publisher/subscriber using rclcpp</description>
<maintainer email="you@email.com">Your Name</maintainer>
<license>Apache License 2.0</license>
在``ament_cmake``构建工具依赖项之后添加一个新行,并粘贴以下与节点的包含语句对应的依赖项:
<depend>rclcpp</depend>
<depend>std_msgs</depend>
这将在构建和执行代码时声明该包需要``rclcpp``和``std_msgs``.
确保保存文件.
2.3 CMakeLists.txt
现在打开 CMakeLists.txt
文件。在现有的依赖项 find_package(ament_cmake REQUIRED)
下方,添加以下行:
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
然后,添加可执行文件并将其命名为 talker
,这样你就可以使用 ros2 run
运行你的节点:
add_executable(talker src/publisher_member_function.cpp)
ament_target_dependencies(talker rclcpp std_msgs)
最后,添加 install(TARGETS...)
部分,以便 ros2 run
可以找到你的可执行文件:
install(TARGETS
talker
DESTINATION lib/${PROJECT_NAME})
你可以通过删除一些不必要的部分和注释来简化你的``CMakeLists.txt``,使其看起来像这样:
cmake_minimum_required(VERSION 3.5)
project(cpp_pubsub)
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
add_executable(talker src/publisher_member_function.cpp)
ament_target_dependencies(talker rclcpp std_msgs)
install(TARGETS
talker
DESTINATION lib/${PROJECT_NAME})
ament_package()
现在您可以构建您的软件包,加载本地设置文件并运行它,但是让我们首先创建订阅者节点,这样您就可以看到整个系统的运行情况。
3 编写订阅者节点
返回到 ros2_ws/src/cpp_pubsub/src
目录,创建下一个节点。在终端中输入以下代码:
wget -O subscriber_member_function.cpp https://raw.githubusercontent.com/ros2/examples/humble/rclcpp/topics/minimal_subscriber/member_function.cpp
wget -O subscriber_member_function.cpp https://raw.githubusercontent.com/ros2/examples/humble/rclcpp/topics/minimal_subscriber/member_function.cpp
在 Windows 命令行提示符中:
curl -sk https://raw.githubusercontent.com/ros2/examples/humble/rclcpp/topics/minimal_subscriber/member_function.cpp -o subscriber_member_function.cpp
或者在powershell中执行:
curl https://raw.githubusercontent.com/ros2/examples/humble/rclcpp/topics/minimal_subscriber/member_function.cpp -o subscriber_member_function.cpp
现在在控制台输入 ls
将会返回:
publisher_member_function.cpp subscriber_member_function.cpp
使用文本编辑器打开 subscriber_member_function.cpp
。
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
using std::placeholders::_1;
class MinimalSubscriber : public rclcpp::Node
{
public:
MinimalSubscriber()
: Node("minimal_subscriber")
{
subscription_ = this->create_subscription<std_msgs::msg::String>(
"topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
}
private:
void topic_callback(const std_msgs::msg::String & msg) const
{
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str());
}
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalSubscriber>());
rclcpp::shutdown();
return 0;
}
3.1 检查代码
订阅者节点的代码与发布者几乎完全相同。现在节点被命名为 minimal_subscriber
,构造函数使用节点的 create_subscription
类来执行回调函数。
没有定时器,因为订阅者只会在数据被发布到 topic
主题时做出响应。
public:
MinimalSubscriber()
: Node("minimal_subscriber")
{
subscription_ = this->create_subscription<std_msgs::msg::String>(
"topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
}
回顾一下 主题教程 中提到,发布者和订阅者使用的主题名称和消息类型必须匹配,才能使它们进行通信。
topic_callback
函数接收通过主题发布的字符串消息数据,并使用 RCLCPP_INFO
宏将其简单地写入控制台。
这个类中仅有一个字段声明,即订阅。
private:
void topic_callback(const std_msgs::msg::String & msg) const
{
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str());
}
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
main
函数完全相同,只是现在它旋转 MinimalSubscriber
节点。对于发布者节点,旋转意味着启动计时器,而对于订阅者节点,它只是准备在消息到来时接收消息。
由于该节点与发布者节点具有相同的依赖关系,因此在``package.xml``中没有新内容可添加。
3.2 CMakeLists.txt
重新打开``CMakeLists.txt``,在发布者的条目下面添加订阅者节点的可执行文件和目标。
add_executable(listener src/subscriber_member_function.cpp)
ament_target_dependencies(listener rclcpp std_msgs)
install(TARGETS
talker
listener
DESTINATION lib/${PROJECT_NAME})
确保保存文件,然后您的发布/订阅系统就准备好了。
4 构建和运行
很可能您已经在您的ROS 2系统中安装了``rclcpp``和``std_msgs``软件包。在构建之前,最好在您的工作空间根目录(ros2_ws
)中运行``rosdep``来检查是否存在缺失的依赖项:
rosdep install -i --from-path src --rosdistro humble -y
rosdep 只能在 Linux 上运行,所以您可以跳过下一步。
rosdep 只能在 Linux 上运行,所以您可以跳过下一步。
仍然在您的工作空间根目录(ros2_ws
)中,构建您的新软件包:
colcon build --packages-select cpp_pubsub
colcon build --packages-select cpp_pubsub
colcon build --merge-install --packages-select cpp_pubsub
打开一个新的终端,导航到 ros2_ws
,并加载设置文件:
. install/setup.bash
. install/setup.bash
call install/setup.bat
现在运行对话节点:
ros2 run cpp_pubsub talker
终端应该会每0.5秒发布一条信息消息,如下所示:
[INFO] [minimal_publisher]: Publishing: "Hello World: 0"
[INFO] [minimal_publisher]: Publishing: "Hello World: 1"
[INFO] [minimal_publisher]: Publishing: "Hello World: 2"
[INFO] [minimal_publisher]: Publishing: "Hello World: 3"
[INFO] [minimal_publisher]: Publishing: "Hello World: 4"
打开另一个终端,在``ros2_ws``内部再次source设置文件,然后启动监听节点:
ros2 run cpp_pubsub listener
监听器将从发布者当前的消息计数开始,将消息打印到控制台,就像这样:
[INFO] [minimal_subscriber]: I heard: "Hello World: 10"
[INFO] [minimal_subscriber]: I heard: "Hello World: 11"
[INFO] [minimal_subscriber]: I heard: "Hello World: 12"
[INFO] [minimal_subscriber]: I heard: "Hello World: 13"
[INFO] [minimal_subscriber]: I heard: "Hello World: 14"
在每个终端中输入``Ctrl+C``来停止节点的旋转。