@@ -56,14 +56,16 @@ struct PublisherOptionsBase
5656template <typename Allocator>
5757struct PublisherOptionsWithAllocator : public PublisherOptionsBase
5858{
59- // / Optional custom allocator.
60- std::shared_ptr<Allocator> allocator = nullptr ;
61-
62- PublisherOptionsWithAllocator<Allocator>() {}
59+ PublisherOptionsWithAllocator<Allocator>()
60+ : allocator_( new Allocator()),
61+ message_allocator_ (*allocator_)
62+ {}
6363
6464 // / Constructor using base class as input.
6565 explicit PublisherOptionsWithAllocator (const PublisherOptionsBase & publisher_options_base)
66- : PublisherOptionsBase(publisher_options_base)
66+ : PublisherOptionsBase(publisher_options_base),
67+ allocator_(new Allocator()),
68+ message_allocator_(*allocator_)
6769 {}
6870
6971 // / Convert this class, and a rclcpp::QoS, into an rcl_publisher_options_t.
@@ -72,12 +74,7 @@ struct PublisherOptionsWithAllocator : public PublisherOptionsBase
7274 to_rcl_publisher_options (const rclcpp::QoS & qos) const
7375 {
7476 rcl_publisher_options_t result = rcl_publisher_get_default_options ();
75- using AllocatorTraits = std::allocator_traits<Allocator>;
76- using MessageAllocatorT = typename AllocatorTraits::template rebind_alloc<MessageT>;
77- auto message_alloc = std::make_shared<MessageAllocatorT>(*this ->get_allocator ().get ());
78- // TODO(stevewolter): This is likely to invoke undefined behavior - message_alloc goes
79- // out of scope at the end of this function, but the allocator doesn't. See #1339.
80- result.allocator = get_rcl_allocator (*message_alloc);
77+ result.allocator = get_rcl_allocator (message_allocator_);
8178 result.qos = qos.get_rmw_qos_profile ();
8279
8380 // Apply payload to rcl_publisher_options if necessary.
@@ -89,20 +86,19 @@ struct PublisherOptionsWithAllocator : public PublisherOptionsBase
8986 }
9087
9188
92- // / Get the allocator, creating one if needed.
89+ // / Get the allocator
9390 std::shared_ptr<Allocator>
9491 get_allocator () const
9592 {
96- if (!this ->allocator ) {
97- // TODO(wjwwood): I would like to use the commented line instead, but
98- // cppcheck 1.89 fails with:
99- // Syntax Error: AST broken, binary operator '>' doesn't have two operands.
100- // return std::make_shared<Allocator>();
101- std::shared_ptr<Allocator> tmp (new Allocator ());
102- return tmp;
103- }
104- return this ->allocator ;
93+ return allocator_;
10594 }
95+
96+ private:
97+ using AllocatorTraits = std::allocator_traits<Allocator>;
98+ using MessageAllocatorT = typename AllocatorTraits::template rebind_alloc<MessageT>;
99+
100+ std::shared_ptr<Allocator> allocator_;
101+ MessageAllocatorT message_allocator_;
106102};
107103
108104using PublisherOptions = PublisherOptionsWithAllocator<std::allocator<void >>;
0 commit comments