Skip to content

Commit

Permalink
Enable TransformListener node-based constructor in Intra-process enab…
Browse files Browse the repository at this point in the history
…led components
  • Loading branch information
roncapat committed Mar 18, 2023
1 parent d449919 commit 1ce0644
Showing 1 changed file with 2 additions and 0 deletions.
2 changes: 2 additions & 0 deletions tf2_ros/include/tf2_ros/transform_listener.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,7 @@ get_default_transform_listener_sub_options()
rclcpp::QosPolicyKind::Durability,
rclcpp::QosPolicyKind::History,
rclcpp::QosPolicyKind::Reliability};
options.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable;
return options;
}

Expand All @@ -73,6 +74,7 @@ get_default_transform_listener_static_sub_options()
rclcpp::QosPolicyKind::Depth,
rclcpp::QosPolicyKind::History,
rclcpp::QosPolicyKind::Reliability};
options.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable;
return options;
}
} // namespace detail
Expand Down

0 comments on commit 1ce0644

Please sign in to comment.