rclcpp  beta1
C++ ROS Client Library API
create_publisher.hpp
Go to the documentation of this file.
1 // Copyright 2016 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__CREATE_PUBLISHER_HPP_
16 #define RCLCPP__CREATE_PUBLISHER_HPP_
17 
18 #include <memory>
19 #include <string>
20 
23 #include "rmw/qos_profiles.h"
24 
25 namespace rclcpp
26 {
27 
28 template<typename MessageT, typename AllocatorT, typename PublisherT>
32  const std::string & topic_name,
33  const rmw_qos_profile_t & qos_profile,
34  bool use_intra_process_comms,
36 {
37  auto publisher_options = rcl_publisher_get_default_options();
38  publisher_options.qos = qos_profile;
39 
40  auto pub = node_topics->create_publisher(
41  topic_name,
42  rclcpp::create_publisher_factory<MessageT, AllocatorT, PublisherT>(allocator),
43  publisher_options,
44  use_intra_process_comms);
45  node_topics->add_publisher(pub);
46  return std::dynamic_pointer_cast<PublisherT>(pub);
47 }
48 
49 } // namespace rclcpp
50 
51 #endif // RCLCPP__CREATE_PUBLISHER_HPP_
Definition: allocator_common.hpp:24
virtual void add_publisher(rclcpp::publisher::PublisherBase::SharedPtr publisher)=0
virtual rclcpp::publisher::PublisherBase::SharedPtr create_publisher(const std::string &topic_name, const rclcpp::PublisherFactory &publisher_factory, rcl_publisher_options_t &publisher_options, bool use_intra_process)=0
Pure virtual interface class for the NodeTopics part of the Node API.
Definition: node_topics_interface.hpp:38
T dynamic_pointer_cast(T... args)
rcl_publisher_options_t rcl_publisher_get_default_options(void)
std::shared_ptr< PublisherT > create_publisher(rclcpp::node_interfaces::NodeTopicsInterface *node_topics, const std::string &topic_name, const rmw_qos_profile_t &qos_profile, bool use_intra_process_comms, std::shared_ptr< AllocatorT > allocator)
Definition: create_publisher.hpp:30