How to subscribe once?

Hi,

I just want to subscribe once to get data then do not want to subscribe anymore.
But after that, I want to continue to subscribe once then stopping again and again

I see I can use subsciber.unregister() but it will create and destroy many times? I worried after many times, my program will have a lot of trash? I do not have experience when run the program for a long time. Could you share experience for this case?

Thanks

Why don’t just try it and find out? That’s the best way to learn.

If you run into any problems let us know.

I do not have the hardware to test now. It would be great if you can share your experience with me.
Or could you share how to monitor trash from a program in Linux?

Hi @NguyenDuyDuc,
You can create a Rosject in using theconstruct website and give it a try. Even if you don’t have the hardware, you should be able to test it like that. I don’t know about your specific use case.

Hi,

I rather use detroy_subscription() method. This is in Node class.

I think, I have used it once, but not in production just for learning.
It worked, as I remember. Unfortunately, I lost the source.
I do not know how does it work when you are doing this in a callback for the subscription.

Péter

As I suspected, destroy_subscription() did not work for me from the callback.
So I created a timer and destroyed the subscription from a timer. Very poor design.
Usually, when a framework does not allow me to do something with clean code, that means,
I try to do something against the framework (so it is discouraged) or I do it totally wrong or the framework needs a fix.

I used the code from here:
https://docs.ros.org/en/iron/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Py-Publisher-And-Subscriber.html

And here is my listener:

import rclpy
from rclpy.node import Node

from std_msgs.msg import String


class MinimalSubscriber(Node):

    def __init__(self):
        super().__init__('minimal_subscriber')
        self.subscription_is_active = False
        self.got_message = False
        self.timer = self.create_timer(1.0, self.timer_callback)

    def timer_callback(self):
        if self.got_message:
            self.unsubscribe()
        if not self.subscription_is_active:
            self.subscribe()
    
    def subscribe(self):
        if (self.subscription_is_active):
            return
        self.got_message = False
        self.subscription_is_active = True
        self.subscription = self.create_subscription(
            String,
            'topic',
            self.listener_callback,
            1
        )
        self.get_logger().info('Subscription done')

    def unsubscribe(self):
        if not self.subscription_is_active:
            return
        
        destroyed = self.destroy_subscription(self.subscription)
        if destroyed:
            self.subscription_is_active = False
            self.get_logger().info('subscription was destroyed')
        else:
            self.get_logger().info('subscription was NOT destroyed')

    def listener_callback(self, msg):
        if self.got_message:
            return

        self.got_message = True
        self.get_logger().info('I heard: "%s"' % msg.data)



def main(args=None):
    rclpy.init(args=args)

    minimal_subscriber = MinimalSubscriber()

    rclpy.spin(minimal_subscriber)

    # Destroy the node explicitly
    # (optional - otherwise it will be done automatically
    # when the garbage collector destroys the node object)
    minimal_subscriber.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

Warning: This design is very poor and use it only with single thread. Not for production. Only for demonstration.

The output:

[INFO] [1703876495.741187384] [minimal_subscriber]: Subscription done
[INFO] [1703876495.759448894] [minimal_subscriber]: I heard: "Hello World: 16"
[INFO] [1703876496.727071450] [minimal_subscriber]: subscription was destroyed
[INFO] [1703876496.728520571] [minimal_subscriber]: Subscription done
[INFO] [1703876496.759581639] [minimal_subscriber]: I heard: "Hello World: 18"
[INFO] [1703876497.727256846] [minimal_subscriber]: subscription was destroyed
[INFO] [1703876497.728903835] [minimal_subscriber]: Subscription done
[INFO] [1703876497.761160166] [minimal_subscriber]: I heard: "Hello World: 20"
[INFO] [1703876498.727452261] [minimal_subscriber]: subscription was destroyed
[INFO] [1703876498.729492199] [minimal_subscriber]: Subscription done
[INFO] [1703876498.760077003] [minimal_subscriber]: I heard: "Hello World: 22"
[INFO] [1703876499.727386478] [minimal_subscriber]: subscription was destroyed
[INFO] [1703876499.729411217] [minimal_subscriber]: Subscription done

I want to get the data from the laser scan to detect whether the front of AMR is a person or a machine. It works but it inferences every time. I want to infer three times if the flag is on and then stopping. And again, again
Would you have some ideas to do it the best?

There are two ways to do this: blocking and non blocking way.

  1. Blocking
    there’s a function available rclcpp::wait_for_message(), which will block the thread and wait until a message is received in the topic. I’m sharing an old code I used for you as a reference:
#include "geometry_msgs/msg/twist.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/wait_for_message.hpp"
#include "sensor_msgs/msg/detail/laser_scan__struct.hpp"
#include "sensor_msgs/msg/laser_scan.hpp"
#include "wall_following_pkg/srv/find_wall.hpp"

#include <chrono>
#include <memory>

using FindWall = wall_following_pkg::srv::FindWall;
using std::placeholders::_1;
using std::placeholders::_2;
using namespace std::chrono_literals;

const bool SIMULATION = true;

class ServerNode : public rclcpp::Node {
public:
  ServerNode() : Node("find_wall_server") {
    RCLCPP_INFO(this->get_logger(), "Robot simulated = %d", SIMULATION);
    srv_ = create_service<FindWall>( "find_wall", std::bind(&ServerNode::find_wall_callback, this, _1, _2));
    this->laser_left = 0.0;
    this->laser_right = 0.0;
    this->laser_forward = 0.0;
    this->laser_backward = 0.0;
  }

private:
  rclcpp::Service<FindWall>::SharedPtr srv_;
  geometry_msgs::msg::Twist twist;
  rclcpp::TimerBase::SharedPtr timer_;
  float laser_left;
  float laser_right;
  float laser_forward;
  float laser_backward;

  void find_wall_callback(const std::shared_ptr<FindWall::Request> request,
                          const std::shared_ptr<FindWall::Response> response) {
    typeid(request).name(); // non intrusive function to avoid unused value warning

    

    auto message = sensor_msgs::msg::LaserScan();

    RCLCPP_INFO(this->get_logger(), "starting to wait for message");
    bool scan_found = false;
    while (!scan_found) {
      scan_found = rclcpp::wait_for_message(message, this->shared_from_this(),"/scan",std::chrono::seconds(1));
      RCLCPP_INFO(this->get_logger(), "scan_found = %d", scan_found);
      RCLCPP_INFO(this->get_logger(), "still waiting for message");
    }

      this->laser_left = message.ranges[90];
      this->laser_right = message.ranges[270];
      this->laser_forward = message.ranges[0];
      this->laser_backward = message.ranges[180];
      RCLCPP_INFO(this->get_logger(), "[LEFT] = '%f'", this->laser_left);
      RCLCPP_INFO(this->get_logger(), "[RIGHT] = '%f'", this->laser_right);
      RCLCPP_INFO(this->get_logger(), "[FORWARD] = '%f'", this->laser_forward);
      RCLCPP_INFO(this->get_logger(), "[BACKWARD] = '%f'", this->laser_backward);

    
    response->wallfound = true;
  }
};

int main(int argc, char *argv[]) {
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<ServerNode>());
  rclcpp::shutdown();
  return 0;
}

This might be useful if the rate at which you want the message is extremely low, and if you want to have the latest data available. But you wont be able to anything while the thread is running and if the rate is significant then it might cause a bit of inefficiency as it creates and destroys a subscriber every time wait_for_message is being called. In other cases ill recommend the non blocking one.
2. Non Blocking
This is really simple, just use a subscriber and a update the message variable which you store locally in your object or anywhere you want. Whenever you need the message read from the said variable. Really simple. Although you might have to make the implementation thread safe depending on your spinner (using mutex while accessing or updating it).