3737namespace rclcpp
3838{
3939
40- typedef std::variant<
41- std::function<void (dynamic_typesupport::DynamicMessage::SharedPtr)>,
42- std::function<void (dynamic_typesupport::DynamicMessage::SharedPtr, const MessageInfo &)>,
43- std::function<void (std::shared_ptr<SerializedMessage>)>,
44- std::function<void (std::shared_ptr<SerializedMessage>, const MessageInfo &)>
45- > AnyDynamicSubscriptionCallback;
46-
4740// / %Subscription for messages whose type descriptions are obtained at runtime.
4841/* *
4942 * Since the type is not known at compile time, this is not a template, and the dynamic library
@@ -54,6 +47,18 @@ typedef std::variant<
5447class DynamicSubscription : public rclcpp ::SubscriptionBase
5548{
5649public:
50+ typedef std::function<void (dynamic_typesupport::DynamicMessage::SharedPtr)> DynamicCallback;
51+ typedef std::function<void (dynamic_typesupport::DynamicMessage::SharedPtr,
52+ const MessageInfo &)> DynamicInfoCallback;
53+ typedef std::function<void (std::shared_ptr<SerializedMessage>)> SerializedCallback;
54+ typedef std::function<void (std::shared_ptr<SerializedMessage>,
55+ const MessageInfo &)> SerializedInfoCallback;
56+
57+ typedef std::variant<
58+ DynamicCallback, DynamicInfoCallback, SerializedCallback, SerializedInfoCallback
59+ > AnyCallback;
60+
61+
5762 // cppcheck-suppress unknownMacro
5863 RCLCPP_SMART_PTR_DEFINITIONS (DynamicSubscription)
5964
@@ -63,7 +68,7 @@ class DynamicSubscription : public rclcpp::SubscriptionBase
6368 rclcpp::dynamic_typesupport::DynamicMessageTypeSupport::SharedPtr type_support,
6469 const std::string & topic_name,
6570 const rclcpp::QoS & qos,
66- AnyDynamicSubscriptionCallback callback,
71+ AnyCallback callback,
6772 const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options)
6873 : SubscriptionBase(
6974 node_base,
@@ -165,10 +170,10 @@ class DynamicSubscription : public rclcpp::SubscriptionBase
165170private:
166171 RCLCPP_DISABLE_COPY (DynamicSubscription)
167172
168- static bool is_callback_serialized(const rclcpp::AnyDynamicSubscriptionCallback &);
173+ static bool is_callback_serialized(const AnyCallback &);
169174
170175 rclcpp::dynamic_typesupport::DynamicMessageTypeSupport::SharedPtr ts_;
171- rclcpp::AnyDynamicSubscriptionCallback callback_;
176+ AnyCallback callback_;
172177
173178 rclcpp::dynamic_typesupport::DynamicSerializationSupport::SharedPtr serialization_support_;
174179 rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr dynamic_message_;
0 commit comments