えいあーるれいの技術日記

ROS2やM5 Stack、Ubuntuについて書いています

subscription数のカウント(rclpy・ROS2)

久しぶりに薄い内容の記事を書きます。(いつも薄い記事しかないって?かましいわ!

ROS2はコンピュータ間の1対他通信をサポートしているとても便利なツールです。しかし、接続が自由な1対他通信ゆえに、プログラムを工夫しないと受信側が落ちてもPublisher側が気づかないという欠点があります。トピックのカウントはros2 topic info -v /topic名で検索したSubscriptionの総数を数えるのも一つの手ですが、もっと簡単に数えることができます。

ここでは他であまり紹介されていませんが、地味に便利なROS2のPublisher側から見たSubscriberの数の取得方法を示します。これを使うとSubscription数が減った時に通知する機能を使いたいときとかに便利だと思います。

↓ドキュメント(rclpyリファレンス)

docs.ros2.org

コード例

publisherクラスのget_subscription_count()メソッドの返り値を受け取ることでPublisher側から見たSubscriberの数を数えられます。以下にコード例を示します。

コードの挙動は

  • Publisher側が値を送信したあとにSubscriptionの数を数えています。
  • Subscription側がトピックを受信するSubscriptionをcreate_sub_countの数だけ作成します。

Publisher側

import rclpy
from std_msgs.msg import Int32
from rclpy.node import Node

Pub側
class pub_sub_int32(Node):
    def __init__(self):
        super().__init__('pub_sub_int32')
        self.pub_data = 0
        self.pub_int32 = self.create_publisher(Int32, '/sub_int32', 10)
        # timer
        self.timer = self.create_timer(0.1, self.timer_update)
    
    def timer_update(self):
        self.pub_data += 1
        msg = Int32()
        msg.data = self.pub_data
        self.pub_int32.publish(msg)
        self.get_logger().info('Subscription count: %d' % self.pub_int32.get_subscription_count())

def ros_pub_main():
    rclpy.init(args=None)
    node = pub_sub_int32()
    rclpy.spin(node)
    node.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    ros_pub_main()

Subscription側

import rclpy
from rclpy.node import Node
from std_msgs.msg import Int32

# Sub側
class create_many_subscription(Node):
    def __init__(self):
        super().__init__('create_many_subscription')
        create_sub_count = 10
        subscribers = []
        for i in range(create_sub_count):
            subscribers.append(self.create_subscription(Int32, '/sub_int32', self.listener, 10))
    def listener(self, msg:Int32):
        self.get_logger().info('I heard: "%s"' % msg.data)

def ros_sub_main():
    rclpy.init(args=None)
    node = create_many_subscription()
    rclpy.spin(node)
    node.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    ros_sub_main()

直接Python3で実行します。

f:id:Ray_ar:20220322100956p:plain