diff --git a/rclcpp/include/rclcpp/dynamic_subscription.hpp b/rclcpp/include/rclcpp/dynamic_subscription.hpp index 34b05e9050..07f6cb90ef 100644 --- a/rclcpp/include/rclcpp/dynamic_subscription.hpp +++ b/rclcpp/include/rclcpp/dynamic_subscription.hpp @@ -15,6 +15,8 @@ #ifndef RCLCPP__DYNAMIC_SUBSCRIPTION_HPP_ #define RCLCPP__DYNAMIC_SUBSCRIPTION_HPP_ +#include + #include #include #include @@ -80,7 +82,7 @@ class DynamicSubscription : public rclcpp::SubscriptionBase } if (type_support->get_rosidl_message_type_support()->typesupport_identifier != - rmw_get_dynamic_typesupport_identifier()) + rosidl_get_dynamic_typesupport_identifier()) { throw std::runtime_error( "DynamicSubscription must use dynamic type introspection type support!"); diff --git a/rclcpp/include/rclcpp/dynamic_typesupport/dynamic_message_type_support.hpp b/rclcpp/include/rclcpp/dynamic_typesupport/dynamic_message_type_support.hpp index 27cfdf43c7..ea8764fa29 100644 --- a/rclcpp/include/rclcpp/dynamic_typesupport/dynamic_message_type_support.hpp +++ b/rclcpp/include/rclcpp/dynamic_typesupport/dynamic_message_type_support.hpp @@ -15,6 +15,7 @@ #ifndef RCLCPP__DYNAMIC_TYPESUPPORT__DYNAMIC_MESSAGE_TYPE_SUPPORT_HPP_ #define RCLCPP__DYNAMIC_TYPESUPPORT__DYNAMIC_MESSAGE_TYPE_SUPPORT_HPP_ +#include #include #include #include @@ -71,7 +72,8 @@ class DynamicMessageTypeSupport : public std::enable_shared_from_this #include #include #include @@ -26,6 +27,7 @@ #include "rcl/type_hash.h" #include "rcl/types.h" #include "rcutils/logging_macros.h" +#include "rcutils/types/rcutils_ret.h" #include "rmw/dynamic_message_type_support.h" #include "rclcpp/dynamic_typesupport/dynamic_message.hpp" @@ -71,7 +73,7 @@ DynamicMessageTypeSupport::DynamicMessageTypeSupport( if (!ts->data) { throw std::runtime_error("could not init rosidl message type support impl"); } - if (ts->typesupport_identifier != rmw_get_dynamic_typesupport_identifier()) { + if (ts->typesupport_identifier != rosidl_get_dynamic_typesupport_identifier()) { throw std::runtime_error("rosidl message type support is of the wrong type"); } @@ -135,20 +137,19 @@ DynamicMessageTypeSupport::DynamicMessageTypeSupport( throw std::runtime_error("failed to get type hash"); } - rmw_ret_t ret = rmw_dynamic_message_type_support_handle_create( + rcutils_ret_t ret = rosidl_dynamic_message_type_support_handle_create( serialization_support->get_rosidl_serialization_support(), - rmw_feature_supported(RMW_MIDDLEWARE_SUPPORTS_TYPE_DISCOVERY), type_hash.get(), // type_hash &description, // type_description nullptr, // type_description_sources (not implemented for dynamic types) &ts); - if (ret != RMW_RET_OK || !ts) { + if (ret != RCUTILS_RET_OK || !ts) { throw std::runtime_error("could not init rosidl message type support"); } if (!ts->data) { throw std::runtime_error("could not init rosidl message type support impl"); } - if (ts->typesupport_identifier != rmw_get_dynamic_typesupport_identifier()) { + if (ts->typesupport_identifier != rosidl_get_dynamic_typesupport_identifier()) { throw std::runtime_error("rosidl message type support is of the wrong type"); } @@ -303,6 +304,7 @@ DynamicMessageTypeSupport::init_rosidl_message_type_support_( auto type_hash = std::make_unique(); rcutils_ret_t hash_ret = rcl_calculate_type_hash( // TODO(methylDragon): Swap this out with the conversion function when it is ready + // from https://github.com/ros2/rcl/pull/1052 reinterpret_cast(description), type_hash.get()); if (hash_ret != RCL_RET_OK || !type_hash) { @@ -328,7 +330,7 @@ DynamicMessageTypeSupport::init_rosidl_message_type_support_( // are managed by the passed in SharedPtr wrapper classes. We just delete it. rosidl_message_type_support_.reset( new rosidl_message_type_support_t{ - rmw_get_dynamic_typesupport_identifier(), // typesupport_identifier + rosidl_get_dynamic_typesupport_identifier(), // typesupport_identifier ts_impl, // data get_message_typesupport_handle_function, // func // get_type_hash_func