Skip to content

Commit 0fd00b4

Browse files
committed
Refactor dynamic message type support init and to use refs
* Implement runtime type typesupport struct Signed-off-by: methylDragon <[email protected]> * Implement first cut Signed-off-by: methylDragon <[email protected]> * Migrate to rosidl_dynamic_typesupport and update field IDs Signed-off-by: methylDragon <[email protected]> * Migrate to type description interfaces Signed-off-by: methylDragon <[email protected]> * Fix const Signed-off-by: methylDragon <[email protected]> * Refine signatures and use return types Signed-off-by: methylDragon <[email protected]> * Fix C linkage Signed-off-by: methylDragon <[email protected]> * Migrate methods to use return types Signed-off-by: methylDragon <[email protected]> * Lint Signed-off-by: methylDragon <[email protected]> * Support type hashes Signed-off-by: methylDragon <[email protected]> * Remove identifier alias Signed-off-by: methylDragon <[email protected]> * Change fini to destroy Signed-off-by: methylDragon <[email protected]> * Use create instead of init Signed-off-by: methylDragon <[email protected]> * Add rcutils conversion function and remove rmw interfaces Signed-off-by: methylDragon <[email protected]> * Clean up some comments Signed-off-by: methylDragon <[email protected]> --------- Signed-off-by: methylDragon <[email protected]>
1 parent 32859cd commit 0fd00b4

12 files changed

+142
-313
lines changed

rclcpp/include/rclcpp/dynamic_subscription.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -58,13 +58,13 @@ class DynamicSubscription : public rclcpp::SubscriptionBase
5858
const rclcpp::QoS & qos,
5959
std::function<void(
6060
rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr,
61-
std::shared_ptr<const rosidl_runtime_c__type_description__TypeDescription>
61+
const rosidl_runtime_c__type_description__TypeDescription &
6262
)> callback,
6363
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
6464
bool use_take_dynamic_message = true)
6565
: SubscriptionBase(
6666
node_base,
67-
*(type_support->get_rosidl_message_type_support()),
67+
type_support->get_const_rosidl_message_type_support(),
6868
topic_name,
6969
options.to_rcl_subscription_options(
7070
qos),
@@ -81,7 +81,7 @@ class DynamicSubscription : public rclcpp::SubscriptionBase
8181
throw std::runtime_error("DynamicMessageTypeSupport cannot be nullptr!");
8282
}
8383

84-
if (type_support->get_rosidl_message_type_support()->typesupport_identifier !=
84+
if (type_support->get_const_rosidl_message_type_support().typesupport_identifier !=
8585
rosidl_get_dynamic_typesupport_identifier())
8686
{
8787
throw std::runtime_error(
@@ -163,7 +163,7 @@ class DynamicSubscription : public rclcpp::SubscriptionBase
163163
rclcpp::dynamic_typesupport::DynamicMessageTypeSupport::SharedPtr ts_;
164164
std::function<void(
165165
rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr,
166-
std::shared_ptr<const rosidl_runtime_c__type_description__TypeDescription>
166+
const rosidl_runtime_c__type_description__TypeDescription &
167167
)> callback_;
168168

169169
rclcpp::dynamic_typesupport::DynamicSerializationSupport::SharedPtr serialization_support_;

rclcpp/include/rclcpp/dynamic_typesupport/dynamic_message.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -122,7 +122,7 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>
122122
// GETTERS =======================================================================================
123123
RCLCPP_PUBLIC
124124
const std::string
125-
get_library_identifier() const;
125+
get_serialization_library_identifier() const;
126126

127127
RCLCPP_PUBLIC
128128
const std::string

rclcpp/include/rclcpp/dynamic_typesupport/dynamic_message_type.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -122,7 +122,7 @@ class DynamicMessageType : public std::enable_shared_from_this<DynamicMessageTyp
122122
// GETTERS =======================================================================================
123123
RCLCPP_PUBLIC
124124
const std::string
125-
get_library_identifier() const;
125+
get_serialization_library_identifier() const;
126126

127127
RCLCPP_PUBLIC
128128
const std::string

rclcpp/include/rclcpp/dynamic_typesupport/dynamic_message_type_builder.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -123,7 +123,7 @@ class DynamicMessageTypeBuilder : public std::enable_shared_from_this<DynamicMes
123123
// GETTERS =======================================================================================
124124
RCLCPP_PUBLIC
125125
const std::string
126-
get_library_identifier() const;
126+
get_serialization_library_identifier() const;
127127

128128
RCLCPP_PUBLIC
129129
const std::string

rclcpp/include/rclcpp/dynamic_typesupport/dynamic_message_type_support.hpp

+23-61
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
#ifndef RCLCPP__DYNAMIC_TYPESUPPORT__DYNAMIC_MESSAGE_TYPE_SUPPORT_HPP_
1616
#define RCLCPP__DYNAMIC_TYPESUPPORT__DYNAMIC_MESSAGE_TYPE_SUPPORT_HPP_
1717

18+
#include <rcl/allocator.h>
19+
1820
#include <rosidl_dynamic_typesupport/dynamic_message_type_support_struct.h>
1921
#include <rosidl_dynamic_typesupport/types.h>
2022
#include <rosidl_runtime_c/message_type_support_struct.h>
@@ -30,7 +32,6 @@
3032
#include "rclcpp/macros.hpp"
3133
#include "rclcpp/visibility_control.hpp"
3234

33-
3435
namespace rclcpp
3536
{
3637
namespace dynamic_typesupport
@@ -44,7 +45,7 @@ namespace dynamic_typesupport
4445
* support struct, instead of `rcl_dynamic_message_type_support_handle_create()`,
4546
* because this class will manage the lifetimes for you.
4647
*
47-
* Do NOT call rcl_dynamic_message_type_support_handle_destroy!!
48+
* Do NOT call rcl_dynamic_message_type_support_handle_fini!!
4849
*
4950
* This class:
5051
* - Manages the lifetime of the raw pointer.
@@ -68,16 +69,17 @@ class DynamicMessageTypeSupport : public std::enable_shared_from_this<DynamicMes
6869
RCLCPP_PUBLIC
6970
DynamicMessageTypeSupport(
7071
const rosidl_runtime_c__type_description__TypeDescription & description,
71-
const std::string & serialization_library_name = "");
72+
const std::string & serialization_library_name = "",
73+
rcl_allocator_t allocator = rcl_get_default_allocator());
7274

7375
/// From description, for provided serialization support
7476
/// Does NOT take ownership of the description (copies instead.)
75-
/// Constructs type support top-down (calling
76-
/// `rosidl_dynamic_message_type_support_handle_create()`)
77+
/// Constructs type support top-down (calling `rosidl_dynamic_message_type_support_handle_init()`)
7778
RCLCPP_PUBLIC
7879
DynamicMessageTypeSupport(
7980
DynamicSerializationSupport::SharedPtr serialization_support,
80-
const rosidl_runtime_c__type_description__TypeDescription & description);
81+
const rosidl_runtime_c__type_description__TypeDescription & description,
82+
rcl_allocator_t allocator = rcl_get_default_allocator());
8183

8284
/// Assume ownership of managed types
8385
/// Does NOT take ownership of the description (copies instead.)
@@ -93,7 +95,8 @@ class DynamicMessageTypeSupport : public std::enable_shared_from_this<DynamicMes
9395
DynamicSerializationSupport::SharedPtr serialization_support,
9496
DynamicMessageType::SharedPtr dynamic_message_type,
9597
DynamicMessage::SharedPtr dynamic_message,
96-
const rosidl_runtime_c__type_description__TypeDescription & description);
98+
const rosidl_runtime_c__type_description__TypeDescription & description,
99+
rcl_allocator_t allocator = rcl_get_default_allocator());
97100

98101
RCLCPP_PUBLIC
99102
virtual ~DynamicMessageTypeSupport();
@@ -102,40 +105,20 @@ class DynamicMessageTypeSupport : public std::enable_shared_from_this<DynamicMes
102105
// GETTERS =======================================================================================
103106
RCLCPP_PUBLIC
104107
const std::string
105-
get_library_identifier() const;
106-
107-
RCLCPP_PUBLIC
108-
rosidl_message_type_support_t *
109-
get_rosidl_message_type_support();
110-
111-
RCLCPP_PUBLIC
112-
const rosidl_message_type_support_t *
113-
get_rosidl_message_type_support() const;
108+
get_serialization_library_identifier() const;
114109

115110
RCLCPP_PUBLIC
116-
std::shared_ptr<rosidl_message_type_support_t>
117-
get_shared_rosidl_message_type_support();
111+
const rosidl_message_type_support_t &
112+
get_const_rosidl_message_type_support();
118113

119114
RCLCPP_PUBLIC
120-
std::shared_ptr<const rosidl_message_type_support_t>
121-
get_shared_rosidl_message_type_support() const;
115+
const rosidl_message_type_support_t &
116+
get_const_rosidl_message_type_support() const;
122117

123118
RCLCPP_PUBLIC
124-
rosidl_runtime_c__type_description__TypeDescription *
125-
get_rosidl_runtime_c_type_description();
126-
127-
RCLCPP_PUBLIC
128-
const rosidl_runtime_c__type_description__TypeDescription *
119+
const rosidl_runtime_c__type_description__TypeDescription &
129120
get_rosidl_runtime_c_type_description() const;
130121

131-
RCLCPP_PUBLIC
132-
std::shared_ptr<rosidl_runtime_c__type_description__TypeDescription>
133-
get_shared_rosidl_runtime_c_type_description();
134-
135-
RCLCPP_PUBLIC
136-
std::shared_ptr<const rosidl_runtime_c__type_description__TypeDescription>
137-
get_shared_rosidl_runtime_c_type_description() const;
138-
139122
RCLCPP_PUBLIC
140123
DynamicSerializationSupport::SharedPtr
141124
get_shared_dynamic_serialization_support();
@@ -163,42 +146,21 @@ class DynamicMessageTypeSupport : public std::enable_shared_from_this<DynamicMes
163146
protected:
164147
RCLCPP_DISABLE_COPY(DynamicMessageTypeSupport)
165148

166-
DynamicSerializationSupport::SharedPtr serialization_support_;
167-
DynamicMessageType::SharedPtr dynamic_message_type_;
168-
DynamicMessage::SharedPtr dynamic_message_;
169-
std::shared_ptr<rosidl_runtime_c__type_description__TypeDescription> description_;
170-
171-
std::shared_ptr<rosidl_message_type_support_t> rosidl_message_type_support_;
149+
RCLCPP_PUBLIC
150+
rosidl_message_type_support_t &
151+
get_rosidl_message_type_support();
172152

173153
private:
174154
RCLCPP_PUBLIC
175155
DynamicMessageTypeSupport();
176156

177-
RCLCPP_PUBLIC
178-
void
179-
manage_description_(rosidl_runtime_c__type_description__TypeDescription * description);
180-
181-
RCLCPP_PUBLIC
182-
void
183-
init_dynamic_message_type_(
184-
DynamicSerializationSupport::SharedPtr serialization_support,
185-
const rosidl_runtime_c__type_description__TypeDescription * description);
186-
187-
RCLCPP_PUBLIC
188-
void
189-
init_dynamic_message_(DynamicMessageType::SharedPtr dynamic_type);
157+
DynamicSerializationSupport::SharedPtr serialization_support_;
158+
DynamicMessageType::SharedPtr dynamic_message_type_;
159+
DynamicMessage::SharedPtr dynamic_message_;
190160

191-
// By aggregation
192-
RCLCPP_PUBLIC
193-
void
194-
init_rosidl_message_type_support_(
195-
DynamicSerializationSupport::SharedPtr serialization_support,
196-
DynamicMessageType::SharedPtr dynamic_message_type,
197-
DynamicMessage::SharedPtr dynamic_message,
198-
rosidl_runtime_c__type_description__TypeDescription * description);
161+
rosidl_message_type_support_t rosidl_message_type_support_;
199162
};
200163

201-
202164
} // namespace dynamic_typesupport
203165
} // namespace rclcpp
204166

rclcpp/include/rclcpp/dynamic_typesupport/dynamic_serialization_support.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ class DynamicSerializationSupport : public std::enable_shared_from_this<DynamicS
7878
// GETTERS =======================================================================================
7979
RCLCPP_PUBLIC
8080
const std::string
81-
get_library_identifier() const;
81+
get_serialization_library_identifier() const;
8282

8383
RCLCPP_PUBLIC
8484
rosidl_dynamic_typesupport_serialization_support_t *

rclcpp/src/rclcpp/dynamic_subscription.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -107,7 +107,7 @@ void DynamicSubscription::handle_dynamic_message(
107107
const rclcpp::MessageInfo & message_info)
108108
{
109109
(void) message_info;
110-
callback_(message, ts_->get_shared_rosidl_runtime_c_type_description());
110+
callback_(message, ts_->get_rosidl_runtime_c_type_description());
111111
}
112112

113113
} // namespace rclcpp

rclcpp/src/rclcpp/dynamic_typesupport/dynamic_message.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -247,7 +247,7 @@ DynamicMessage::match_serialization_support_(
247247
{
248248
bool out = true;
249249

250-
if (serialization_support.get_library_identifier() != std::string(
250+
if (serialization_support.get_serialization_library_identifier() != std::string(
251251
rosidl_dynamic_type_data.serialization_support->library_identifier))
252252
{
253253
RCUTILS_LOG_ERROR("serialization support library identifier does not match dynamic data's");
@@ -268,7 +268,7 @@ DynamicMessage::match_serialization_support_(
268268

269269
// GETTERS =======================================================================================
270270
const std::string
271-
DynamicMessage::get_library_identifier() const
271+
DynamicMessage::get_serialization_library_identifier() const
272272
{
273273
return std::string(rosidl_dynamic_data_->serialization_support->library_identifier);
274274
}
@@ -453,7 +453,7 @@ DynamicMessage::init_from_type_shared(DynamicMessageType & type) const
453453
bool
454454
DynamicMessage::equals(const DynamicMessage & other) const
455455
{
456-
if (get_library_identifier() != other.get_library_identifier()) {
456+
if (get_serialization_library_identifier() != other.get_serialization_library_identifier()) {
457457
throw std::runtime_error("library identifiers don't match");
458458
}
459459
bool equals;

rclcpp/src/rclcpp/dynamic_typesupport/dynamic_message_type.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -181,7 +181,7 @@ DynamicMessageType::match_serialization_support_(
181181
{
182182
bool out = true;
183183

184-
if (serialization_support.get_library_identifier() != std::string(
184+
if (serialization_support.get_serialization_library_identifier() != std::string(
185185
rosidl_dynamic_type.serialization_support->library_identifier))
186186
{
187187
RCUTILS_LOG_ERROR(
@@ -204,7 +204,7 @@ DynamicMessageType::match_serialization_support_(
204204

205205
// GETTERS =========================================================================================
206206
const std::string
207-
DynamicMessageType::get_library_identifier() const
207+
DynamicMessageType::get_serialization_library_identifier() const
208208
{
209209
return std::string(rosidl_dynamic_type_->serialization_support->library_identifier);
210210
}
@@ -310,7 +310,7 @@ DynamicMessageType::clone_shared() const
310310
bool
311311
DynamicMessageType::equals(const DynamicMessageType & other) const
312312
{
313-
if (get_library_identifier() != other.get_library_identifier()) {
313+
if (get_serialization_library_identifier() != other.get_serialization_library_identifier()) {
314314
throw std::runtime_error("library identifiers don't match");
315315
}
316316
bool out;

rclcpp/src/rclcpp/dynamic_typesupport/dynamic_message_type_builder.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -211,7 +211,7 @@ DynamicMessageTypeBuilder::match_serialization_support_(
211211
{
212212
bool out = true;
213213

214-
if (serialization_support.get_library_identifier() != std::string(
214+
if (serialization_support.get_serialization_library_identifier() != std::string(
215215
rosidl_dynamic_type_builder.serialization_support->library_identifier))
216216
{
217217
RCUTILS_LOG_ERROR(
@@ -234,7 +234,7 @@ DynamicMessageTypeBuilder::match_serialization_support_(
234234

235235
// GETTERS =======================================================================================
236236
const std::string
237-
DynamicMessageTypeBuilder::get_library_identifier() const
237+
DynamicMessageTypeBuilder::get_serialization_library_identifier() const
238238
{
239239
return std::string(rosidl_dynamic_type_builder_->serialization_support->library_identifier);
240240
}

0 commit comments

Comments
 (0)