Skip to content

Commit

Permalink
Use dynamic typesupport identifier getter
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed Apr 4, 2023
1 parent ca17caf commit 2217287
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 4 deletions.
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/dynamic_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ class DynamicSubscription : public rclcpp::SubscriptionBase
}

if (type_support->get_rosidl_message_type_support()->typesupport_identifier !=
rmw_dynamic_typesupport_c__identifier)
rmw_get_dynamic_typesupport_identifier())
{
throw std::runtime_error(
"DynamicSubscription must use dynamic type introspection type support!");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ DynamicMessageTypeSupport::DynamicMessageTypeSupport(
if (!ts->data) {
throw std::runtime_error("could not init rosidl message type support impl");
}
if (ts->typesupport_identifier != rmw_dynamic_typesupport_c__identifier) {
if (ts->typesupport_identifier != rmw_get_dynamic_typesupport_identifier()) {
throw std::runtime_error("rosidl message type support is of the wrong type");
}

Expand Down Expand Up @@ -132,7 +132,7 @@ DynamicMessageTypeSupport::DynamicMessageTypeSupport(
if (!ts->data) {
throw std::runtime_error("could not init rosidl message type support impl");
}
if (ts->typesupport_identifier != rmw_dynamic_typesupport_c__identifier) {
if (ts->typesupport_identifier != rmw_get_dynamic_typesupport_identifier()) {
throw std::runtime_error("rosidl message type support is of the wrong type");
}

Expand Down Expand Up @@ -316,7 +316,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_dynamic_typesupport_c__identifier, // typesupport_identifier
rmw_get_dynamic_typesupport_identifier(), // typesupport_identifier
ts_impl, // data
get_message_typesupport_handle_function, // func
// get_type_hash_func
Expand Down

0 comments on commit 2217287

Please sign in to comment.