15 #ifndef RCLCPP__CREATE_PUBLISHER_HPP_
16 #define RCLCPP__CREATE_PUBLISHER_HPP_
43 typename NodeParametersT,
47 NodeParametersT & node_parameters,
48 NodeTopicsT & node_topics,
57 const rclcpp::QoS & actual_qos = options.qos_overriding_options.get_policy_kinds().size() ?
59 options.qos_overriding_options, node_parameters,
60 node_topics_interface->resolve_topic_name(topic_name),
65 auto pub = node_topics_interface->create_publisher(
67 rclcpp::create_publisher_factory<MessageT, AllocatorT, PublisherT>(options),
72 node_topics_interface->add_publisher(pub, options.callback_group);
74 return std::dynamic_pointer_cast<PublisherT>(pub);
103 return detail::create_publisher<MessageT, AllocatorT, PublisherT>(
104 node, node, topic_name, qos, options);
114 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters,
115 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr & node_topics,
123 return detail::create_publisher<MessageT, AllocatorT, PublisherT>(
124 node_parameters, node_topics, topic_name, qos, options);
129 #endif // RCLCPP__CREATE_PUBLISHER_HPP_