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

Can a subscriber and publisher co-exist in a single nodelet?

asked 2018-03-27 12:55:15 -0500

petermp gravatar image

updated 2018-03-28 02:17:07 -0500

gvdhoorn gravatar image

I have a need to implement a nodelet that subscribes for messages from a topic, process them and then publish to another topic.

Can this be done using a single nodelet?


Edit: I tried the below demo, but see only publishing msgs. Sub's callback are not invoked.

#include <chrono>
#include <iostream>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

using namespace std::chrono_literals;

namespace composition
{

// Create a Talker "component" that subclasses the generic rclcpp::Node base class.
// Components get built into shared libraries and as such do not write their own main functions.
// The process using the component's shared library will instantiate the class as a ROS node.
Peter::Peter()
: Node("peter"), count_(0)
{
  // Create a publisher of "std_mgs/String" messages on the "chatter" topic.
  pub_ = create_publisher<std_msgs::msg::String>("chatter");

  // Use a timer to schedule periodic message publishing.
  timer_ = create_wall_timer(1s, std::bind(&Peter::on_timer, this));

  // Create a callback function for when messages are received.
  // Variations of this function also exist using, for example, UniquePtr for zero-copy transport.
  auto callback =
    [this](const typename std_msgs::msg::String::SharedPtr msg) -> void
    {
      RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg->data.c_str())
      std::flush(std::cout);
    };

  // Create a subscription to the "chatter" topic which can be matched with one or more
  // compatible ROS publishers.
  // Note that not all publishers on the same topic with the same type will be compatible:
  // they must have compatible Quality of Service policies.
  auto sub_ = create_subscription<std_msgs::msg::String>("chatter", callback);
}

void Peter::on_timer()
{
  auto msg = std::make_shared<std_msgs::msg::String>();
  msg->data = "Peter is here: " + std::to_string(++count_);
  RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg->data.c_str())
  std::flush(std::cout);

  // Put the message into a queue to be processed by the middleware.
  // This call is non-blocking.
  pub_->publish(msg);
}

}  // namespace composition

#include "class_loader/class_loader_register_macro.h"

// Register the component with class_loader.
// This acts as a sort of entry point, allowing the component to be discoverable when its library
// is being loaded into a running process.
CLASS_LOADER_REGISTER_CLASS(composition::Peter, rclcpp::Node)
edit retag flag offensive close merge delete

Comments

I've removed my answer as I'd missed the ros2 tag. The use of the term nodelet made me think you were asking about the ROS1 concept.

Note: there are no 'nodelets' in ROS2, only nodes.

gvdhoorn gravatar image gvdhoorn  ( 2018-03-28 02:16:25 -0500 )edit

Thanks. I am new to the forum and apparently made some edit mistakes.

I am able to get the code working and confirm that we can do both publishing and subscribing in any order using a single nodelet (in dynamic load composition example).

Peter

petermp gravatar image petermp  ( 2018-03-28 12:14:42 -0500 )edit
1

What's missing here is the declaration of the class. I believe the bug is that pub_ is member of the class and therefore persists after the constructor, but the subscription sub_ is local to the constructor and is destroyed when it is finished. You must keep the sub_ to get callbacks.

William gravatar image William  ( 2018-03-28 18:43:43 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-03-27 17:11:09 -0500

marguedas gravatar image

You should be able to publish, subscribe, use services in composed nodes the same way you do with regular nodes. Unfortunately the code sample you provided is not enough to help you (and the formatting make it hard to read). How do you compose your nodes? how do you invoke them ?

If it helps, I pushed an example of Node that publishes and subscribes here The main is creating an executor and adding the node to it. To compose more nodes in that process you would need to add more node like it's done in the composition example

edit flag offensive delete link more

Question Tools

Stats

Asked: 2018-03-27 12:55:15 -0500

Seen: 681 times

Last updated: Mar 28 '18