Can I have the same node publishing and subscribing to different topics in ROS2 ?

asked 2018-05-17 06:22:09 -0500

aks gravatar image

updated 2018-05-17 12:18:14 -0500

Is there a sample code wherein 1 node is subscribing to a topic and another node is publishing on a different topic in ROS2 ?

    class HeatConduction1 : public rclcpp::Node
{
public:
  explicit HeatConduction1(const std::string & topic_subscriber, const std::string & topic_publisher)
  : Node("heatConduction1")
  {


    auto callback =
      [this](const std_msgs::msg::Float32::SharedPtr msg_) -> void
      {
        RCLCPP_INFO(this->get_logger(), "I heard: [%f]", msg_->data)
      };

    // Create a subscription to the 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.
    sub_ = create_subscription<std_msgs::msg::Float32>(topic_subscriber, callback);


    heatflow_12 = std::make_shared<std_msgs::msg::Float32>();

    auto publish_message = [this]()->void {

    heatflow_12->data = 99;
    RCLCPP_INFO(this->get_logger(), "I published: [%f]", heatflow_12->data)


        pub_->publish(heatflow_12);
    };

    rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
    custom_qos_profile.depth = 7;
    pub_ = this->create_publisher<std_msgs::msg::Float32>(topic_publisher, custom_qos_profile);

   }


private:
  rclcpp::Subscription<std_msgs::msg::Float32>::SharedPtr sub_;
  std::shared_ptr<std_msgs::msg::Float32> heatflow_12;
  rclcpp::Publisher<std_msgs::msg::Float32>::SharedPtr pub_;
  rclcpp::TimerBase::SharedPtr timer_;
};

int main(int argc, char * argv[])
{
  // Force flush of the stdout buffer.
  setvbuf(stdout, NULL, _IONBF, BUFSIZ);


  if (rcutils_cli_option_exist(argv, argv + argc, "-h")) {
    print_usage();
    return 0;
  }

   rclcpp::init(argc, argv);

  // Parse the command line options.
  auto topic1 = std::string("heatflow_source");
  auto topic2 = std::string("heatflow_12");

  if (rcutils_cli_option_exist(argv, argv + argc, "-t")) {
    topic1 = std::string(rcutils_cli_get_option(argv, argv + argc, "-t"));
  }

 if (rcutils_cli_option_exist(argv, argv + argc, "-t")) {
    topic2 = std::string(rcutils_cli_get_option(argv, argv + argc, "-t"));
  }

  // Create a node.
  auto node = std::make_shared<HeatConduction1>(topic1,topic2);

  rclcpp::spin(node);

  rclcpp::shutdown();
  return 0;
}
edit retag flag offensive close merge delete

Comments

I don't get your question. Are you looking at an example code that has:

a node publishing to a topic A and subscribing to a topic B a node publishing to a topic B and subscribing to a topic A ?

If yes, I don't think there is one. Have a look at https://github.com/ros2/ros2/wiki/Tut... ...

pokitoz gravatar image pokitoz  ( 2018-05-17 07:43:31 -0500 )edit

yes, something similar. For that i wrote this code wherein this nodeHeatConduction1 subscribes to a topic heatflow_source and shoul publish on the topic heatflow_12. But i am not sure if this is the right way.

aks gravatar image aks  ( 2018-05-17 08:04:28 -0500 )edit

You need to create a subscriber and a publisher inside your class. Which is what you are doing. The constructor will have to take 2 arguments: topic_publish and topic_subscribe: std::make_shared<heatconduction1>(topic_publish, topic_subscribe);

pokitoz gravatar image pokitoz  ( 2018-05-17 08:18:25 -0500 )edit

@pokitoz I tried to implement what you suggested. I have edited the question with the updated code but the problem is only the callback function is called in the constructor and not the publish_message. Any idea where am i going wrong ?

aks gravatar image aks  ( 2018-05-17 08:39:27 -0500 )edit

I don't see that you call publish_message anywhere... Perhaps you meant to call that in your subscriber callback?

ChuiV gravatar image ChuiV  ( 2021-10-06 09:09:05 -0500 )edit