Skip to content

Commit c8734b3

Browse files
committed
Refactor dynamic type support structs to use allocators and refs
Signed-off-by: methylDragon <[email protected]>
1 parent 8447d36 commit c8734b3

13 files changed

+479
-658
lines changed

rclcpp/include/rclcpp/dynamic_typesupport/detail/dynamic_message_impl.hpp

+12-12
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@
3737
{ \
3838
ValueT out; \
3939
rosidl_dynamic_typesupport_dynamic_data_get_ ## FunctionT ## _value( \
40-
rosidl_dynamic_data_.get(), id, &out); \
40+
&rosidl_dynamic_data_, id, &out); \
4141
return out; \
4242
}
4343

@@ -55,7 +55,7 @@
5555
DynamicMessage::set_value<ValueT>(rosidl_dynamic_typesupport_member_id_t id, ValueT value) \
5656
{ \
5757
rosidl_dynamic_typesupport_dynamic_data_set_ ## FunctionT ## _value( \
58-
rosidl_dynamic_data_.get(), id, value); \
58+
&rosidl_dynamic_data_, id, value); \
5959
}
6060

6161
#define __DYNAMIC_MESSAGE_SET_VALUE_BY_NAME_FN(ValueT, FunctionT) \
@@ -73,7 +73,7 @@
7373
{ \
7474
rosidl_dynamic_typesupport_member_id_t out; \
7575
rosidl_dynamic_typesupport_dynamic_data_insert_ ## FunctionT ## _value( \
76-
rosidl_dynamic_data_.get(), value, &out); \
76+
&rosidl_dynamic_data_, value, &out); \
7777
return out; \
7878
}
7979

@@ -127,7 +127,7 @@ std::byte
127127
DynamicMessage::get_value<std::byte>(rosidl_dynamic_typesupport_member_id_t id)
128128
{
129129
unsigned char out;
130-
rosidl_dynamic_typesupport_dynamic_data_get_byte_value(get_rosidl_dynamic_data(), id, &out);
130+
rosidl_dynamic_typesupport_dynamic_data_get_byte_value(&get_rosidl_dynamic_data(), id, &out);
131131
return static_cast<std::byte>(out);
132132
}
133133

@@ -146,7 +146,7 @@ DynamicMessage::set_value<std::byte>(
146146
rosidl_dynamic_typesupport_member_id_t id, const std::byte value)
147147
{
148148
rosidl_dynamic_typesupport_dynamic_data_set_byte_value(
149-
rosidl_dynamic_data_.get(), id, static_cast<unsigned char>(value));
149+
&rosidl_dynamic_data_, id, static_cast<unsigned char>(value));
150150
}
151151

152152

@@ -164,7 +164,7 @@ DynamicMessage::insert_value<std::byte>(const std::byte value)
164164
{
165165
rosidl_dynamic_typesupport_member_id_t out;
166166
rosidl_dynamic_typesupport_dynamic_data_insert_byte_value(
167-
rosidl_dynamic_data_.get(), static_cast<unsigned char>(value), &out);
167+
&rosidl_dynamic_data_, static_cast<unsigned char>(value), &out);
168168
return out;
169169
}
170170

@@ -177,7 +177,7 @@ DynamicMessage::get_value<std::string>(rosidl_dynamic_typesupport_member_id_t id
177177
size_t buf_length;
178178
char * buf = nullptr;
179179
rosidl_dynamic_typesupport_dynamic_data_get_string_value(
180-
get_rosidl_dynamic_data(), id, &buf, &buf_length);
180+
&get_rosidl_dynamic_data(), id, &buf, &buf_length);
181181
auto out = std::string(buf, buf_length);
182182
delete buf;
183183
return out;
@@ -191,7 +191,7 @@ DynamicMessage::get_value<std::u16string>(rosidl_dynamic_typesupport_member_id_t
191191
size_t buf_length;
192192
char16_t * buf = nullptr;
193193
rosidl_dynamic_typesupport_dynamic_data_get_wstring_value(
194-
get_rosidl_dynamic_data(), id, &buf, &buf_length);
194+
&get_rosidl_dynamic_data(), id, &buf, &buf_length);
195195
auto out = std::u16string(buf, buf_length);
196196
delete buf;
197197
return out;
@@ -220,7 +220,7 @@ DynamicMessage::set_value<std::string>(
220220
rosidl_dynamic_typesupport_member_id_t id, const std::string value)
221221
{
222222
rosidl_dynamic_typesupport_dynamic_data_set_string_value(
223-
rosidl_dynamic_data_.get(), id, value.c_str(), value.size());
223+
&rosidl_dynamic_data_, id, value.c_str(), value.size());
224224
}
225225

226226

@@ -230,7 +230,7 @@ DynamicMessage::set_value<std::u16string>(
230230
rosidl_dynamic_typesupport_member_id_t id, const std::u16string value)
231231
{
232232
rosidl_dynamic_typesupport_dynamic_data_set_wstring_value(
233-
rosidl_dynamic_data_.get(), id, value.c_str(), value.size());
233+
&rosidl_dynamic_data_, id, value.c_str(), value.size());
234234
}
235235

236236

@@ -256,7 +256,7 @@ DynamicMessage::insert_value<std::string>(const std::string value)
256256
{
257257
rosidl_dynamic_typesupport_member_id_t out;
258258
rosidl_dynamic_typesupport_dynamic_data_insert_string_value(
259-
rosidl_dynamic_data_.get(), value.c_str(), value.size(), &out);
259+
&rosidl_dynamic_data_, value.c_str(), value.size(), &out);
260260
return out;
261261
}
262262

@@ -267,7 +267,7 @@ DynamicMessage::insert_value<std::u16string>(const std::u16string value)
267267
{
268268
rosidl_dynamic_typesupport_member_id_t out;
269269
rosidl_dynamic_typesupport_dynamic_data_insert_wstring_value(
270-
rosidl_dynamic_data_.get(), value.c_str(), value.size(), &out);
270+
&rosidl_dynamic_data_, value.c_str(), value.size(), &out);
271271
return out;
272272
}
273273

rclcpp/include/rclcpp/dynamic_typesupport/detail/dynamic_message_type_builder_impl.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@
3939
const std::string & default_value) \
4040
{ \
4141
rosidl_dynamic_typesupport_dynamic_type_builder_add_ ## FunctionT ## _member( \
42-
rosidl_dynamic_type_builder_.get(), \
42+
&rosidl_dynamic_type_builder_, \
4343
id, name.c_str(), name.size(), default_value.c_str(), default_value.size()); \
4444
}
4545

@@ -52,7 +52,7 @@
5252
const std::string & default_value) \
5353
{ \
5454
rosidl_dynamic_typesupport_dynamic_type_builder_add_ ## FunctionT ## _array_member( \
55-
rosidl_dynamic_type_builder_.get(), \
55+
&rosidl_dynamic_type_builder_, \
5656
id, name.c_str(), name.size(), default_value.c_str(), default_value.size(), \
5757
array_length); \
5858
}
@@ -67,7 +67,7 @@
6767
{ \
6868
rosidl_dynamic_typesupport_dynamic_type_builder_add_ ## FunctionT ## \
6969
_unbounded_sequence_member( \
70-
rosidl_dynamic_type_builder_.get(), \
70+
&rosidl_dynamic_type_builder_, \
7171
id, name.c_str(), name.size(), default_value.c_str(), default_value.size()); \
7272
}
7373

@@ -81,7 +81,7 @@
8181
const std::string & default_value) \
8282
{ \
8383
rosidl_dynamic_typesupport_dynamic_type_builder_add_ ## FunctionT ## _bounded_sequence_member( \
84-
rosidl_dynamic_type_builder_.get(), \
84+
&rosidl_dynamic_type_builder_, \
8585
id, name.c_str(), name.size(), default_value.c_str(), default_value.size(), \
8686
sequence_bound); \
8787
}

rclcpp/include/rclcpp/dynamic_typesupport/dynamic_message.hpp

+49-47
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef RCLCPP__DYNAMIC_TYPESUPPORT__DYNAMIC_MESSAGE_HPP_
1616
#define RCLCPP__DYNAMIC_TYPESUPPORT__DYNAMIC_MESSAGE_HPP_
1717

18+
#include <rcl/allocator.h>
1819
#include <rcl/types.h>
1920
#include <rosidl_dynamic_typesupport/types.h>
2021

@@ -26,21 +27,18 @@
2627
#include "rclcpp/macros.hpp"
2728
#include "rclcpp/visibility_control.hpp"
2829

29-
3030
namespace rclcpp
3131
{
3232
namespace dynamic_typesupport
3333
{
3434

35-
3635
class DynamicMessageType;
3736
class DynamicMessageTypeBuilder;
3837

39-
/// Utility wrapper class for rosidl_dynamic_typesupport_dynamic_data_t *
38+
/// Utility wrapper class for rosidl_dynamic_typesupport_dynamic_data_t
4039
/**
4140
* This class:
42-
* - Manages the lifetime of the raw pointer.
43-
* - Exposes getter methods to get the raw pointer and shared pointers
41+
* - Exposes getter methods for the struct
4442
* - Exposes the underlying serialization support API
4543
*
4644
* Ownership:
@@ -67,50 +65,48 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>
6765
// the data should be the exact same object managed by the DynamicSerializationSupport,
6866
// otherwise the lifetime management will not work properly.
6967

70-
/// Construct a new DynamicMessage with the provided dynamic type builder
68+
/// Construct a new DynamicMessage with the provided dynamic type builder, using its allocator
7169
RCLCPP_PUBLIC
7270
explicit DynamicMessage(std::shared_ptr<DynamicMessageTypeBuilder> dynamic_type_builder);
7371

74-
/// Construct a new DynamicMessage with the provided dynamic type
72+
/// Construct a new DynamicMessage with the provided dynamic type builder and allocator
73+
RCLCPP_PUBLIC
74+
DynamicMessage(
75+
std::shared_ptr<DynamicMessageTypeBuilder> dynamic_type_builder,
76+
rcl_allocator_t allocator);
77+
78+
/// Construct a new DynamicMessage with the provided dynamic type, using its allocator
7579
RCLCPP_PUBLIC
7680
explicit DynamicMessage(std::shared_ptr<DynamicMessageType> dynamic_type);
7781

78-
/// Assume ownership of raw pointer
82+
/// Construct a new DynamicMessage with the provided dynamic type and allocator
7983
RCLCPP_PUBLIC
8084
DynamicMessage(
81-
DynamicSerializationSupport::SharedPtr serialization_support,
82-
rosidl_dynamic_typesupport_dynamic_data_t * rosidl_dynamic_data);
85+
std::shared_ptr<DynamicMessageType> dynamic_type,
86+
rcl_allocator_t allocator);
8387

84-
/// Copy shared pointer
88+
/// Assume ownership of struct
8589
RCLCPP_PUBLIC
8690
DynamicMessage(
8791
DynamicSerializationSupport::SharedPtr serialization_support,
88-
std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t> rosidl_dynamic_data);
92+
rosidl_dynamic_typesupport_dynamic_data_t && rosidl_dynamic_data);
8993

9094
/// Loaning constructor
91-
/// Must only be called with raw ptr obtained from loaning!
95+
/// Must only be called with a rosidl dynaimc data object obtained from loaning!
9296
// NOTE(methylDragon): I'd put this in protected, but I need this exposed to
9397
// enable_shared_from_this...
9498
RCLCPP_PUBLIC
9599
DynamicMessage(
96100
DynamicMessage::SharedPtr parent_data,
97-
rosidl_dynamic_typesupport_dynamic_data_t * rosidl_loaned_data);
101+
rosidl_dynamic_typesupport_dynamic_data_t && rosidl_loaned_data);
98102

99103
// NOTE(methylDragon): Deliberately no constructor from description to nudge users towards using
100104
// construction from dynamic type/builder, which is more efficient
101105

102-
/// Copy constructor
103-
RCLCPP_PUBLIC
104-
DynamicMessage(const DynamicMessage & other);
105-
106106
/// Move constructor
107107
RCLCPP_PUBLIC
108108
DynamicMessage(DynamicMessage && other) noexcept;
109109

110-
/// Copy assignment
111-
RCLCPP_PUBLIC
112-
DynamicMessage & operator=(const DynamicMessage & other);
113-
114110
/// Move assignment
115111
RCLCPP_PUBLIC
116112
DynamicMessage & operator=(DynamicMessage && other) noexcept;
@@ -129,21 +125,13 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>
129125
get_name() const;
130126

131127
RCLCPP_PUBLIC
132-
rosidl_dynamic_typesupport_dynamic_data_t *
128+
rosidl_dynamic_typesupport_dynamic_data_t &
133129
get_rosidl_dynamic_data();
134130

135131
RCLCPP_PUBLIC
136-
const rosidl_dynamic_typesupport_dynamic_data_t *
132+
const rosidl_dynamic_typesupport_dynamic_data_t &
137133
get_rosidl_dynamic_data() const;
138134

139-
RCLCPP_PUBLIC
140-
std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t>
141-
get_shared_rosidl_dynamic_data();
142-
143-
RCLCPP_PUBLIC
144-
std::shared_ptr<const rosidl_dynamic_typesupport_dynamic_data_t>
145-
get_shared_rosidl_dynamic_data() const;
146-
147135
RCLCPP_PUBLIC
148136
DynamicSerializationSupport::SharedPtr
149137
get_shared_dynamic_serialization_support();
@@ -176,31 +164,37 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>
176164
// METHODS =======================================================================================
177165
RCLCPP_PUBLIC
178166
DynamicMessage
179-
clone() const;
167+
clone(rcl_allocator_t allocator = rcl_get_default_allocator());
180168

181169
RCLCPP_PUBLIC
182170
DynamicMessage::SharedPtr
183-
clone_shared() const;
171+
clone_shared(rcl_allocator_t allocator = rcl_get_default_allocator());
184172

185173
RCLCPP_PUBLIC
186174
DynamicMessage
187-
init_from_type(DynamicMessageType & type) const;
175+
init_from_type(
176+
DynamicMessageType & type, rcl_allocator_t allocator = rcl_get_default_allocator()) const;
188177

189178
RCLCPP_PUBLIC
190179
DynamicMessage::SharedPtr
191-
init_from_type_shared(DynamicMessageType & type) const;
180+
init_from_type_shared(
181+
DynamicMessageType & type, rcl_allocator_t allocator = rcl_get_default_allocator()) const;
192182

193183
RCLCPP_PUBLIC
194184
bool
195185
equals(const DynamicMessage & other) const;
196186

197187
RCLCPP_PUBLIC
198188
DynamicMessage::SharedPtr
199-
loan_value(rosidl_dynamic_typesupport_member_id_t id);
189+
loan_value(
190+
rosidl_dynamic_typesupport_member_id_t id,
191+
rcl_allocator_t allocator = rcl_get_default_allocator());
200192

201193
RCLCPP_PUBLIC
202194
DynamicMessage::SharedPtr
203-
loan_value(const std::string & name);
195+
loan_value(
196+
const std::string & name,
197+
rcl_allocator_t allocator = rcl_get_default_allocator());
204198

205199
RCLCPP_PUBLIC
206200
void
@@ -232,11 +226,11 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>
232226

233227
RCLCPP_PUBLIC
234228
bool
235-
serialize(rcl_serialized_message_t * buffer);
229+
serialize(rcl_serialized_message_t & buffer);
236230

237231
RCLCPP_PUBLIC
238232
bool
239-
deserialize(rcl_serialized_message_t * buffer);
233+
deserialize(rcl_serialized_message_t & buffer);
240234

241235

242236
// MEMBER ACCESS TEMPLATES =======================================================================
@@ -366,19 +360,27 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>
366360
// NESTED MEMBER ACCESS ==========================================================================
367361
RCLCPP_PUBLIC
368362
DynamicMessage
369-
get_complex_value(rosidl_dynamic_typesupport_member_id_t id);
363+
get_complex_value(
364+
rosidl_dynamic_typesupport_member_id_t id,
365+
rcl_allocator_t allocator = rcl_get_default_allocator());
370366

371367
RCLCPP_PUBLIC
372368
DynamicMessage
373-
get_complex_value(const std::string & name);
369+
get_complex_value(
370+
const std::string & name,
371+
rcl_allocator_t allocator = rcl_get_default_allocator());
374372

375373
RCLCPP_PUBLIC
376374
DynamicMessage::SharedPtr
377-
get_complex_value_shared(rosidl_dynamic_typesupport_member_id_t id);
375+
get_complex_value_shared(
376+
rosidl_dynamic_typesupport_member_id_t id,
377+
rcl_allocator_t allocator = rcl_get_default_allocator());
378378

379379
RCLCPP_PUBLIC
380380
DynamicMessage::SharedPtr
381-
get_complex_value_shared(const std::string & name);
381+
get_complex_value_shared(
382+
const std::string & name,
383+
rcl_allocator_t allocator = rcl_get_default_allocator());
382384

383385
RCLCPP_PUBLIC
384386
void
@@ -405,14 +407,15 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>
405407
// DynamicSerializationSupport
406408
DynamicSerializationSupport::SharedPtr serialization_support_;
407409

408-
std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t> rosidl_dynamic_data_;
409-
410+
rosidl_dynamic_typesupport_dynamic_data_t rosidl_dynamic_data_;
410411
bool is_loaned_;
411412

412413
// Used for returning the loaned value, and lifetime management
413414
DynamicMessage::SharedPtr parent_data_;
414415

415416
private:
417+
RCLCPP_DISABLE_COPY(DynamicMessage)
418+
416419
RCLCPP_PUBLIC
417420
DynamicMessage();
418421

@@ -423,7 +426,6 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>
423426
const rosidl_dynamic_typesupport_dynamic_data_t & dynamic_data);
424427
};
425428

426-
427429
} // namespace dynamic_typesupport
428430
} // namespace rclcpp
429431

0 commit comments

Comments
 (0)