From 0ee1ceefbc41de635e92d32cec8d66724b7f40d1 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Tue, 6 Dec 2022 14:54:32 -0800 Subject: [PATCH] Implement first cut Signed-off-by: methylDragon --- rclcpp/CMakeLists.txt | 1 + .../include/rclcpp/generic_subscription.hpp | 18 ++ rclcpp/include/rclcpp/rclcpp.hpp | 2 + .../rclcpp/runtime_type_subscription.hpp | 182 ++++++++++++++++++ rclcpp/include/rclcpp/subscription.hpp | 37 ++++ rclcpp/include/rclcpp/subscription_base.hpp | 63 +++++- rclcpp/src/rclcpp/executor.cpp | 46 +++++ rclcpp/src/rclcpp/generic_subscription.cpp | 40 +++- .../src/rclcpp/runtime_type_subscription.cpp | 117 +++++++++++ rclcpp/src/rclcpp/subscription_base.cpp | 23 ++- .../node_interfaces/test_node_topics.cpp | 7 + 11 files changed, 531 insertions(+), 5 deletions(-) create mode 100644 rclcpp/include/rclcpp/runtime_type_subscription.hpp create mode 100644 rclcpp/src/rclcpp/runtime_type_subscription.cpp diff --git a/rclcpp/CMakeLists.txt b/rclcpp/CMakeLists.txt index 3abd999f3d..4d454fe5c4 100644 --- a/rclcpp/CMakeLists.txt +++ b/rclcpp/CMakeLists.txt @@ -94,6 +94,7 @@ set(${PROJECT_NAME}_SRCS src/rclcpp/qos.cpp src/rclcpp/qos_event.cpp src/rclcpp/qos_overriding_options.cpp + src/rclcpp/runtime_type_subscription.cpp src/rclcpp/serialization.cpp src/rclcpp/serialized_message.cpp src/rclcpp/service.cpp diff --git a/rclcpp/include/rclcpp/generic_subscription.hpp b/rclcpp/include/rclcpp/generic_subscription.hpp index 12a1c79f8f..6ab7d083eb 100644 --- a/rclcpp/include/rclcpp/generic_subscription.hpp +++ b/rclcpp/include/rclcpp/generic_subscription.hpp @@ -123,6 +123,24 @@ class GenericSubscription : public rclcpp::SubscriptionBase RCLCPP_PUBLIC void return_serialized_message(std::shared_ptr & message) override; + + // RUNTIME TYPE ================================================================================== + // TODO(methylDragon): Reorder later + RCLCPP_PUBLIC + std::shared_ptr get_dynamic_type() override; + + RCLCPP_PUBLIC + std::shared_ptr get_dynamic_data() override; + + RCLCPP_PUBLIC + std::shared_ptr get_serialization_support() override; + + RCLCPP_PUBLIC + void handle_runtime_type_message( + const std::shared_ptr & ser, + const std::shared_ptr & dyn_data, + const rclcpp::MessageInfo & message_info) override; + private: RCLCPP_DISABLE_COPY(GenericSubscription) diff --git a/rclcpp/include/rclcpp/rclcpp.hpp b/rclcpp/include/rclcpp/rclcpp.hpp index f1d751ff3f..af07196587 100644 --- a/rclcpp/include/rclcpp/rclcpp.hpp +++ b/rclcpp/include/rclcpp/rclcpp.hpp @@ -167,4 +167,6 @@ #include "rclcpp/waitable.hpp" #include "rclcpp/wait_set.hpp" +#include "rclcpp/runtime_type_subscription.hpp" + #endif // RCLCPP__RCLCPP_HPP_ diff --git a/rclcpp/include/rclcpp/runtime_type_subscription.hpp b/rclcpp/include/rclcpp/runtime_type_subscription.hpp new file mode 100644 index 0000000000..a9ee646e88 --- /dev/null +++ b/rclcpp/include/rclcpp/runtime_type_subscription.hpp @@ -0,0 +1,182 @@ +// Copyright 2022 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RCLCPP__RUNTIME_TYPE_SUBSCRIPTION_HPP_ +#define RCLCPP__RUNTIME_TYPE_SUBSCRIPTION_HPP_ + +#include +#include +#include + +#include "rcpputils/shared_library.hpp" + +#include "rclcpp/callback_group.hpp" +#include "rclcpp/macros.hpp" +#include "rclcpp/node_interfaces/node_base_interface.hpp" +#include "rclcpp/node_interfaces/node_topics_interface.hpp" +#include "rclcpp/qos.hpp" +#include "rclcpp/serialized_message.hpp" +#include "rclcpp/subscription_base.hpp" +#include "rclcpp/typesupport_helpers.hpp" +#include "rclcpp/visibility_control.hpp" + +namespace rclcpp +{ + +/// %Subscription for messages whose type descriptions are obtained at runtime. +/** + * Since the type is not known at compile time, this is not a template, and the dynamic library + * containing type support information has to be identified and loaded based on the type name. + * + * NOTE(methylDragon): No considerations for intra-process handling are made. + */ +class RuntimeTypeSubscription : public rclcpp::SubscriptionBase +{ +public: + // cppcheck-suppress unknownMacro + RCLCPP_SMART_PTR_DEFINITIONS(RuntimeTypeSubscription) + + template> + RuntimeTypeSubscription( + rclcpp::node_interfaces::NodeBaseInterface * node_base, + rosidl_message_type_support_t & type_support_handle, + const std::string & topic_name, + const rclcpp::QoS & qos, + // TODO(methylDragons): Eventually roll out an rclcpp::DynamicData that encompasses the ser + // support and DynamicData, and pass that to the callback + std::function, std::shared_ptr + )> callback, + const rclcpp::SubscriptionOptionsWithAllocator & options, + bool use_take_runtime_type_message = false) + : SubscriptionBase( + node_base, + type_support_handle, + topic_name, + options.to_rcl_subscription_options(qos), + options.event_callbacks, + options.use_default_callbacks, + false, + true, + use_take_runtime_type_message), + ts_(type_support_handle), + callback_(callback) + { + if(type_support_handle.typesupport_identifier + != rmw_typesupport_runtime_type_introspection_c__identifier) + { + throw std::runtime_error( + "RuntimeTypeSubscription must use runtime type introspection type support!"); + } + } + + // TODO(methylDragon): + /// Deferred type description constructor, only usable if the middleware implementation supports + /// type discovery + // template> + // RuntimeTypeSubscription( + // rclcpp::node_interfaces::NodeBaseInterface * node_base, + // const std::string & topic_name, + // const rclcpp::QoS & qos, + // // TODO(methylDragons): Eventually roll out an rclcpp::DynamicData that encompasses the ser + // // support and DynamicData, and pass that to the callback + // std::function, std::shared_ptr + // )> callback, + // const rclcpp::SubscriptionOptionsWithAllocator & options, + // const char * serialization_lib_name = nullptr) + // : SubscriptionBase( + // node_base, + // // NOTE(methylDragon): Since the typesupport is deferred, it needs to be modified post-hoc + // // which means it technically isn't const correct... + // *rmw_get_runtime_type_message_typesupport_handle(serialization_lib_name), + // topic_name, + // options.to_rcl_subscription_options(qos), + // options.event_callbacks, + // options.use_default_callbacks, + // false, + // true), + // callback_(callback) + // {} + + RCLCPP_PUBLIC + virtual ~RuntimeTypeSubscription() = default; + + // Same as create_serialized_message() as the subscription is to serialized_messages only + RCLCPP_PUBLIC + std::shared_ptr create_message() override; + + RCLCPP_PUBLIC + std::shared_ptr create_serialized_message() override; + + /// Cast the message to a rclcpp::SerializedMessage and call the callback. + RCLCPP_PUBLIC + void handle_message( + std::shared_ptr & message, const rclcpp::MessageInfo & message_info) override; + + /// Handle dispatching rclcpp::SerializedMessage to user callback. + RCLCPP_PUBLIC + void + handle_serialized_message( + const std::shared_ptr & serialized_message, + const rclcpp::MessageInfo & message_info) override; + + /// This function is currently not implemented. + RCLCPP_PUBLIC + void handle_loaned_message( + void * loaned_message, const rclcpp::MessageInfo & message_info) override; + + // Same as return_serialized_message() as the subscription is to serialized_messages only + RCLCPP_PUBLIC + void return_message(std::shared_ptr & message) override; + + RCLCPP_PUBLIC + void return_serialized_message(std::shared_ptr & message) override; + + + // RUNTIME TYPE ================================================================================== + // TODO(methylDragon): Reorder later + RCLCPP_PUBLIC + std::shared_ptr + get_dynamic_type() override; + + RCLCPP_PUBLIC + std::shared_ptr + get_dynamic_data() override; + + RCLCPP_PUBLIC + std::shared_ptr + get_serialization_support() override; + + RCLCPP_PUBLIC + void handle_runtime_type_message( + const std::shared_ptr & ser, + const std::shared_ptr & dyn_data, + const rclcpp::MessageInfo & message_info + ) override; + + +private: + RCLCPP_DISABLE_COPY(RuntimeTypeSubscription) + + rosidl_message_type_support_t & ts_; + + std::function, std::shared_ptr + )> callback_; +}; + +} // namespace rclcpp + +#endif // RCLCPP__RUNTIME_TYPE_SUBSCRIPTION_HPP_ diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index d9e84b29f8..09f637e462 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -388,6 +388,43 @@ class Subscription : public SubscriptionBase return any_callback_.use_take_shared_method(); } + // RUNTIME TYPE ================================================================================== + // TODO(methylDragon): Reorder later + // TODO(methylDragon): Implement later... + std::shared_ptr + get_dynamic_type() override + { + throw rclcpp::exceptions::UnimplementedError( + "get_dynamic_type is not implemented for Subscription"); + } + + std::shared_ptr + get_dynamic_data() override + { + throw rclcpp::exceptions::UnimplementedError( + "get_dynamic_data is not implemented for Subscription"); + } + + std::shared_ptr + get_serialization_support() override + { + throw rclcpp::exceptions::UnimplementedError( + "get_serialization_support is not implemented for Subscription"); + } + + void + handle_runtime_type_message( + const std::shared_ptr & ser, + const std::shared_ptr & dyn_data, + const rclcpp::MessageInfo & message_info) override + { + (void) ser; + (void) dyn_data; + (void) message_info; + throw rclcpp::exceptions::UnimplementedError( + "handle_runtime_type_message is not implemented for Subscription"); + } + private: RCLCPP_DISABLE_COPY(Subscription) diff --git a/rclcpp/include/rclcpp/subscription_base.hpp b/rclcpp/include/rclcpp/subscription_base.hpp index b1aeb4eb7d..5f6ff5ef2d 100644 --- a/rclcpp/include/rclcpp/subscription_base.hpp +++ b/rclcpp/include/rclcpp/subscription_base.hpp @@ -77,6 +77,8 @@ class SubscriptionBase : public std::enable_shared_from_this * \param[in] topic_name Name of the topic to subscribe to. * \param[in] subscription_options Options for the subscription. * \param[in] is_serialized is true if the message will be delivered still serialized + * \param[in] use_runtime_type_cb is true if the message will be taken serialized and then handled + * using dynamic type and dynamic data (type constructed at runtime) */ RCLCPP_PUBLIC SubscriptionBase( @@ -86,7 +88,12 @@ class SubscriptionBase : public std::enable_shared_from_this const rcl_subscription_options_t & subscription_options, const SubscriptionEventCallbacks & event_callbacks, bool use_default_callbacks, - bool is_serialized = false); + bool is_serialized = false, + bool use_runtime_type_cb = false, + bool use_take_runtime_type_message = false); + // TODO(methylDragon): If we don't need this, remove it, + // rclcpp::node_interfaces::NodeGraphInterface * node_graph = 0, + // rclcpp::node_interfaces::NodeServicesInterface * node_services = 0); /// Destructor. RCLCPP_PUBLIC @@ -535,6 +542,54 @@ class SubscriptionBase : public std::enable_shared_from_this rclcpp::ContentFilterOptions get_content_filter() const; + // RUNTIME TYPE ================================================================================== + // TODO(methylDragon): Reorder later + RCLCPP_PUBLIC + virtual + std::shared_ptr + get_dynamic_type() = 0; + + RCLCPP_PUBLIC + virtual + std::shared_ptr + get_dynamic_data() = 0; + + RCLCPP_PUBLIC + virtual + std::shared_ptr + get_serialization_support() = 0; + + RCLCPP_PUBLIC + virtual + void + handle_runtime_type_message( + const std::shared_ptr & ser, + const std::shared_ptr & dyn_data, + const rclcpp::MessageInfo & message_info + ) = 0; + + // TODO(methylDragon): + // RCLCPP_PUBLIC + // bool + // take_runtime_type_message(ser_dynamic_data_t * message_out, rclcpp::MessageInfo & message_info_out); + + /// Return if the subscription should use runtime type + /** + * This will cause the subscription to use the handle_runtime_type_message methods, which must be + * used with take_serialized or take_runtime_type. + * + * \return `true` if the subscription should use a runtime type callback, `false` otherwise + */ + RCLCPP_PUBLIC + bool + use_runtime_type_cb() const; + + RCLCPP_PUBLIC + bool + use_take_runtime_type_message() const; + // =============================================================================================== + + protected: template void @@ -565,6 +620,10 @@ class SubscriptionBase : public std::enable_shared_from_this rclcpp::node_interfaces::NodeBaseInterface * const node_base_; + // TODO(methylDragon): Remove if we don't need this + // rclcpp::node_interfaces::NodeGraphInterface * const node_graph_; + // rclcpp::node_interfaces::NodeServicesInterface * const node_services_; + std::shared_ptr node_handle_; std::shared_ptr subscription_handle_; std::shared_ptr intra_process_subscription_handle_; @@ -585,6 +644,8 @@ class SubscriptionBase : public std::enable_shared_from_this rosidl_message_type_support_t type_support_; bool is_serialized_; + bool use_runtime_type_cb_; + bool use_take_runtime_type_message_; std::atomic subscription_in_use_by_wait_set_{false}; std::atomic intra_process_subscription_waitable_in_use_by_wait_set_{false}; diff --git a/rclcpp/src/rclcpp/executor.cpp b/rclcpp/src/rclcpp/executor.cpp index 401beb0a73..b980a79d62 100644 --- a/rclcpp/src/rclcpp/executor.cpp +++ b/rclcpp/src/rclcpp/executor.cpp @@ -587,6 +587,52 @@ Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr subscription) rclcpp::MessageInfo message_info; message_info.get_rmw_message_info().from_intra_process = false; + // PROPOSED ====================================================================================== + // If a subscription is meant to use_runtime_type_cb, then it will use its serialization-specific + // dynamic data. + // + // Two cases: + // - Runtime type subscription using dynamic type stored in its own internal type support struct + // - Non-runtime type subscription with no stored dynamic type + // - Subscriptions of this type must be able to lookup the local message description to + // generate a dynamic type at runtime! + // - TODO(methylDragon): I won't be handling this case yet + // + // TODO(methylDragon): + // - use_runtime_type_cb (can use take_serialized or take_runtime_type) + // - take_runtime_type (MUST have use_runtime_type_cb true) + if (subscription->use_runtime_type_cb()) { + if (subscription->use_take_runtime_type_message()) { + // TODO(methylDragon) + throw rclcpp::exceptions::UnimplementedError("take_runtime_type_message is not implemented"); + } else { + std::shared_ptr serialized_msg = subscription->create_serialized_message(); + take_and_do_error_handling( + "taking a serialized message from topic", + subscription->get_topic_name(), + [&]() {return subscription->take_serialized(*serialized_msg.get(), message_info);}, + [&]() + { + std::shared_ptr ser = subscription->get_serialization_support(); + std::shared_ptr dyn_data = subscription->get_dynamic_data(); + + // NOTE(methylDragon): We might want to consider cloning the dynamic data here + + rcl_ret_t ret = rmw_serialized_to_dynamic_data( + &serialized_msg->get_rcl_serialized_message(), dyn_data.get()); + + if (ret != RMW_RET_OK) { + throw_from_rcl_error(ret, "Couldn't convert serialized message to dynamic data!"); + } + subscription->handle_runtime_type_message(ser, dyn_data, message_info); + } + ); + subscription->return_serialized_message(serialized_msg); + } + return; + } + // =============================================================================================== + if (subscription->is_serialized()) { // This is the case where a copy of the serialized message is taken from // the middleware via inter-process communication. diff --git a/rclcpp/src/rclcpp/generic_subscription.cpp b/rclcpp/src/rclcpp/generic_subscription.cpp index cc50955773..0209511951 100644 --- a/rclcpp/src/rclcpp/generic_subscription.cpp +++ b/rclcpp/src/rclcpp/generic_subscription.cpp @@ -43,8 +43,7 @@ void GenericSubscription::handle_message( "handle_message is not implemented for GenericSubscription"); } -void -GenericSubscription::handle_serialized_message( +void GenericSubscription::handle_serialized_message( const std::shared_ptr & message, const rclcpp::MessageInfo &) { @@ -72,4 +71,41 @@ void GenericSubscription::return_serialized_message( message.reset(); } + +// RUNTIME TYPE ================================================================================== +// TODO(methylDragon): Reorder later +std::shared_ptr +GenericSubscription::get_dynamic_type() +{ + throw rclcpp::exceptions::UnimplementedError( + "get_dynamic_type is not implemented for GenericSubscription"); +} + +std::shared_ptr +GenericSubscription::get_dynamic_data() +{ + throw rclcpp::exceptions::UnimplementedError( + "get_dynamic_data is not implemented for GenericSubscription"); +} + +std::shared_ptr +GenericSubscription::get_serialization_support() +{ + throw rclcpp::exceptions::UnimplementedError( + "get_serialization_support is not implemented for GenericSubscription"); +} + +void +GenericSubscription::handle_runtime_type_message( + const std::shared_ptr & ser, + const std::shared_ptr & dyn_data, + const rclcpp::MessageInfo & message_info) +{ + (void) ser; + (void) dyn_data; + (void) message_info; + throw rclcpp::exceptions::UnimplementedError( + "handle_runtime_type_message is not implemented for GenericSubscription"); +} + } // namespace rclcpp diff --git a/rclcpp/src/rclcpp/runtime_type_subscription.cpp b/rclcpp/src/rclcpp/runtime_type_subscription.cpp new file mode 100644 index 0000000000..9edfa5a0f1 --- /dev/null +++ b/rclcpp/src/rclcpp/runtime_type_subscription.cpp @@ -0,0 +1,117 @@ +// Copyright 2022 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "rclcpp/runtime_type_subscription.hpp" + +#include +#include + +#include "rcl/subscription.h" + +#include "rclcpp/exceptions.hpp" + +namespace rclcpp +{ + +std::shared_ptr RuntimeTypeSubscription::create_message() +{ + return create_serialized_message(); +} + +std::shared_ptr RuntimeTypeSubscription::create_serialized_message() +{ + return std::make_shared(0); +} + +void RuntimeTypeSubscription::handle_message( + std::shared_ptr &, const rclcpp::MessageInfo &) +{ + throw rclcpp::exceptions::UnimplementedError( + "handle_message is not implemented for RuntimeTypeSubscription"); +} + +void RuntimeTypeSubscription::handle_serialized_message( + const std::shared_ptr &, const rclcpp::MessageInfo &) +{ + throw rclcpp::exceptions::UnimplementedError( + "handle_serialized_message is not implemented for RuntimeTypeSubscription"); +} + +void RuntimeTypeSubscription::handle_loaned_message( + void *, const rclcpp::MessageInfo &) +{ + throw rclcpp::exceptions::UnimplementedError( + "handle_loaned_message is not implemented for RuntimeTypeSubscription"); +} + +void RuntimeTypeSubscription::return_message(std::shared_ptr & message) +{ + auto typed_message = std::static_pointer_cast(message); + return_serialized_message(typed_message); +} + +void RuntimeTypeSubscription::return_serialized_message( + std::shared_ptr & message) +{ + message.reset(); +} + + +// RUNTIME TYPE ==================================================================================== +// TODO(methylDragon): Re-order later +std::shared_ptr +RuntimeTypeSubscription::get_dynamic_type() +{ + auto ts_impl = (runtime_type_ts_impl_t *)(ts_.data); + + // no-op deleter because the lifetime is managed by the typesupport outside + return std::shared_ptr( + ts_impl->dynamic_type, [](ser_dynamic_type_t *){} + ); +}; + +// NOTE(methylDragon): Should we store a separate copy of dynamic data in the sub so it isn't tied +// to the typesupport instead? +// If that's the case, will there ever be a lifetime contention between a sub +// that manages the data and the callback/user usage of the data? +std::shared_ptr +RuntimeTypeSubscription::get_dynamic_data() +{ + auto ts_impl = (runtime_type_ts_impl_t *)(ts_.data); + + // no-op deleter because the lifetime is managed by the typesupport outside + return std::shared_ptr( + ts_impl->dynamic_data, [](ser_dynamic_data_t *){} + ); +}; + +std::shared_ptr RuntimeTypeSubscription::get_serialization_support() +{ + auto ts_impl = (runtime_type_ts_impl_t *)(ts_.data); + + // no-op deleter because the lifetime is managed by the typesupport outside + return std::shared_ptr( + ts_impl->ser, [](serialization_support_t *){} + ); +}; + +void RuntimeTypeSubscription::handle_runtime_type_message( + const std::shared_ptr & ser, + const std::shared_ptr & dyn_data, + const rclcpp::MessageInfo &) +{ + callback_(ser, dyn_data); +} + +} // namespace rclcpp diff --git a/rclcpp/src/rclcpp/subscription_base.cpp b/rclcpp/src/rclcpp/subscription_base.cpp index 0225747b3a..6ff196f269 100644 --- a/rclcpp/src/rclcpp/subscription_base.cpp +++ b/rclcpp/src/rclcpp/subscription_base.cpp @@ -41,7 +41,9 @@ SubscriptionBase::SubscriptionBase( const rcl_subscription_options_t & subscription_options, const SubscriptionEventCallbacks & event_callbacks, bool use_default_callbacks, - bool is_serialized) + bool is_serialized, + bool use_runtime_type_cb, + bool use_take_runtime_type_message) : node_base_(node_base), node_handle_(node_base_->get_shared_rcl_node_handle()), node_logger_(rclcpp::get_node_logger(node_handle_.get())), @@ -49,7 +51,9 @@ SubscriptionBase::SubscriptionBase( intra_process_subscription_id_(0), event_callbacks_(event_callbacks), type_support_(type_support_handle), - is_serialized_(is_serialized) + is_serialized_(is_serialized), + use_runtime_type_cb_(use_runtime_type_cb), + use_take_runtime_type_message_(use_take_runtime_type_message) { auto custom_deletor = [node_handle = this->node_handle_](rcl_subscription_t * rcl_subs) { @@ -478,3 +482,18 @@ SubscriptionBase::get_content_filter() const return ret_options; } + + +// RUNTIME TYPE ================================================================================== +// TODO(methylDragon): Reorder later +bool +SubscriptionBase::use_runtime_type_cb() const +{ + return use_runtime_type_cb_; +} + +bool +SubscriptionBase::use_take_runtime_type_message() const +{ + return use_take_runtime_type_message_; +} diff --git a/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp b/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp index ecfc89a6aa..b0664aff9b 100644 --- a/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp +++ b/rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp @@ -77,6 +77,13 @@ class TestSubscription : public rclcpp::SubscriptionBase const std::shared_ptr &, const rclcpp::MessageInfo &) override {} void return_message(std::shared_ptr &) override {} void return_serialized_message(std::shared_ptr &) override {} + + std::shared_ptr get_dynamic_type() override {return nullptr;} + std::shared_ptr get_dynamic_data() override {return nullptr;} + std::shared_ptr get_serialization_support() override {return nullptr;} + void handle_runtime_type_message( + const std::shared_ptr &, const std::shared_ptr &, + const rclcpp::MessageInfo &) override {} }; class TestNodeTopics : public ::testing::Test