Skip to content

Commit b4ac2cb

Browse files
committed
Drop the generic version of get_rcl_allocator.
This allows us to simplify a bunch of code as well. Signed-off-by: Steve Wolter <[email protected]>
1 parent 6e22e2f commit b4ac2cb

File tree

6 files changed

+31
-115
lines changed

6 files changed

+31
-115
lines changed

rclcpp/include/rclcpp/allocator/allocator_common.hpp

+4-52
Original file line numberDiff line numberDiff line change
@@ -29,64 +29,16 @@ namespace allocator
2929
template<typename T, typename Alloc>
3030
using AllocRebind = typename std::allocator_traits<Alloc>::template rebind_traits<T>;
3131

32-
template<typename Alloc>
33-
void * retyped_allocate(size_t size, void * untyped_allocator)
34-
{
35-
auto typed_allocator = static_cast<Alloc *>(untyped_allocator);
36-
if (!typed_allocator) {
37-
throw std::runtime_error("Received incorrect allocator type");
38-
}
39-
return std::allocator_traits<Alloc>::allocate(*typed_allocator, size);
40-
}
41-
42-
template<typename Alloc>
43-
void retyped_deallocate(void * untyped_pointer, void * untyped_allocator)
44-
{
45-
auto typed_allocator = static_cast<Alloc *>(untyped_allocator);
46-
if (!typed_allocator) {
47-
throw std::runtime_error("Received incorrect allocator type");
48-
}
49-
auto typed_ptr = static_cast<typename Alloc::value_type *>(untyped_pointer);
50-
std::allocator_traits<Alloc>::deallocate(*typed_allocator, typed_ptr, 1);
51-
}
52-
53-
template<typename Alloc>
54-
void * retyped_reallocate(void * untyped_pointer, size_t size, void * untyped_allocator)
55-
{
56-
auto typed_allocator = static_cast<Alloc *>(untyped_allocator);
57-
if (!typed_allocator) {
58-
throw std::runtime_error("Received incorrect allocator type");
59-
}
60-
auto typed_ptr = static_cast<typename Alloc::value_type *>(untyped_pointer);
61-
std::allocator_traits<Alloc>::deallocate(*typed_allocator, typed_ptr, 1);
62-
return std::allocator_traits<Alloc>::allocate(*typed_allocator, size);
63-
}
64-
6532
} // namespace allocator
6633

67-
// Deprecated: Generic converter from C++ allocator into RCL allocator.
68-
// This allocator overallocates memory by 100x and invokes UB on free,
69-
// see #1254.
70-
template<typename Alloc>
71-
rcl_allocator_t get_rcl_allocator(Alloc & allocator)
72-
{
73-
rcl_allocator_t rcl_allocator = rcl_get_default_allocator();
74-
#ifndef _WIN32
75-
rcl_allocator.allocate = &allocator::retyped_allocate<Alloc>;
76-
rcl_allocator.deallocate = &allocator::retyped_deallocate<Alloc>;
77-
rcl_allocator.reallocate = &allocator::retyped_reallocate<Alloc>;
78-
rcl_allocator.state = &allocator;
79-
#else
80-
(void)allocator; // Remove warning
81-
#endif
82-
return rcl_allocator;
83-
}
84-
8534
// Builds the RCL default allocator for the C++ standard allocator.
8635
// This assumes that the user intent behind both allocators is the
8736
// same: Using system malloc for allocation.
37+
//
38+
// If you're using a custom allocator in ROS, you'll need to provide
39+
// your own overload for this function.
8840
template<typename T>
89-
rcl_allocator_t get_rcl_allocator(std::allocator<T> & allocator)
41+
rcl_allocator_t get_rcl_allocator(std::allocator<T> allocator)
9042
{
9143
(void)allocator; // Remove warning
9244
return rcl_get_default_allocator();

rclcpp/include/rclcpp/publisher_options.hpp

+16-17
Original file line numberDiff line numberDiff line change
@@ -56,16 +56,14 @@ struct PublisherOptionsBase
5656
template<typename Allocator>
5757
struct PublisherOptionsWithAllocator : public PublisherOptionsBase
5858
{
59-
PublisherOptionsWithAllocator<Allocator>()
60-
: allocator_(new Allocator()),
61-
message_allocator_(*allocator_)
62-
{}
59+
/// Optional custom allocator.
60+
std::shared_ptr<Allocator> allocator = nullptr;
61+
62+
PublisherOptionsWithAllocator<Allocator>() {}
6363

6464
/// Constructor using base class as input.
6565
explicit PublisherOptionsWithAllocator(const PublisherOptionsBase & publisher_options_base)
66-
: PublisherOptionsBase(publisher_options_base),
67-
allocator_(new Allocator()),
68-
message_allocator_(*allocator_)
66+
: PublisherOptionsBase(publisher_options_base)
6967
{}
7068

7169
/// Convert this class, and a rclcpp::QoS, into an rcl_publisher_options_t.
@@ -74,7 +72,7 @@ struct PublisherOptionsWithAllocator : public PublisherOptionsBase
7472
to_rcl_publisher_options(const rclcpp::QoS & qos) const
7573
{
7674
rcl_publisher_options_t result = rcl_publisher_get_default_options();
77-
result.allocator = get_rcl_allocator(message_allocator_);
75+
result.allocator = get_rcl_allocator(*this->get_allocator());
7876
result.qos = qos.get_rmw_qos_profile();
7977

8078
// Apply payload to rcl_publisher_options if necessary.
@@ -86,19 +84,20 @@ struct PublisherOptionsWithAllocator : public PublisherOptionsBase
8684
}
8785

8886

89-
/// Get the allocator
87+
/// Get the allocator, creating one if needed.
9088
std::shared_ptr<Allocator>
9189
get_allocator() const
9290
{
93-
return allocator_;
91+
if (!this->allocator) {
92+
// TODO(wjwwood): I would like to use the commented line instead, but
93+
// cppcheck 1.89 fails with:
94+
// Syntax Error: AST broken, binary operator '>' doesn't have two operands.
95+
// return std::make_shared<Allocator>();
96+
std::shared_ptr<Allocator> tmp(new Allocator());
97+
return tmp;
98+
}
99+
return this->allocator;
94100
}
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_;
102101
};
103102

104103
using PublisherOptions = PublisherOptionsWithAllocator<std::allocator<void>>;

rclcpp/include/rclcpp/subscription_options.hpp

+11-17
Original file line numberDiff line numberDiff line change
@@ -78,17 +78,15 @@ struct SubscriptionOptionsBase
7878
template<typename Allocator>
7979
struct SubscriptionOptionsWithAllocator : public SubscriptionOptionsBase
8080
{
81-
SubscriptionOptionsWithAllocator<Allocator>()
82-
: allocator_(new Allocator()),
83-
message_allocator_(*allocator_)
84-
{}
81+
/// Optional custom allocator.
82+
std::shared_ptr<Allocator> allocator = nullptr;
83+
84+
SubscriptionOptionsWithAllocator<Allocator>() {}
8585

8686
/// Constructor using base class as input.
8787
explicit SubscriptionOptionsWithAllocator(
8888
const SubscriptionOptionsBase & subscription_options_base)
89-
: SubscriptionOptionsBase(subscription_options_base),
90-
allocator_(new Allocator()),
91-
message_allocator_(*allocator_)
89+
: SubscriptionOptionsBase(subscription_options_base)
9290
{}
9391

9492
/// Convert this class, with a rclcpp::QoS, into an rcl_subscription_options_t.
@@ -101,7 +99,7 @@ struct SubscriptionOptionsWithAllocator : public SubscriptionOptionsBase
10199
to_rcl_subscription_options(const rclcpp::QoS & qos) const
102100
{
103101
rcl_subscription_options_t result = rcl_subscription_get_default_options();
104-
result.allocator = get_rcl_allocator(message_allocator_);
102+
result.allocator = get_rcl_allocator(*this->get_allocator());
105103
result.qos = qos.get_rmw_qos_profile();
106104
result.rmw_subscription_options.ignore_local_publications = this->ignore_local_publications;
107105

@@ -113,19 +111,15 @@ struct SubscriptionOptionsWithAllocator : public SubscriptionOptionsBase
113111
return result;
114112
}
115113

116-
/// Get the allocator
114+
/// Get the allocator, creating one if needed.
117115
std::shared_ptr<Allocator>
118116
get_allocator() const
119117
{
120-
return allocator_
118+
if (!this->allocator) {
119+
return std::make_shared<Allocator>();
120+
}
121+
return this->allocator;
121122
}
122-
123-
private:
124-
using AllocatorTraits = std::allocator_traits<Allocator>;
125-
using MessageAllocatorT = typename AllocatorTraits::template rebind_alloc<MessageT>;
126-
127-
std::shared_ptr<Allocator> allocator_;
128-
MessageAllocatorT message_allocator_;
129123
};
130124

131125
using SubscriptionOptions = SubscriptionOptionsWithAllocator<std::allocator<void>>;

rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,6 @@ NodeParameters::NodeParameters(
6060
// TODO(wjwwood): expose this allocator through the Parameter interface.
6161
rclcpp::PublisherOptionsWithAllocator<AllocatorT> publisher_options(
6262
parameter_event_publisher_options);
63-
publisher_options.allocator = std::make_shared<AllocatorT>();
6463

6564
if (start_parameter_services) {
6665
parameter_service_ = std::make_shared<ParameterService>(node_base, node_services, this);

rclcpp/test/rclcpp/allocator/test_allocator_common.cpp

-27
Original file line numberDiff line numberDiff line change
@@ -18,33 +18,6 @@
1818

1919
#include "rclcpp/allocator/allocator_common.hpp"
2020

21-
TEST(TestAllocatorCommon, retyped_allocate) {
22-
std::allocator<int> allocator;
23-
void * untyped_allocator = &allocator;
24-
void * allocated_mem =
25-
rclcpp::allocator::retyped_allocate<std::allocator<char>>(1u, untyped_allocator);
26-
ASSERT_NE(nullptr, allocated_mem);
27-
28-
auto code = [&untyped_allocator, allocated_mem]() {
29-
rclcpp::allocator::retyped_deallocate<std::allocator<int>>(
30-
allocated_mem, untyped_allocator);
31-
};
32-
EXPECT_NO_THROW(code());
33-
34-
allocated_mem = allocator.allocate(1);
35-
ASSERT_NE(nullptr, allocated_mem);
36-
void * reallocated_mem =
37-
rclcpp::allocator::retyped_reallocate<std::allocator<int>>(
38-
allocated_mem, 2u, untyped_allocator);
39-
ASSERT_NE(nullptr, reallocated_mem);
40-
41-
auto code2 = [&untyped_allocator, reallocated_mem]() {
42-
rclcpp::allocator::retyped_deallocate<std::allocator<int>>(
43-
reallocated_mem, untyped_allocator);
44-
};
45-
EXPECT_NO_THROW(code2());
46-
}
47-
4821
TEST(TestAllocatorCommon, get_rcl_allocator) {
4922
std::allocator<int> allocator;
5023
auto rcl_allocator = rclcpp::get_rcl_allocator(allocator);

rclcpp/test/rclcpp/test_subscription.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -246,7 +246,6 @@ TEST_F(TestSubscription, various_creation_signatures) {
246246
}
247247
{
248248
rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void>> options;
249-
options.allocator = std::make_shared<std::allocator<void>>();
250249
EXPECT_NE(nullptr, options.get_allocator());
251250
auto sub = rclcpp::create_subscription<Empty>(
252251
node, "topic", 42, cb, options);

0 commit comments

Comments
 (0)