ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

I have not fully tested this (for bugs or performance), but I believe I have a working solution. In the Subscriber class of message_filters (subscriber.h), I have added a subscribezc method (below) that is exactly the same as the standard method but subscribes using a unique_ptr. I am getting the same pointer address for the message as it moves through the nodes (all running in a component container). I just did another test using the regular subscribe function, however and had the same result. I'm using Foxy on Ubuntu 20.04 installed from APT and I'm not sure if ROS was updated to use zero copy even in cases where not subscribed to a unique_ptr.

  void subscribezc(rclcpp::Node * node, const std::string& topic, const rmw_qos_profile_t qos = rmw_qos_profile_default)
  {
    unsubscribe();

    if (!topic.empty())
    {
      topic_ = topic;
      rclcpp::QoS rclcpp_qos(rclcpp::QoSInitialization::from_rmw(qos));
      rclcpp_qos.get_rmw_qos_profile() = qos;
      qos_ = qos;
      sub_ = node->create_subscription<M>(topic, rclcpp_qos,
               [this, node](std::unique_ptr<M> msg) {
                 RCLCPP_INFO(node->get_logger(), "Got UP Callback %x", msg.get());
                 this->cb(EventType(std::move(msg)));
               });

      node_raw_ = node;
    }
  }