Template Function rclcpp::create_publisher(NodeT&&, const std::string&, const rclcpp::QoS&, const rclcpp::PublisherOptionsWithAllocator<AllocatorT>&)

Function Documentation

template<typename MessageT, typename AllocatorT = std::allocator<void>, typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>, typename NodeT>
std::shared_ptr<PublisherT> rclcpp::create_publisher(NodeT &&node, const std::string &topic_name, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator<AllocatorT> &options = (rclcpp::PublisherOptionsWithAllocator<AllocatorT>()))

Create and return a publisher of the given MessageT type.

The NodeT type only needs to have a method called get_node_topics_interface() which returns a shared_ptr to a NodeTopicsInterface.

In case options.qos_overriding_options is enabling qos parameter overrides, NodeT must also have a method called get_node_parameters_interface() which returns a shared_ptr to a NodeParametersInterface.