generic_publisher.h
Go to the documentation of this file.
1 // Copyright 2018, Bosch Software Innovations GmbH.
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 GENERIC_PUBLISHER_H
16 #define GENERIC_PUBLISHER_H
17 
18 #include <memory>
19 #include <string>
20 #include <rclcpp/rclcpp.hpp>
21 
22 class GenericPublisher : public rclcpp::PublisherBase
23 {
24 public:
25  GenericPublisher(rclcpp::node_interfaces::NodeBaseInterface* node_base,
26  const std::string& topic_name,
27  const rosidl_message_type_support_t& type_support)
28  : rclcpp::PublisherBase(node_base, topic_name, type_support, rcl_publisher_get_default_options())
29  {
30  }
31 
32  virtual ~GenericPublisher() = default;
33 
34  void publish(std::shared_ptr<rmw_serialized_message_t> message)
35  {
36  auto return_code = rcl_publish_serialized_message(get_publisher_handle().get(), message.get(), NULL);
37 
38  if (return_code != RCL_RET_OK)
39  {
40  rclcpp::exceptions::throw_from_rcl_error(return_code, "failed to publish serialized message");
41  }
42  }
43 
44  static std::shared_ptr<GenericPublisher> create(rclcpp::Node& node,
45  const std::string& topic_name,
46  const std::string& topic_type)
47  {
48 
49  auto library = std::move(rosbag2_cpp::get_typesupport_library(topic_type, "rosidl_typesupport_cpp"));
50  auto type_support = rosbag2_cpp::get_typesupport_handle(topic_type, "rosidl_typesupport_cpp", library);
51 
52 
53  return std::make_shared<GenericPublisher>(node.get_node_base_interface().get(), topic_name, *type_support);
54  }
55 };
56 
57 #endif // GENERIC_PUBLISHER_H
virtual ~GenericPublisher()=default
void publish(std::shared_ptr< rmw_serialized_message_t > message)
GenericPublisher(rclcpp::node_interfaces::NodeBaseInterface *node_base, const std::string &topic_name, const rosidl_message_type_support_t &type_support)
static std::shared_ptr< GenericPublisher > create(rclcpp::Node &node, const std::string &topic_name, const std::string &topic_type)


plotjuggler_ros
Author(s): Davide Faconti
autogenerated on Fri Jun 23 2023 02:28:03