Skip to content

Commit 32859cd

Browse files
committed
Remove RMW interfaces
Signed-off-by: methylDragon <[email protected]>
1 parent 30210a2 commit 32859cd

File tree

3 files changed

+14
-8
lines changed

3 files changed

+14
-8
lines changed

rclcpp/include/rclcpp/dynamic_subscription.hpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
#ifndef RCLCPP__DYNAMIC_SUBSCRIPTION_HPP_
1616
#define RCLCPP__DYNAMIC_SUBSCRIPTION_HPP_
1717

18+
#include <rosidl_dynamic_typesupport/identifier.h>
19+
1820
#include <functional>
1921
#include <memory>
2022
#include <string>
@@ -80,7 +82,7 @@ class DynamicSubscription : public rclcpp::SubscriptionBase
8082
}
8183

8284
if (type_support->get_rosidl_message_type_support()->typesupport_identifier !=
83-
rmw_get_dynamic_typesupport_identifier())
85+
rosidl_get_dynamic_typesupport_identifier())
8486
{
8587
throw std::runtime_error(
8688
"DynamicSubscription must use dynamic type introspection type support!");

rclcpp/include/rclcpp/dynamic_typesupport/dynamic_message_type_support.hpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef RCLCPP__DYNAMIC_TYPESUPPORT__DYNAMIC_MESSAGE_TYPE_SUPPORT_HPP_
1616
#define RCLCPP__DYNAMIC_TYPESUPPORT__DYNAMIC_MESSAGE_TYPE_SUPPORT_HPP_
1717

18+
#include <rosidl_dynamic_typesupport/dynamic_message_type_support_struct.h>
1819
#include <rosidl_dynamic_typesupport/types.h>
1920
#include <rosidl_runtime_c/message_type_support_struct.h>
2021
#include <rosidl_runtime_c/type_description/type_description__struct.h>
@@ -71,7 +72,8 @@ class DynamicMessageTypeSupport : public std::enable_shared_from_this<DynamicMes
7172

7273
/// From description, for provided serialization support
7374
/// Does NOT take ownership of the description (copies instead.)
74-
/// Constructs type support top-down (calling `rmw_dynamic_message_type_support_handle_create()`)
75+
/// Constructs type support top-down (calling
76+
/// `rosidl_dynamic_message_type_support_handle_create()`)
7577
RCLCPP_PUBLIC
7678
DynamicMessageTypeSupport(
7779
DynamicSerializationSupport::SharedPtr serialization_support,

rclcpp/src/rclcpp/dynamic_typesupport/dynamic_message_type_support.cpp

+8-6
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
#include <rosidl_dynamic_typesupport/identifier.h>
1516
#include <rosidl_dynamic_typesupport/types.h>
1617
#include <rosidl_runtime_c/message_type_support_struct.h>
1718
#include <rosidl_runtime_c/type_description_utils.h>
@@ -26,6 +27,7 @@
2627
#include "rcl/type_hash.h"
2728
#include "rcl/types.h"
2829
#include "rcutils/logging_macros.h"
30+
#include "rcutils/types/rcutils_ret.h"
2931
#include "rmw/dynamic_message_type_support.h"
3032

3133
#include "rclcpp/dynamic_typesupport/dynamic_message.hpp"
@@ -71,7 +73,7 @@ DynamicMessageTypeSupport::DynamicMessageTypeSupport(
7173
if (!ts->data) {
7274
throw std::runtime_error("could not init rosidl message type support impl");
7375
}
74-
if (ts->typesupport_identifier != rmw_get_dynamic_typesupport_identifier()) {
76+
if (ts->typesupport_identifier != rosidl_get_dynamic_typesupport_identifier()) {
7577
throw std::runtime_error("rosidl message type support is of the wrong type");
7678
}
7779

@@ -135,20 +137,19 @@ DynamicMessageTypeSupport::DynamicMessageTypeSupport(
135137
throw std::runtime_error("failed to get type hash");
136138
}
137139

138-
rmw_ret_t ret = rmw_dynamic_message_type_support_handle_create(
140+
rcutils_ret_t ret = rosidl_dynamic_message_type_support_handle_create(
139141
serialization_support->get_rosidl_serialization_support(),
140-
rmw_feature_supported(RMW_MIDDLEWARE_SUPPORTS_TYPE_DISCOVERY),
141142
type_hash.get(), // type_hash
142143
&description, // type_description
143144
nullptr, // type_description_sources (not implemented for dynamic types)
144145
&ts);
145-
if (ret != RMW_RET_OK || !ts) {
146+
if (ret != RCUTILS_RET_OK || !ts) {
146147
throw std::runtime_error("could not init rosidl message type support");
147148
}
148149
if (!ts->data) {
149150
throw std::runtime_error("could not init rosidl message type support impl");
150151
}
151-
if (ts->typesupport_identifier != rmw_get_dynamic_typesupport_identifier()) {
152+
if (ts->typesupport_identifier != rosidl_get_dynamic_typesupport_identifier()) {
152153
throw std::runtime_error("rosidl message type support is of the wrong type");
153154
}
154155

@@ -303,6 +304,7 @@ DynamicMessageTypeSupport::init_rosidl_message_type_support_(
303304
auto type_hash = std::make_unique<rosidl_type_hash_t>();
304305
rcutils_ret_t hash_ret = rcl_calculate_type_hash(
305306
// TODO(methylDragon): Swap this out with the conversion function when it is ready
307+
// from https://github.com/ros2/rcl/pull/1052
306308
reinterpret_cast<type_description_interfaces__msg__TypeDescription *>(description),
307309
type_hash.get());
308310
if (hash_ret != RCL_RET_OK || !type_hash) {
@@ -328,7 +330,7 @@ DynamicMessageTypeSupport::init_rosidl_message_type_support_(
328330
// are managed by the passed in SharedPtr wrapper classes. We just delete it.
329331
rosidl_message_type_support_.reset(
330332
new rosidl_message_type_support_t{
331-
rmw_get_dynamic_typesupport_identifier(), // typesupport_identifier
333+
rosidl_get_dynamic_typesupport_identifier(), // typesupport_identifier
332334
ts_impl, // data
333335
get_message_typesupport_handle_function, // func
334336
// get_type_hash_func

0 commit comments

Comments
 (0)