Skip to content

Commit dd1ab8c

Browse files
committed
Refactor dynamic typesupport to couple serialization support to objects
Signed-off-by: methylDragon <[email protected]>
1 parent 0a45133 commit dd1ab8c

File tree

9 files changed

+23
-35
lines changed

9 files changed

+23
-35
lines changed

rclcpp/include/rclcpp/dynamic_subscription.hpp

Lines changed: 7 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -53,11 +53,10 @@ class DynamicSubscription : public rclcpp::SubscriptionBase
5353
rosidl_message_type_support_t & type_support_handle,
5454
const std::string & topic_name,
5555
const rclcpp::QoS & qos,
56-
// TODO(methylDragons): Eventually roll out an rclcpp::DynamicData that encompasses the serialization_support
57-
// support and DynamicData, and pass that to the callback
58-
std::function<void(
59-
std::shared_ptr<rosidl_dynamic_typesupport_serialization_support_t>, std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t>
60-
)> callback,
56+
// TODO(methylDragons): Eventually roll out an rclcpp::DynamicMessage that encompasses the
57+
// serialization_support support and DynamicData, and pass that to the
58+
// callback
59+
std::function<void(std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t>)> callback,
6160
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
6261
bool use_take_dynamic_message = false)
6362
: SubscriptionBase(
@@ -77,7 +76,7 @@ class DynamicSubscription : public rclcpp::SubscriptionBase
7776
!= rmw_dynamic_typesupport_c__identifier)
7877
{
7978
throw std::runtime_error(
80-
"DynamicSubscription must use runtime type introspection type support!");
79+
"DynamicSubscription must use dynamic type introspection type support!");
8180
}
8281
}
8382

@@ -145,7 +144,7 @@ class DynamicSubscription : public rclcpp::SubscriptionBase
145144
void return_serialized_message(std::shared_ptr<rclcpp::SerializedMessage> & message) override;
146145

147146

148-
// RUNTIME TYPE ==================================================================================
147+
// DYNAMIC TYPE ==================================================================================
149148
// TODO(methylDragon): Reorder later
150149
RCLCPP_PUBLIC
151150
std::shared_ptr<rosidl_dynamic_typesupport_dynamic_type_t>
@@ -161,7 +160,6 @@ class DynamicSubscription : public rclcpp::SubscriptionBase
161160

162161
RCLCPP_PUBLIC
163162
void handle_dynamic_message(
164-
const std::shared_ptr<rosidl_dynamic_typesupport_serialization_support_t> & serialization_support,
165163
const std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t> & dyn_data,
166164
const rclcpp::MessageInfo & message_info
167165
) override;
@@ -171,10 +169,7 @@ class DynamicSubscription : public rclcpp::SubscriptionBase
171169
RCLCPP_DISABLE_COPY(DynamicSubscription)
172170

173171
rosidl_message_type_support_t & ts_;
174-
175-
std::function<void(
176-
std::shared_ptr<rosidl_dynamic_typesupport_serialization_support_t>, std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t>
177-
)> callback_;
172+
std::function<void(std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t>)> callback_;
178173
};
179174

180175
} // namespace rclcpp

rclcpp/include/rclcpp/generic_subscription.hpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -124,7 +124,7 @@ class GenericSubscription : public rclcpp::SubscriptionBase
124124
void return_serialized_message(std::shared_ptr<rclcpp::SerializedMessage> & message) override;
125125

126126

127-
// RUNTIME TYPE ==================================================================================
127+
// DYNAMIC TYPE ==================================================================================
128128
// TODO(methylDragon): Reorder later
129129
RCLCPP_PUBLIC
130130
std::shared_ptr<rosidl_dynamic_typesupport_dynamic_type_t> get_dynamic_type() override;
@@ -137,7 +137,6 @@ class GenericSubscription : public rclcpp::SubscriptionBase
137137

138138
RCLCPP_PUBLIC
139139
void handle_dynamic_message(
140-
const std::shared_ptr<rosidl_dynamic_typesupport_serialization_support_t> & serialization_support,
141140
const std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t> & dyn_data,
142141
const rclcpp::MessageInfo & message_info) override;
143142

rclcpp/include/rclcpp/subscription.hpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -388,7 +388,7 @@ class Subscription : public SubscriptionBase
388388
return any_callback_.use_take_shared_method();
389389
}
390390

391-
// RUNTIME TYPE ==================================================================================
391+
// DYNAMIC TYPE ==================================================================================
392392
// TODO(methylDragon): Reorder later
393393
// TODO(methylDragon): Implement later...
394394
std::shared_ptr<rosidl_dynamic_typesupport_dynamic_type_t>
@@ -414,11 +414,9 @@ class Subscription : public SubscriptionBase
414414

415415
void
416416
handle_dynamic_message(
417-
const std::shared_ptr<rosidl_dynamic_typesupport_serialization_support_t> & serialization_support,
418417
const std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t> & dyn_data,
419418
const rclcpp::MessageInfo & message_info) override
420419
{
421-
(void) serialization_support;
422420
(void) dyn_data;
423421
(void) message_info;
424422
throw rclcpp::exceptions::UnimplementedError(

rclcpp/include/rclcpp/subscription_base.hpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -542,7 +542,7 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
542542
rclcpp::ContentFilterOptions
543543
get_content_filter() const;
544544

545-
// RUNTIME TYPE ==================================================================================
545+
// DYNAMIC TYPE ==================================================================================
546546
// TODO(methylDragon): Reorder later
547547
RCLCPP_PUBLIC
548548
virtual
@@ -563,7 +563,6 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
563563
virtual
564564
void
565565
handle_dynamic_message(
566-
const std::shared_ptr<rosidl_dynamic_typesupport_serialization_support_t> & serialization_support,
567566
const std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t> & dyn_data,
568567
const rclcpp::MessageInfo & message_info
569568
) = 0;
@@ -573,12 +572,12 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
573572
// bool
574573
// take_dynamic_message(rosidl_dynamic_typesupport_dynamic_data_t * message_out, rclcpp::MessageInfo & message_info_out);
575574

576-
/// Return if the subscription should use runtime type
575+
/// Return if the subscription should use dynamic type
577576
/**
578577
* This will cause the subscription to use the handle_dynamic_message methods, which must be
579578
* used with take_serialized or take_dynamic_message.
580579
*
581-
* \return `true` if the subscription should use a runtime type callback, `false` otherwise
580+
* \return `true` if the subscription should use a dynamic type callback, `false` otherwise
582581
*/
583582
RCLCPP_PUBLIC
584583
bool

rclcpp/src/rclcpp/dynamic_subscription.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ void DynamicSubscription::return_serialized_message(
6868
}
6969

7070

71-
// RUNTIME TYPE ====================================================================================
71+
// DYNAMIC TYPE ====================================================================================
7272
// TODO(methylDragon): Re-order later
7373
std::shared_ptr<rosidl_dynamic_typesupport_dynamic_type_t>
7474
DynamicSubscription::get_dynamic_type()
@@ -84,7 +84,7 @@ DynamicSubscription::get_dynamic_type()
8484
// NOTE(methylDragon): Should we store a separate copy of dynamic data in the sub so it isn't tied
8585
// to the typesupport instead?
8686
// If that's the case, will there ever be a lifetime contention between a sub
87-
// that manages the data and the callback/user usage of the data?
87+
// that manages the data and the callback/user usage of the data?
8888
std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t>
8989
DynamicSubscription::get_dynamic_data()
9090
{
@@ -107,11 +107,10 @@ std::shared_ptr<rosidl_dynamic_typesupport_serialization_support_t> DynamicSubsc
107107
};
108108

109109
void DynamicSubscription::handle_dynamic_message(
110-
const std::shared_ptr<rosidl_dynamic_typesupport_serialization_support_t> & serialization_support,
111110
const std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t> & dyn_data,
112111
const rclcpp::MessageInfo &)
113112
{
114-
callback_(serialization_support, dyn_data);
113+
callback_(dyn_data);
115114
}
116115

117116
} // namespace rclcpp

rclcpp/src/rclcpp/executor.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -601,12 +601,12 @@ Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr subscription)
601601
message_info.get_rmw_message_info().from_intra_process = false;
602602

603603
// PROPOSED ======================================================================================
604-
// If a subscription is meant to use_dynamic_message_cb, then it will use its serialization-specific
605-
// dynamic data.
604+
// If a subscription is meant to use_dynamic_message_cb, then it will use its
605+
// serialization-specific dynamic data.
606606
//
607607
// Two cases:
608-
// - Runtime type subscription using dynamic type stored in its own internal type support struct
609-
// - Non-runtime type subscription with no stored dynamic type
608+
// - Dynamic type subscription using dynamic type stored in its own internal type support struct
609+
// - Non-dynamic type subscription with no stored dynamic type
610610
// - Subscriptions of this type must be able to lookup the local message description to
611611
// generate a dynamic type at runtime!
612612
// - TODO(methylDragon): I won't be handling this case yet
@@ -637,7 +637,7 @@ Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr subscription)
637637
if (ret != RMW_RET_OK) {
638638
throw_from_rcl_error(ret, "Couldn't convert serialized message to dynamic data!");
639639
}
640-
subscription->handle_dynamic_message(serialization_support, dyn_data, message_info);
640+
subscription->handle_dynamic_message(dyn_data, message_info);
641641
}
642642
);
643643
subscription->return_serialized_message(serialized_msg);

rclcpp/src/rclcpp/generic_subscription.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ void GenericSubscription::return_serialized_message(
7272
}
7373

7474

75-
// RUNTIME TYPE ==================================================================================
75+
// DYNAMIC TYPE ==================================================================================
7676
// TODO(methylDragon): Reorder later
7777
std::shared_ptr<rosidl_dynamic_typesupport_dynamic_type_t>
7878
GenericSubscription::get_dynamic_type()
@@ -97,11 +97,9 @@ GenericSubscription::get_serialization_support()
9797

9898
void
9999
GenericSubscription::handle_dynamic_message(
100-
const std::shared_ptr<rosidl_dynamic_typesupport_serialization_support_t> & serialization_support,
101100
const std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t> & dyn_data,
102101
const rclcpp::MessageInfo & message_info)
103102
{
104-
(void) serialization_support;
105103
(void) dyn_data;
106104
(void) message_info;
107105
throw rclcpp::exceptions::UnimplementedError(

rclcpp/src/rclcpp/subscription_base.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -516,7 +516,7 @@ SubscriptionBase::get_content_filter() const
516516
}
517517

518518

519-
// RUNTIME TYPE ==================================================================================
519+
// DYNAMIC TYPE ==================================================================================
520520
// TODO(methylDragon): Reorder later
521521
bool
522522
SubscriptionBase::use_dynamic_message_cb() const

rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,7 @@ class TestSubscription : public rclcpp::SubscriptionBase
8282
std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t> get_dynamic_data() override {return nullptr;}
8383
std::shared_ptr<rosidl_dynamic_typesupport_serialization_support_t> get_serialization_support() override {return nullptr;}
8484
void handle_dynamic_message(
85-
const std::shared_ptr<rosidl_dynamic_typesupport_serialization_support_t> &, const std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t> &,
85+
const std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t> &,
8686
const rclcpp::MessageInfo &) override {}
8787
};
8888

0 commit comments

Comments
 (0)