diff --git a/demo_nodes_cpp/src/topics/allocator_tutorial.cpp b/demo_nodes_cpp/src/topics/allocator_tutorial.cpp index 81aeeed22..0d8bad71f 100644 --- a/demo_nodes_cpp/src/topics/allocator_tutorial.cpp +++ b/demo_nodes_cpp/src/topics/allocator_tutorial.cpp @@ -15,6 +15,7 @@ #include #include #include +#include #include #include @@ -28,69 +29,34 @@ using namespace std::chrono_literals; // For demonstration purposes only, not necessary for allocator_traits static uint32_t num_allocs = 0; static uint32_t num_deallocs = 0; -// A very simple custom allocator. Counts calls to allocate and deallocate. -template -struct MyAllocator +// A very simple custom memory resource. Counts calls to do_allocate and do_deallocate. +class CustomMemoryResource : public std::pmr::memory_resource { -public: - using value_type = T; - using size_type = std::size_t; - using pointer = T *; - using const_pointer = const T *; - using difference_type = typename std::pointer_traits::difference_type; - - MyAllocator() noexcept +private: + void * do_allocate(std::size_t bytes, std::size_t alignment) override { - } - - ~MyAllocator() noexcept {} - - template - MyAllocator(const MyAllocator &) noexcept - { - } - - T * allocate(size_t size, const void * = 0) - { - if (size == 0) { - return nullptr; - } num_allocs++; - return static_cast(std::malloc(size * sizeof(T))); + (void)alignment; + return std::malloc(bytes); } - void deallocate(T * ptr, size_t size) + void do_deallocate( + void * p, std::size_t bytes, + std::size_t alignment) override { - (void)size; - if (!ptr) { - return; - } num_deallocs++; - std::free(ptr); + (void)bytes; + (void)alignment; + std::free(p); } - template - struct rebind + bool do_is_equal( + const std::pmr::memory_resource & other) const noexcept override { - typedef MyAllocator other; - }; + return this == &other; + } }; -template -constexpr bool operator==( - const MyAllocator &, - const MyAllocator &) noexcept -{ - return true; -} - -template -constexpr bool operator!=( - const MyAllocator &, - const MyAllocator &) noexcept -{ - return false; -} // Override global new and delete to count calls during execution. @@ -130,7 +96,7 @@ void operator delete(void * ptr) noexcept int main(int argc, char ** argv) { using rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy; - using Alloc = MyAllocator; + using Alloc = std::pmr::polymorphic_allocator; using MessageAllocTraits = rclcpp::allocator::AllocRebind; using MessageAlloc = MessageAllocTraits::allocator_type; @@ -184,7 +150,8 @@ int main(int argc, char ** argv) }; // Create a custom allocator and pass the allocator to the publisher and subscriber. - auto alloc = std::make_shared(); + CustomMemoryResource mem_resource{}; + auto alloc = std::make_shared(&mem_resource); rclcpp::PublisherOptionsWithAllocator publisher_options; publisher_options.allocator = alloc; auto publisher = node->create_publisher(