From 6dfb3e727d43870787f174f90d2c3593a7518ee6 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Fri, 15 Dec 2023 16:57:53 -0300 Subject: [PATCH] Revert "make type support helper supported for service (#2209)" This reverts commit d9b2744057b8fd230f2c71c739fcdf7e27219d85. Signed-off-by: Jorge Perez --- rclcpp/include/rclcpp/generic_publisher.hpp | 2 +- .../include/rclcpp/generic_subscription.hpp | 2 +- rclcpp/include/rclcpp/typesupport_helpers.hpp | 39 --------- rclcpp/src/rclcpp/typesupport_helpers.cpp | 80 +++++-------------- .../test/rclcpp/test_typesupport_helpers.cpp | 53 +----------- 5 files changed, 22 insertions(+), 154 deletions(-) diff --git a/rclcpp/include/rclcpp/generic_publisher.hpp b/rclcpp/include/rclcpp/generic_publisher.hpp index 292e6900d3..7cd2d8bc39 100644 --- a/rclcpp/include/rclcpp/generic_publisher.hpp +++ b/rclcpp/include/rclcpp/generic_publisher.hpp @@ -77,7 +77,7 @@ class GenericPublisher : public rclcpp::PublisherBase : rclcpp::PublisherBase( node_base, topic_name, - *rclcpp::get_message_typesupport_handle(topic_type, "rosidl_typesupport_cpp", *ts_lib), + *rclcpp::get_typesupport_handle(topic_type, "rosidl_typesupport_cpp", *ts_lib), options.template to_rcl_publisher_options(qos), // NOTE(methylDragon): Passing these args separately is necessary for event binding options.event_callbacks, diff --git a/rclcpp/include/rclcpp/generic_subscription.hpp b/rclcpp/include/rclcpp/generic_subscription.hpp index dfbae0467b..975a9d0d0d 100644 --- a/rclcpp/include/rclcpp/generic_subscription.hpp +++ b/rclcpp/include/rclcpp/generic_subscription.hpp @@ -79,7 +79,7 @@ class GenericSubscription : public rclcpp::SubscriptionBase const rclcpp::SubscriptionOptionsWithAllocator & options) : SubscriptionBase( node_base, - *rclcpp::get_message_typesupport_handle(topic_type, "rosidl_typesupport_cpp", *ts_lib), + *rclcpp::get_typesupport_handle(topic_type, "rosidl_typesupport_cpp", *ts_lib), topic_name, options.to_rcl_subscription_options(qos), options.event_callbacks, diff --git a/rclcpp/include/rclcpp/typesupport_helpers.hpp b/rclcpp/include/rclcpp/typesupport_helpers.hpp index c93b318440..2fad84cf3b 100644 --- a/rclcpp/include/rclcpp/typesupport_helpers.hpp +++ b/rclcpp/include/rclcpp/typesupport_helpers.hpp @@ -22,7 +22,6 @@ #include "rcpputils/shared_library.hpp" #include "rosidl_runtime_cpp/message_type_support_decl.hpp" -#include "rosidl_runtime_cpp/service_type_support_decl.hpp" #include "rclcpp/visibility_control.hpp" @@ -41,15 +40,11 @@ get_typesupport_library(const std::string & type, const std::string & typesuppor /// Extract the type support handle from the library. /** * The library needs to match the topic type. The shared library must stay loaded for the lifetime of the result. - * - * \deprecated Use get_message_typesupport_handle() instead - * * \param[in] type The topic type, e.g. "std_msgs/msg/String" * \param[in] typesupport_identifier Type support identifier, typically "rosidl_typesupport_cpp" * \param[in] library The shared type support library * \return A type support handle */ -[[deprecated("Use `get_message_typesupport_handle` instead")]] RCLCPP_PUBLIC const rosidl_message_type_support_t * get_typesupport_handle( @@ -57,40 +52,6 @@ get_typesupport_handle( const std::string & typesupport_identifier, rcpputils::SharedLibrary & library); -/// Extract the message type support handle from the library. -/** - * The library needs to match the topic type. The shared library must stay loaded for the lifetime of the result. - * - * \param[in] type The topic type, e.g. "std_msgs/msg/String" - * \param[in] typesupport_identifier Type support identifier, typically "rosidl_typesupport_cpp" - * \param[in] library The shared type support library - * \throws std::runtime_error if the symbol of type not found in the library. - * \return A message type support handle - */ -RCLCPP_PUBLIC -const rosidl_message_type_support_t * -get_message_typesupport_handle( - const std::string & type, - const std::string & typesupport_identifier, - rcpputils::SharedLibrary & library); - -/// Extract the service type support handle from the library. -/** - * The library needs to match the topic type. The shared library must stay loaded for the lifetime of the result. - * - * \param[in] type The service type, e.g. "std_srvs/srv/Empty" - * \param[in] typesupport_identifier Type support identifier, typically "rosidl_typesupport_cpp" - * \param[in] library The shared type support library - * \throws std::runtime_error if the symbol of type not found in the library. - * \return A service type support handle - */ -RCLCPP_PUBLIC -const rosidl_service_type_support_t * -get_service_typesupport_handle( - const std::string & type, - const std::string & typesupport_identifier, - rcpputils::SharedLibrary & library); - } // namespace rclcpp #endif // RCLCPP__TYPESUPPORT_HELPERS_HPP_ diff --git a/rclcpp/src/rclcpp/typesupport_helpers.cpp b/rclcpp/src/rclcpp/typesupport_helpers.cpp index 04dd8c4c9f..7286c35baa 100644 --- a/rclcpp/src/rclcpp/typesupport_helpers.cpp +++ b/rclcpp/src/rclcpp/typesupport_helpers.cpp @@ -91,12 +91,20 @@ extract_type_identifier(const std::string & full_type) return std::make_tuple(package_name, middle_module, type_name); } -const void * get_typesupport_handle_impl( +} // anonymous namespace + +std::shared_ptr +get_typesupport_library(const std::string & type, const std::string & typesupport_identifier) +{ + auto package_name = std::get<0>(extract_type_identifier(type)); + auto library_path = get_typesupport_library_path(package_name, typesupport_identifier); + return std::make_shared(library_path); +} + +const rosidl_message_type_support_t * +get_typesupport_handle( const std::string & type, const std::string & typesupport_identifier, - const std::string & typesupport_name, - const std::string & symbol_part_name, - const std::string & middle_module_additional, rcpputils::SharedLibrary & library) { std::string package_name; @@ -104,23 +112,19 @@ const void * get_typesupport_handle_impl( std::string type_name; std::tie(package_name, middle_module, type_name) = extract_type_identifier(type); - if (middle_module.empty()) { - middle_module = middle_module_additional; - } - - auto mk_error = [&package_name, &type_name, &typesupport_name](auto reason) { + auto mk_error = [&package_name, &type_name](auto reason) { std::stringstream rcutils_dynamic_loading_error; rcutils_dynamic_loading_error << - "Something went wrong loading the typesupport library for " << - typesupport_name << " type " << package_name << + "Something went wrong loading the typesupport library for message type " << package_name << "/" << type_name << ". " << reason; return rcutils_dynamic_loading_error.str(); }; try { - std::string symbol_name = typesupport_identifier + symbol_part_name + - package_name + "__" + middle_module + "__" + type_name; - const void * (* get_ts)() = nullptr; + std::string symbol_name = typesupport_identifier + "__get_message_type_support_handle__" + + package_name + "__" + (middle_module.empty() ? "msg" : middle_module) + "__" + type_name; + + const rosidl_message_type_support_t * (* get_ts)() = nullptr; // This will throw runtime_error if the symbol was not found. get_ts = reinterpret_cast(library.get_symbol(symbol_name)); return get_ts(); @@ -129,52 +133,4 @@ const void * get_typesupport_handle_impl( } } -} // anonymous namespace - -std::shared_ptr -get_typesupport_library(const std::string & type, const std::string & typesupport_identifier) -{ - auto package_name = std::get<0>(extract_type_identifier(type)); - auto library_path = get_typesupport_library_path(package_name, typesupport_identifier); - return std::make_shared(library_path); -} - -const rosidl_message_type_support_t * get_typesupport_handle( - const std::string & type, - const std::string & typesupport_identifier, - rcpputils::SharedLibrary & library) -{ - return get_message_typesupport_handle(type, typesupport_identifier, library); -} - -const rosidl_message_type_support_t * get_message_typesupport_handle( - const std::string & type, - const std::string & typesupport_identifier, - rcpputils::SharedLibrary & library) -{ - static const std::string typesupport_name = "message"; - static const std::string symbol_part_name = "__get_message_type_support_handle__"; - static const std::string middle_module_additional = "msg"; - - return static_cast(get_typesupport_handle_impl( - type, typesupport_identifier, typesupport_name, symbol_part_name, - middle_module_additional, library - )); -} - -const rosidl_service_type_support_t * get_service_typesupport_handle( - const std::string & type, - const std::string & typesupport_identifier, - rcpputils::SharedLibrary & library) -{ - static const std::string typesupport_name = "service"; - static const std::string symbol_part_name = "__get_service_type_support_handle__"; - static const std::string middle_module_additional = "srv"; - - return static_cast(get_typesupport_handle_impl( - type, typesupport_identifier, typesupport_name, symbol_part_name, - middle_module_additional, library - )); -} - } // namespace rclcpp diff --git a/rclcpp/test/rclcpp/test_typesupport_helpers.cpp b/rclcpp/test/rclcpp/test_typesupport_helpers.cpp index 2117b89455..8cdcfc19c0 100644 --- a/rclcpp/test/rclcpp/test_typesupport_helpers.cpp +++ b/rclcpp/test/rclcpp/test_typesupport_helpers.cpp @@ -50,7 +50,7 @@ TEST(TypesupportHelpersTest, returns_c_type_info_for_valid_legacy_library) { try { auto library = rclcpp::get_typesupport_library( "test_msgs/BasicTypes", "rosidl_typesupport_cpp"); - auto string_typesupport = rclcpp::get_message_typesupport_handle( + auto string_typesupport = rclcpp::get_typesupport_handle( "test_msgs/BasicTypes", "rosidl_typesupport_cpp", *library); EXPECT_THAT( @@ -65,7 +65,7 @@ TEST(TypesupportHelpersTest, returns_c_type_info_for_valid_library) { try { auto library = rclcpp::get_typesupport_library( "test_msgs/msg/BasicTypes", "rosidl_typesupport_cpp"); - auto string_typesupport = rclcpp::get_message_typesupport_handle( + auto string_typesupport = rclcpp::get_typesupport_handle( "test_msgs/msg/BasicTypes", "rosidl_typesupport_cpp", *library); EXPECT_THAT( @@ -75,52 +75,3 @@ TEST(TypesupportHelpersTest, returns_c_type_info_for_valid_library) { FAIL() << e.what(); } } - -TEST(TypesupportHelpersTest, returns_service_type_info_for_valid_legacy_library) { - try { - auto library = rclcpp::get_typesupport_library( - "test_msgs/Empty", "rosidl_typesupport_cpp"); - auto empty_typesupport = rclcpp::get_service_typesupport_handle( - "test_msgs/Empty", "rosidl_typesupport_cpp", *library); - - EXPECT_THAT( - std::string(empty_typesupport->typesupport_identifier), - ContainsRegex("rosidl_typesupport")); - } catch (const std::runtime_error & e) { - FAIL() << e.what(); - } -} - -TEST(TypesupportHelpersTest, returns_service_type_info_for_valid_library) { - try { - auto library = rclcpp::get_typesupport_library( - "test_msgs/srv/Empty", "rosidl_typesupport_cpp"); - auto empty_typesupport = rclcpp::get_service_typesupport_handle( - "test_msgs/srv/Empty", "rosidl_typesupport_cpp", *library); - - EXPECT_THAT( - std::string(empty_typesupport->typesupport_identifier), - ContainsRegex("rosidl_typesupport")); - } catch (const std::runtime_error & e) { - FAIL() << e.what(); - } -} - -TEST(TypesupportHelpersTest, test_throw_exception_with_invalid_type) { - // message - std::string invalid_type = "test_msgs/msg/InvalidType"; - auto library = rclcpp::get_typesupport_library(invalid_type, "rosidl_typesupport_cpp"); - EXPECT_THROW( - rclcpp::get_message_typesupport_handle(invalid_type, "rosidl_typesupport_cpp", *library), - std::runtime_error); - EXPECT_THROW( - rclcpp::get_service_typesupport_handle(invalid_type, "rosidl_typesupport_cpp", *library), - std::runtime_error); - - // service - invalid_type = "test_msgs/srv/InvalidType"; - library = rclcpp::get_typesupport_library(invalid_type, "rosidl_typesupport_cpp"); - EXPECT_THROW( - rclcpp::get_service_typesupport_handle(invalid_type, "rosidl_typesupport_cpp", *library), - std::runtime_error); -}