从节点(C++)录制一个包

**目标:**将您自己的C++节点的数据记录到包中。

教程级别: 高级

**时间:**20分钟

背景

rosbag2 不仅仅提供了 ros2 bag 命令行工具,还提供了一个 C++ API,可以从你自己的源代码中读取和写入 bag 文件。这允许你订阅一个话题并同时将接收到的数据保存到 bag 文件中,同时对该数据进行任何其他处理。

先决条件

你应该在常规的 ROS 2 配置中安装了 rosbag2 包。

如果你是通过在 Linux 上安装 Debian 包进行安装的,它可能是默认安装的。如果没有安装,可以使用以下命令安装:

sudo apt install ros-humble-rosbag2

本教程讨论了如何使用 ROS 2 bags,包括在终端上的使用。你应该已经完成了 基本 ROS 2 bag 教程

任务

1 创建一个包

在一个新的终端中 源化你的 ROS 2 安装,这样 ros2 命令才能正常工作。

进入在 之前的教程 中创建的 ros2_ws 目录。进入 ros2_ws/src 目录并创建一个新的包:

ros2 pkg create --build-type ament_cmake bag_recorder_nodes --dependencies example_interfaces rclcpp rosbag2_cpp std_msgs

您的终端将返回一条消息,验证您的软件包 bag_recorder_nodes 及其所有必要的文件和文件夹的创建情况。--dependencies 参数将自动向 package.xmlCMakeLists.txt 添加必要的依赖项。在本例中,该软件包将使用 rosbag2_cpp 软件包和 rclcpp 软件包。还需要在本教程的后续部分中依赖于 example_interfaces 软件包。

1.1 更新 package.xml

由于您在软件包创建过程中使用了 --dependencies 选项,因此您无需手动向 package.xmlCMakeLists.txt 添加依赖项。但请确保向 package.xml 添加描述、维护者电子邮件和姓名以及许可信息。

<description>C++ bag writing tutorial</description>
<maintainer email="you@email.com">Your Name</maintainer>
<license>Apache License 2.0</license>

2 编写 C++ 节点

ros2_ws/src/bag_recorder_nodes/src 目录下创建一个名为 simple_bag_recorder.cpp 的新文件,并将以下代码粘贴到其中。

#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>

#include <rosbag2_cpp/writer.hpp>

using std::placeholders::_1;

class SimpleBagRecorder : public rclcpp::Node
{
public:
  SimpleBagRecorder()
  : Node("simple_bag_recorder")
  {
    writer_ = std::make_unique<rosbag2_cpp::Writer>();

    writer_->open("my_bag");

    subscription_ = create_subscription<std_msgs::msg::String>(
      "chatter", 10, std::bind(&SimpleBagRecorder::topic_callback, this, _1));
  }

private:
  void topic_callback(std::shared_ptr<rclcpp::SerializedMessage> msg) const
  {
    rclcpp::Time time_stamp = this->now();

    writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp);
  }

  rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
  std::unique_ptr<rosbag2_cpp::Writer> writer_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<SimpleBagRecorder>());
  rclcpp::shutdown();
  return 0;
}

2.1 检查代码

顶部的 #include 语句是包的依赖项。注意包含了来自 rosbag2_cpp 包的头文件,用于处理袋文件所需的函数和结构。

在类的构造函数中,我们首先创建一个用于写入袋文件的写入器对象。

writer_ = std::make_unique<rosbag2_cpp::Writer>();

现在我们有了一个writer对象,我们可以使用它来打开bag。我们只需指定要创建的bag的URI,将其他选项保持默认。使用默认的存储选项,这意味着将创建一个``sqlite3``格式的bag。默认的转换选项也会被使用,这将不进行任何转换,而是将消息以接收时的序列化格式存储起来。

writer_->open("my_bag");

现在设置好了writer以记录我们传递给它的数据,我们创建一个订阅并为其指定一个回调函数。我们将在回调函数中向bag写入数据。

subscription_ = create_subscription<std_msgs::msg::String>(
  "chatter", 10, std::bind(&SimpleBagRecorder::topic_callback, this, _1));

回调函数本身与典型的回调函数不同。我们不会接收主题数据类型的实例,而是接收一个``rclcpp::SerializedMessage``。我们这样做有两个原因。

  1. 消息数据在被写入bag之前需要被``rosbag2``进行序列化,因此我们不会在接收数据时进行反序列化,然后再进行序列化,而是要求ROS直接将序列化的消息给我们。

  2. 写入API可以接受序列化的消息。

void topic_callback(std::shared_ptr<rclcpp::SerializedMessage> msg) const
{

在订阅回调中,首先要确定用于存储消息的时间戳。这可以是与您的数据相关的任何适当的值,但通常有两个常见值可选:数据生成时的时间(如果已知),以及接收到数据的时间。在这里使用的是第二个选项,即接收时间。

rclcpp::Time time_stamp = this->now();

然后,我们可以将消息写入包中。因为我们还没有向包注册任何主题,所以必须使用消息的完整主题信息来指定。这就是为什么我们传入主题名称和主题类型的原因。

writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp);

该类包含两个成员变量。

  1. 订阅对象。注意,模板参数是回调函数的类型,而不是主题的类型。在这种情况下,回调函数接收一个``rclcpp::SerializedMessage``的共享指针,所以模板参数必须是这个类型。

  2. 一个指向用于向包中写入数据的写入器对象的管理指针。请注意,在这里使用的写入器类型是``rosbag2_cpp::Writer``,即通用的写入器接口。可能会有其他具有不同行为的写入器可用。

rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
std::unique_ptr<rosbag2_cpp::Writer> writer_;

文件以``main``函数结束,用于创建一个节点实例并启动ROS处理。

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<SimpleBagRecorder>());
  rclcpp::shutdown();
  return 0;
}

2.2 添加可执行文件

现在打开 CMakeLists.txt 文件。

在文件的顶部附近,将 CMAKE_CXX_STANDARD14 改为 17

# Default to C++17
if(NOT CMAKE_CXX_STANDARD)
  set(CMAKE_CXX_STANDARD 17)
endif()

在包含 find_package(rosbag2_cpp REQUIRED) 的依赖项块下面,添加以下代码行。

add_executable(simple_bag_recorder src/simple_bag_recorder.cpp)
ament_target_dependencies(simple_bag_recorder rclcpp rosbag2_cpp std_msgs)

install(TARGETS
  simple_bag_recorder
  DESTINATION lib/${PROJECT_NAME}
)

3. 构建和运行

返回到你的工作空间的根目录,ros2_ws,并构建你的新包。

colcon build --packages-select bag_recorder_nodes

打开一个新终端,进入``ros2_ws``目录,并源化设置文件。

source install/setup.bash

现在运行节点:

ros2 run bag_recorder_nodes simple_bag_recorder

打开第二个终端并运行``talker``示例节点。

ros2 run demo_nodes_cpp talker

这将开始在 chatter 话题上发布数据。当写入包的节点接收到这些数据时,它将把它写入到 my_bag 包中。

终止这两个节点。然后,在一个终端中启动 listener 示例节点。

ros2 run demo_nodes_cpp listener

在另一个终端中,使用 ros2 bag 命令来播放由你的节点记录的包。

ros2 bag play my_bag

你将看到包中的消息被 listener 节点接收到。

如果您希望再次运行写入包节点,则首先需要删除``my_bag``目录。

4 从节点记录合成数据

任何数据都可以记录到包中,不仅限于通过主题接收到的数据。从自己的节点写入包的常见用例是生成并存储合成数据。在本节中,您将学习如何编写一个生成数据并将其存储在包中的节点。我们将演示两种实现方法。第一种方法使用定时器的节点;这是您在数据生成与节点外部的情况下使用的方法,例如直接从硬件(如相机)读取数据。第二种方法不使用节点;这是您在不需要使用ROS基础设施的任何功能时可以使用的方法。

4.1 编写一个 C++ 节点

ros2_ws/src/bag_recorder_nodes/src 目录下,创建一个名为 data_generator_node.cpp 的新文件,并将以下代码粘贴到其中。

#include <chrono>

#include <example_interfaces/msg/int32.hpp>
#include <rclcpp/rclcpp.hpp>

#include <rosbag2_cpp/writer.hpp>

using namespace std::chrono_literals;

class DataGenerator : public rclcpp::Node
{
public:
  DataGenerator()
  : Node("data_generator")
  {
    data_.data = 0;
    writer_ = std::make_unique<rosbag2_cpp::Writer>();

    writer_->open("timed_synthetic_bag");

    writer_->create_topic(
      {"synthetic",
       "example_interfaces/msg/Int32",
       rmw_get_serialization_format(),
       ""});

    timer_ = create_wall_timer(1s, std::bind(&DataGenerator::timer_callback, this));
  }

private:
  void timer_callback()
  {
    writer_->write(data_, "synthetic", now());

    ++data_.data;
  }

  rclcpp::TimerBase::SharedPtr timer_;
  std::unique_ptr<rosbag2_cpp::Writer> writer_;
  example_interfaces::msg::Int32 data_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<DataGenerator>());
  rclcpp::shutdown();
  return 0;
}

4.2 检查代码

大部分代码与第一个示例相同。以下是重要的区别描述。

首先,更改了包的名称。

writer_->open("timed_synthetic_bag");

在这个例子中,我们提前在包中注册了话题。在大多数情况下,这是可选的,但是当传入没有话题信息的序列化消息时,必须执行此操作。

writer_->create_topic(
  {"synthetic",
   "example_interfaces/msg/Int32",
   rmw_get_serialization_format(),
   ""});

这个节点不是订阅某个话题,而是具有一个定时器。定时器以1秒的周期触发,并在触发时调用给定的成员函数。

timer_ = create_wall_timer(1s, std::bind(&DataGenerator::timer_callback, this));

在定时器回调函数中,我们生成(或以其他方式获取,例如从连接到某个硬件的串口读取)希望存储在包中的数据。与上一个示例的重要区别在于,数据尚未序列化。相反,我们将一个ROS消息数据类型传递给写入器对象,在这种情况下是``example_interfaces/msg/Int32``的一个实例。写入器会在将数据写入包之前为我们序列化数据。

writer_->write(data_, "synthetic", now());

4.3 添加可执行文件

打开``CMakeLists.txt``文件,并在之前添加的行后面添加以下行(特别是在``install(TARGETS ...)``宏调用之后)。

add_executable(data_generator_node src/data_generator_node.cpp)
ament_target_dependencies(data_generator_node rclcpp rosbag2_cpp example_interfaces)

install(TARGETS
  data_generator_node
  DESTINATION lib/${PROJECT_NAME}
)

4.4 构建和运行

返回到你的工作空间根目录``ros2_ws``,并构建你的包。

colcon build --packages-select bag_recorder_nodes

打开一个新终端,进入``ros2_ws``目录,并源化设置文件。

source install/setup.bash

(如果``timed_synthetic_bag``目录已经存在,你必须在运行节点之前先将其删除。)

现在运行节点:

ros2 run bag_recorder_nodes data_generator_node

等待大约30秒,然后使用 ctrl-c 终止节点。接下来,播放已创建的 bag 文件。

ros2 bag play timed_synthetic_bag

打开第二个终端并回显 /synthetic 话题。

ros2 topic echo /synthetic

您将在控制台上以每秒一条消息的速度看到生成并存储在 bag 文件中的数据被打印出来。

5 使用可执行文件记录合成数据。

现在你可以创建一个能够存储来自话题以外数据的袋子了,接下来你将学习如何从非节点可执行文件生成和记录合成数据。这种方法的优点是代码更简单,可以快速创建大量数据。

5.1 编写一个 C++ 可执行文件

ros2_ws/src/bag_recorder_nodes/src 目录下创建一个名为 data_generator_executable.cpp 的新文件,并将以下代码粘贴进去。

#include <chrono>

#include <rclcpp/rclcpp.hpp>  // For rclcpp::Clock, rclcpp::Duration and rclcpp::Time
#include <example_interfaces/msg/int32.hpp>

#include <rosbag2_cpp/writer.hpp>
#include <rosbag2_cpp/writers/sequential_writer.hpp>
#include <rosbag2_storage/serialized_bag_message.hpp>

using namespace std::chrono_literals;

int main(int, char**)
{
  example_interfaces::msg::Int32 data;
  data.data = 0;
  std::unique_ptr<rosbag2_cpp::Writer> writer_ = std::make_unique<rosbag2_cpp::Writer>();

  writer_->open("big_synthetic_bag");

  writer_->create_topic(
    {"synthetic",
     "example_interfaces/msg/Int32",
     rmw_get_serialization_format(),
     ""});

  rclcpp::Clock clock;
  rclcpp::Time time_stamp = clock.now();
  for (int32_t ii = 0; ii < 100; ++ii) {
    writer_->write(data, "synthetic", time_stamp);
    ++data.data;
    time_stamp += rclcpp::Duration(1s);
  }

  return 0;
}

5.2 检查代码

通过比较这个示例和之前的示例,我们会发现它们并没有那么不同。唯一的显著差异是使用了for循环来驱动数据生成,而不是使用定时器。

请注意,我们现在还为数据生成时间戳,而不是依赖于当前系统时间为每个样本生成时间戳。时间戳可以是任何您需要的值。数据将按照这些时间戳给出的速度进行播放,因此这是控制样本默认播放速度的一种有用方式。还要注意,虽然每个样本之间的间隔是一秒钟,但这个可执行文件不需要在每个样本之间等待一秒钟。这样我们就能够在比播放所需的时间少得多的时间内生成大量跨越很长时间范围的数据。

rclcpp::Clock clock;
rclcpp::Time time_stamp = clock.now();
for (int32_t ii = 0; ii < 100; ++ii) {
  writer_->write(data, "synthetic", time_stamp);
  ++data.data;
  time_stamp += rclcpp::Duration(1s);
}

5.3 添加可执行文件

打开``CMakeLists.txt``文件,在之前添加的行后面添加以下行。

add_executable(data_generator_executable src/data_generator_executable.cpp)
ament_target_dependencies(data_generator_executable rclcpp rosbag2_cpp example_interfaces)

install(TARGETS
  data_generator_executable
  DESTINATION lib/${PROJECT_NAME}
)

5.4 构建和运行

返回到你的工作空间根目录``ros2_ws``,并构建你的包。

colcon build --packages-select bag_recorder_nodes

打开终端,进入 ros2_ws 目录,并加载设置文件。

source install/setup.bash

(如果 big_synthetic_bag 目录已经存在,您必须先删除它,然后再运行可执行文件。)

现在运行可执行文件:

ros2 run bag_recorder_nodes data_generator_executable

注意可执行文件的运行和完成非常快速。

现在播放创建的包。

ros2 bag play big_synthetic_bag

打开第二个终端并回显 /synthetic 话题。

ros2 topic echo /synthetic

您将会看到以每秒一条消息的速率在控制台打印在包中生成并存储的数据。即使包生成速度很快,回放仍按照时间戳指示的速率进行。

总结

你创建了一个节点,它将接收到的数据记录到一个包(bag)中。你测试了使用该节点录制包,并通过回放包来验证数据是否已记录。然后,你继续创建了一个节点和一个可执行文件,用于生成合成数据并将其存储在包中。