Skip to content

Commit 65effc3

Browse files
committed
Revert "make type support helper supported for service (#2209)"
This reverts commit d9b2744.
1 parent d9b2744 commit 65effc3

File tree

5 files changed

+22
-154
lines changed

5 files changed

+22
-154
lines changed

rclcpp/include/rclcpp/generic_publisher.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -77,7 +77,7 @@ class GenericPublisher : public rclcpp::PublisherBase
7777
: rclcpp::PublisherBase(
7878
node_base,
7979
topic_name,
80-
*rclcpp::get_message_typesupport_handle(topic_type, "rosidl_typesupport_cpp", *ts_lib),
80+
*rclcpp::get_typesupport_handle(topic_type, "rosidl_typesupport_cpp", *ts_lib),
8181
options.template to_rcl_publisher_options<rclcpp::SerializedMessage>(qos),
8282
// NOTE(methylDragon): Passing these args separately is necessary for event binding
8383
options.event_callbacks,

rclcpp/include/rclcpp/generic_subscription.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,7 @@ class GenericSubscription : public rclcpp::SubscriptionBase
7979
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options)
8080
: SubscriptionBase(
8181
node_base,
82-
*rclcpp::get_message_typesupport_handle(topic_type, "rosidl_typesupport_cpp", *ts_lib),
82+
*rclcpp::get_typesupport_handle(topic_type, "rosidl_typesupport_cpp", *ts_lib),
8383
topic_name,
8484
options.to_rcl_subscription_options(qos),
8585
options.event_callbacks,

rclcpp/include/rclcpp/typesupport_helpers.hpp

Lines changed: 0 additions & 39 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,6 @@
2222

2323
#include "rcpputils/shared_library.hpp"
2424
#include "rosidl_runtime_cpp/message_type_support_decl.hpp"
25-
#include "rosidl_runtime_cpp/service_type_support_decl.hpp"
2625

2726
#include "rclcpp/visibility_control.hpp"
2827

@@ -41,56 +40,18 @@ get_typesupport_library(const std::string & type, const std::string & typesuppor
4140
/// Extract the type support handle from the library.
4241
/**
4342
* The library needs to match the topic type. The shared library must stay loaded for the lifetime of the result.
44-
*
45-
* \deprecated Use get_message_typesupport_handle() instead
46-
*
4743
* \param[in] type The topic type, e.g. "std_msgs/msg/String"
4844
* \param[in] typesupport_identifier Type support identifier, typically "rosidl_typesupport_cpp"
4945
* \param[in] library The shared type support library
5046
* \return A type support handle
5147
*/
52-
[[deprecated("Use `get_message_typesupport_handle` instead")]]
5348
RCLCPP_PUBLIC
5449
const rosidl_message_type_support_t *
5550
get_typesupport_handle(
5651
const std::string & type,
5752
const std::string & typesupport_identifier,
5853
rcpputils::SharedLibrary & library);
5954

60-
/// Extract the message type support handle from the library.
61-
/**
62-
* The library needs to match the topic type. The shared library must stay loaded for the lifetime of the result.
63-
*
64-
* \param[in] type The topic type, e.g. "std_msgs/msg/String"
65-
* \param[in] typesupport_identifier Type support identifier, typically "rosidl_typesupport_cpp"
66-
* \param[in] library The shared type support library
67-
* \throws std::runtime_error if the symbol of type not found in the library.
68-
* \return A message type support handle
69-
*/
70-
RCLCPP_PUBLIC
71-
const rosidl_message_type_support_t *
72-
get_message_typesupport_handle(
73-
const std::string & type,
74-
const std::string & typesupport_identifier,
75-
rcpputils::SharedLibrary & library);
76-
77-
/// Extract the service type support handle from the library.
78-
/**
79-
* The library needs to match the topic type. The shared library must stay loaded for the lifetime of the result.
80-
*
81-
* \param[in] type The service type, e.g. "std_srvs/srv/Empty"
82-
* \param[in] typesupport_identifier Type support identifier, typically "rosidl_typesupport_cpp"
83-
* \param[in] library The shared type support library
84-
* \throws std::runtime_error if the symbol of type not found in the library.
85-
* \return A service type support handle
86-
*/
87-
RCLCPP_PUBLIC
88-
const rosidl_service_type_support_t *
89-
get_service_typesupport_handle(
90-
const std::string & type,
91-
const std::string & typesupport_identifier,
92-
rcpputils::SharedLibrary & library);
93-
9455
} // namespace rclcpp
9556

9657
#endif // RCLCPP__TYPESUPPORT_HELPERS_HPP_

rclcpp/src/rclcpp/typesupport_helpers.cpp

Lines changed: 18 additions & 62 deletions
Original file line numberDiff line numberDiff line change
@@ -91,36 +91,40 @@ extract_type_identifier(const std::string & full_type)
9191
return std::make_tuple(package_name, middle_module, type_name);
9292
}
9393

94-
const void * get_typesupport_handle_impl(
94+
} // anonymous namespace
95+
96+
std::shared_ptr<rcpputils::SharedLibrary>
97+
get_typesupport_library(const std::string & type, const std::string & typesupport_identifier)
98+
{
99+
auto package_name = std::get<0>(extract_type_identifier(type));
100+
auto library_path = get_typesupport_library_path(package_name, typesupport_identifier);
101+
return std::make_shared<rcpputils::SharedLibrary>(library_path);
102+
}
103+
104+
const rosidl_message_type_support_t *
105+
get_typesupport_handle(
95106
const std::string & type,
96107
const std::string & typesupport_identifier,
97-
const std::string & typesupport_name,
98-
const std::string & symbol_part_name,
99-
const std::string & middle_module_additional,
100108
rcpputils::SharedLibrary & library)
101109
{
102110
std::string package_name;
103111
std::string middle_module;
104112
std::string type_name;
105113
std::tie(package_name, middle_module, type_name) = extract_type_identifier(type);
106114

107-
if (middle_module.empty()) {
108-
middle_module = middle_module_additional;
109-
}
110-
111-
auto mk_error = [&package_name, &type_name, &typesupport_name](auto reason) {
115+
auto mk_error = [&package_name, &type_name](auto reason) {
112116
std::stringstream rcutils_dynamic_loading_error;
113117
rcutils_dynamic_loading_error <<
114-
"Something went wrong loading the typesupport library for " <<
115-
typesupport_name << " type " << package_name <<
118+
"Something went wrong loading the typesupport library for message type " << package_name <<
116119
"/" << type_name << ". " << reason;
117120
return rcutils_dynamic_loading_error.str();
118121
};
119122

120123
try {
121-
std::string symbol_name = typesupport_identifier + symbol_part_name +
122-
package_name + "__" + middle_module + "__" + type_name;
123-
const void * (* get_ts)() = nullptr;
124+
std::string symbol_name = typesupport_identifier + "__get_message_type_support_handle__" +
125+
package_name + "__" + (middle_module.empty() ? "msg" : middle_module) + "__" + type_name;
126+
127+
const rosidl_message_type_support_t * (* get_ts)() = nullptr;
124128
// This will throw runtime_error if the symbol was not found.
125129
get_ts = reinterpret_cast<decltype(get_ts)>(library.get_symbol(symbol_name));
126130
return get_ts();
@@ -129,52 +133,4 @@ const void * get_typesupport_handle_impl(
129133
}
130134
}
131135

132-
} // anonymous namespace
133-
134-
std::shared_ptr<rcpputils::SharedLibrary>
135-
get_typesupport_library(const std::string & type, const std::string & typesupport_identifier)
136-
{
137-
auto package_name = std::get<0>(extract_type_identifier(type));
138-
auto library_path = get_typesupport_library_path(package_name, typesupport_identifier);
139-
return std::make_shared<rcpputils::SharedLibrary>(library_path);
140-
}
141-
142-
const rosidl_message_type_support_t * get_typesupport_handle(
143-
const std::string & type,
144-
const std::string & typesupport_identifier,
145-
rcpputils::SharedLibrary & library)
146-
{
147-
return get_message_typesupport_handle(type, typesupport_identifier, library);
148-
}
149-
150-
const rosidl_message_type_support_t * get_message_typesupport_handle(
151-
const std::string & type,
152-
const std::string & typesupport_identifier,
153-
rcpputils::SharedLibrary & library)
154-
{
155-
static const std::string typesupport_name = "message";
156-
static const std::string symbol_part_name = "__get_message_type_support_handle__";
157-
static const std::string middle_module_additional = "msg";
158-
159-
return static_cast<const rosidl_message_type_support_t *>(get_typesupport_handle_impl(
160-
type, typesupport_identifier, typesupport_name, symbol_part_name,
161-
middle_module_additional, library
162-
));
163-
}
164-
165-
const rosidl_service_type_support_t * get_service_typesupport_handle(
166-
const std::string & type,
167-
const std::string & typesupport_identifier,
168-
rcpputils::SharedLibrary & library)
169-
{
170-
static const std::string typesupport_name = "service";
171-
static const std::string symbol_part_name = "__get_service_type_support_handle__";
172-
static const std::string middle_module_additional = "srv";
173-
174-
return static_cast<const rosidl_service_type_support_t *>(get_typesupport_handle_impl(
175-
type, typesupport_identifier, typesupport_name, symbol_part_name,
176-
middle_module_additional, library
177-
));
178-
}
179-
180136
} // namespace rclcpp

rclcpp/test/rclcpp/test_typesupport_helpers.cpp

Lines changed: 2 additions & 51 deletions
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ TEST(TypesupportHelpersTest, returns_c_type_info_for_valid_legacy_library) {
5050
try {
5151
auto library = rclcpp::get_typesupport_library(
5252
"test_msgs/BasicTypes", "rosidl_typesupport_cpp");
53-
auto string_typesupport = rclcpp::get_message_typesupport_handle(
53+
auto string_typesupport = rclcpp::get_typesupport_handle(
5454
"test_msgs/BasicTypes", "rosidl_typesupport_cpp", *library);
5555

5656
EXPECT_THAT(
@@ -65,7 +65,7 @@ TEST(TypesupportHelpersTest, returns_c_type_info_for_valid_library) {
6565
try {
6666
auto library = rclcpp::get_typesupport_library(
6767
"test_msgs/msg/BasicTypes", "rosidl_typesupport_cpp");
68-
auto string_typesupport = rclcpp::get_message_typesupport_handle(
68+
auto string_typesupport = rclcpp::get_typesupport_handle(
6969
"test_msgs/msg/BasicTypes", "rosidl_typesupport_cpp", *library);
7070

7171
EXPECT_THAT(
@@ -75,52 +75,3 @@ TEST(TypesupportHelpersTest, returns_c_type_info_for_valid_library) {
7575
FAIL() << e.what();
7676
}
7777
}
78-
79-
TEST(TypesupportHelpersTest, returns_service_type_info_for_valid_legacy_library) {
80-
try {
81-
auto library = rclcpp::get_typesupport_library(
82-
"test_msgs/Empty", "rosidl_typesupport_cpp");
83-
auto empty_typesupport = rclcpp::get_service_typesupport_handle(
84-
"test_msgs/Empty", "rosidl_typesupport_cpp", *library);
85-
86-
EXPECT_THAT(
87-
std::string(empty_typesupport->typesupport_identifier),
88-
ContainsRegex("rosidl_typesupport"));
89-
} catch (const std::runtime_error & e) {
90-
FAIL() << e.what();
91-
}
92-
}
93-
94-
TEST(TypesupportHelpersTest, returns_service_type_info_for_valid_library) {
95-
try {
96-
auto library = rclcpp::get_typesupport_library(
97-
"test_msgs/srv/Empty", "rosidl_typesupport_cpp");
98-
auto empty_typesupport = rclcpp::get_service_typesupport_handle(
99-
"test_msgs/srv/Empty", "rosidl_typesupport_cpp", *library);
100-
101-
EXPECT_THAT(
102-
std::string(empty_typesupport->typesupport_identifier),
103-
ContainsRegex("rosidl_typesupport"));
104-
} catch (const std::runtime_error & e) {
105-
FAIL() << e.what();
106-
}
107-
}
108-
109-
TEST(TypesupportHelpersTest, test_throw_exception_with_invalid_type) {
110-
// message
111-
std::string invalid_type = "test_msgs/msg/InvalidType";
112-
auto library = rclcpp::get_typesupport_library(invalid_type, "rosidl_typesupport_cpp");
113-
EXPECT_THROW(
114-
rclcpp::get_message_typesupport_handle(invalid_type, "rosidl_typesupport_cpp", *library),
115-
std::runtime_error);
116-
EXPECT_THROW(
117-
rclcpp::get_service_typesupport_handle(invalid_type, "rosidl_typesupport_cpp", *library),
118-
std::runtime_error);
119-
120-
// service
121-
invalid_type = "test_msgs/srv/InvalidType";
122-
library = rclcpp::get_typesupport_library(invalid_type, "rosidl_typesupport_cpp");
123-
EXPECT_THROW(
124-
rclcpp::get_service_typesupport_handle(invalid_type, "rosidl_typesupport_cpp", *library),
125-
std::runtime_error);
126-
}

0 commit comments

Comments
 (0)