ros / bond_core

Maintains a bond (i.e. heart beat ) between ROS nodes and provides feedback when the bond is broken
http://www.ros.org/wiki/bond_core
36 stars 65 forks source link

Fail to process all bond callbacks in bondpy #95

Open sosoeeee opened 5 months ago

sosoeeee commented 5 months ago

Thank you for your work on migrating bondpy to ROS2!

I am currently using bondpy to create a Python lifecycle node as part of my development with the nav2 lifecycle manager. While the bond is formed successfully using bondpy, I encountered an issue where the node quickly dies due to a heartbeat timeout. After investigation, I discovered that bondpy fails to respond to all bond_status messages published by the lifecycle manager at high speed.

To resolve this issue, I referred to the implementation of bondcpp and increased the message buffer size from 1 to 100 in bondpy as follows:

def start(self):
    with self.lock:
        self.connect_timer.reset()
        self.sub = self.node.create_subscription(Status, self.topic, self._on_bond_status, 100)

        self.thread = threading.Thread(target=self._publishing_thread)
        self.thread.daemon = True
        self.thread.start()
        self.__started = True

If this modification does not lead to any potential errors, I would appreciate it if it could be included in an update to bondpy.

clalancette commented 5 months ago

Please feel free to open a pull request with that change, and we are happy to review it.

sosoeeee commented 5 months ago

Thank you for your reply! I have opened a pull request.