目标:本教程将展示在编写 ROS 2 C++ 代码时如何使用自定义内存分配器。
教程级别:高级
时间:20 分钟
目录
背景
编写分配器
编写一个示例主程序
将分配器传递到进程内管道
测试和验证代码
TLSF 分配器
本教程将教您如何为发布者和订阅者集成自定义分配器,以便在您的 ROS 节点执行时从不调用默认堆分配器。本教程的代码可在此处获得。https://github.com/ros2/demos/blob/jazzy/demo_nodes_cpp/src/topics/allocator_tutorial_pmr.cpp
背景
假设您想编写实时安全代码,并且您听说过在实时关键部分调用 new
的许多危险,因为大多数平台上的默认堆分配器是非确定性的。
默认情况下,许多 C++ 标准库结构在增长时会隐式分配内存,例如 std::vector
。然而,这些数据结构也接受一个“分配器Allocator”模板参数。如果您为这些数据结构之一指定一个自定义分配器,它将使用该分配器而不是系统分配器来增长或缩小数据结构。您的自定义分配器可以在堆栈上预先分配一块内存池,这可能更适合实时应用程序。
在 ROS 2 C++ 客户端库 (rclcpp) 中,我们遵循与 C++ 标准库类似的理念。发布者Publishers、订阅者subscribers和执行器Executor接受一个分配器模板参数,该参数控制该实体在执行期间进行的分配。
编写一个分配器
要编写与 ROS 2 的分配器接口兼容的分配器,您的分配器必须与 C++ 标准库分配器接口兼容。
自 C++17 起,标准库提供了一种称为 std::pmr::memory_resource
的东西。这是一个可以派生的类,用于创建满足最低要求的自定义分配器。
例如,以下自定义内存资源的声明满足要求(当然,您仍然需要在此类中实现声明的函数):
这是一个自定义内存资源类 CustomMemoryResource
,继承自 std::pmr::memory_resource
。该类重写了三个方法:
do_allocate
:用于分配指定大小和对齐方式的内存。do_deallocate
:用于释放指定大小和对齐方式的内存。do_is_equal
:用于比较两个内存资源是否相等。
// 定义一个名为 CustomMemoryResource 的类,继承自 std::pmr::memory_resource
class CustomMemoryResource : public std::pmr::memory_resource
{
private:
// 重写 do_allocate 方法,用于分配内存
void * do_allocate(std::size_t bytes, std::size_t alignment) override;
// 重写 do_deallocate 方法,用于释放内存
void do_deallocate(
void * p, std::size_t bytes,
std::size_t alignment) override;
// 重写 do_is_equal 方法,用于比较两个内存资源是否相等
bool do_is_equal(
const std::pmr::memory_resource & other) const noexcept override;
};
要了解 std::pmr::memory_resource
的全部功能,请参见 https://en.cppreference.com/w/cpp/memory/memory_resource。
此教程的自定义分配器的完整实现位于 https://github.com/ros2/demos/blob/jazzy/demo_nodes_cpp/src/topics/allocator_tutorial_pmr.cpp。
编写示例主程序
一旦你编写了一个有效的 C++分配器,你必须将其作为共享指针传递给你的发布者、订阅者和执行器。但首先,我们将声明一些别名以缩短名称。
// 使用命名空间简化代码
using rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy;
// 定义一个多态分配器类型
using Alloc = std::pmr::polymorphic_allocator<void>;
// 定义消息分配器特性
using MessageAllocTraits =
rclcpp::allocator::AllocRebind<std_msgs::msg::UInt32, Alloc>;
// 定义消息分配器类型
using MessageAlloc = MessageAllocTraits::allocator_type;
// 定义消息删除器类型
using MessageDeleter = rclcpp::allocator::Deleter<MessageAlloc, std_msgs::msg::UInt32>;
// 定义消息唯一指针类型
using MessageUniquePtr = std::unique_ptr<std_msgs::msg::UInt32, MessageDeleter>;
现在我们可以使用自定义分配器创建我们的资源:如何创建自定义内存资源,并将其用于ROS 2节点的发布者和订阅者。通过设置自定义内存分配器,可以在程序执行期间跟踪内存分配和释放的次数。
CustomMemoryResource mem_resource{}; // 创建自定义内存资源对象
auto alloc = std::make_shared<Alloc>(&mem_resource); // 创建共享指针分配器
rclcpp::PublisherOptionsWithAllocator<Alloc> publisher_options; // 定义发布者选项
publisher_options.allocator = alloc; // 设置发布者选项的分配器
auto publisher = node->create_publisher<std_msgs::msg::UInt32>(
"allocator_tutorial", 10, publisher_options); // 创建发布者
rclcpp::SubscriptionOptionsWithAllocator<Alloc> subscription_options; // 定义订阅者选项
subscription_options.allocator = alloc; // 设置订阅者选项的分配器
auto msg_mem_strat = std::make_shared<
rclcpp::message_memory_strategy::MessageMemoryStrategy<
std_msgs::msg::UInt32, Alloc>>(alloc); // 创建消息内存策略
auto subscriber = node->create_subscription<std_msgs::msg::UInt32>(
"allocator_tutorial", 10, callback, subscription_options, msg_mem_strat); // 创建订阅者
std::shared_ptr<rclcpp::memory_strategy::MemoryStrategy> memory_strategy =
std::make_shared<AllocatorMemoryStrategy<Alloc>>(alloc); // 创建内存策略
rclcpp::ExecutorOptions options; // 定义执行器选项
options.memory_strategy = memory_strategy; // 设置执行器选项的内存策略
rclcpp::executors::SingleThreadedExecutor execut