1515#include < chrono>
1616#include < list>
1717#include < memory>
18+ #include < memory_resource>
1819#include < string>
1920#include < utility>
2021
@@ -28,69 +29,34 @@ using namespace std::chrono_literals;
2829// For demonstration purposes only, not necessary for allocator_traits
2930static uint32_t num_allocs = 0 ;
3031static uint32_t num_deallocs = 0 ;
31- // A very simple custom allocator. Counts calls to allocate and deallocate.
32- template <typename T = void >
33- struct MyAllocator
32+ // A very simple custom memory resource. Counts calls to do_allocate and do_deallocate.
33+ class CustomMemoryResource : public std ::pmr::memory_resource
3434{
35- public:
36- using value_type = T;
37- using size_type = std::size_t ;
38- using pointer = T *;
39- using const_pointer = const T *;
40- using difference_type = typename std::pointer_traits<pointer>::difference_type;
41-
42- MyAllocator () noexcept
35+ private:
36+ void * do_allocate (std::size_t bytes, std::size_t alignment) override
4337 {
44- }
45-
46- ~MyAllocator () noexcept {}
47-
48- template <typename U>
49- MyAllocator (const MyAllocator<U> &) noexcept
50- {
51- }
52-
53- T * allocate (size_t size, const void * = 0 )
54- {
55- if (size == 0 ) {
56- return nullptr ;
57- }
5838 num_allocs++;
59- return static_cast <T *>(std::malloc (size * sizeof (T)));
39+ (void )alignment;
40+ return std::malloc (bytes);
6041 }
6142
62- void deallocate (T * ptr, size_t size)
43+ void do_deallocate (
44+ void * p, std::size_t bytes,
45+ std::size_t alignment) override
6346 {
64- (void )size;
65- if (!ptr) {
66- return ;
67- }
6847 num_deallocs++;
69- std::free (ptr);
48+ (void )bytes;
49+ (void )alignment;
50+ std::free (p);
7051 }
7152
72- template < typename U>
73- struct rebind
53+ bool do_is_equal (
54+ const std::pmr::memory_resource & other) const noexcept override
7455 {
75- typedef MyAllocator<U> other;
76- };
56+ return this == & other;
57+ }
7758};
7859
79- template <typename T, typename U>
80- constexpr bool operator ==(
81- const MyAllocator<T> &,
82- const MyAllocator<U> &) noexcept
83- {
84- return true ;
85- }
86-
87- template <typename T, typename U>
88- constexpr bool operator !=(
89- const MyAllocator<T> &,
90- const MyAllocator<U> &) noexcept
91- {
92- return false ;
93- }
9460
9561// Override global new and delete to count calls during execution.
9662
@@ -130,7 +96,7 @@ void operator delete(void * ptr) noexcept
13096int main (int argc, char ** argv)
13197{
13298 using rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy;
133- using Alloc = MyAllocator <void >;
99+ using Alloc = std::pmr::polymorphic_allocator <void >;
134100 using MessageAllocTraits =
135101 rclcpp::allocator::AllocRebind<std_msgs::msg::UInt32, Alloc>;
136102 using MessageAlloc = MessageAllocTraits::allocator_type;
@@ -184,7 +150,8 @@ int main(int argc, char ** argv)
184150 };
185151
186152 // Create a custom allocator and pass the allocator to the publisher and subscriber.
187- auto alloc = std::make_shared<Alloc>();
153+ CustomMemoryResource mem_resource{};
154+ auto alloc = std::make_shared<Alloc>(&mem_resource);
188155 rclcpp::PublisherOptionsWithAllocator<Alloc> publisher_options;
189156 publisher_options.allocator = alloc;
190157 auto publisher = node->create_publisher <std_msgs::msg::UInt32>(
0 commit comments