Skip to content

Development guidelines

mhidalgo-bdai edited this page Dec 4, 2023 · 4 revisions

To streamline development, consider the following rules of thumb:

  1. Do not subclass from rclpy.node.Node, use process-wide APIs instead
  2. When appropriate, subclass bdai_ros2_wrappers.node.Node instead
  3. Use logging module to log unless within a node subclass

Do not subclass from rclpy.node.Node, use process-wide APIs instead

Rationale

While node subclassing is the typical approach to ROS 2 development, fostering code reuse, it is easy to run into deadlocks once ros_utilities are embraced and asynchronous programming is slowly replaced by synchronous programming. Calling a service and waiting for a reply, waiting for a transform to become available, are some examples of blocking calls on which an rclpy.node.Node subclass could block indefinitely if used at construction time. These problems go away if process-wide APIs and prebaked auto-spinning nodes are used instead.

Application
from bdai_ros2_wrappers.tf_listener_wrapper import TFListenerWrapper
from bdai_ros2_wrappers.context import wait_for_shutdown

-import rclpy
-from rclpy.node import Node
+import bdai_ros2_wrappers.process as ros_process

-class ApplicationNode(Node):
+class Application:
    def __init__(self):
-       super().__init__("app")
-       self.tf_listener = TFListenerWrapper(self)
+       self.tf_listener = TFListenerWrapper()
        self.tf_listener.wait_for_a_tform_b("map", "robot")  # this would block forever on a node subclass

+@ros_process.main()
def main():
-   rclpy.init()
-   rclpy.spin(ApplicationNode())
+   app = Application()
+   wait_for_shutdown()
-   rclpy.shutdown()

If necessary, subclass bdai_ros2_wrappers.node.Node instead

Rationale

Sometimes subclassing rclpy.node.Node is necessary: to offer standard ROS 2 reusable nodes, to simplify managing ROS 2 interfaces' lifetimes (e.g. subscriptions, clients, etc.), and so on. If done with care, this is perfectly feasible. For node subclasses that rely on synchronous programming, however, rclpy.node.Node default mutually exclusive callback group can lead to deadlocks (as only one callback may be running at a time). This can be circumvented by manually specifying a reentrant or non-reentrant callback group, or simply by subclassing bdai_ros2_wrappers.node.Node instead, an rclpy.node.Node subclass with a non-reentrant callback group.

Application
-from rclpy.node import Node
+from bdai_ros2_wrappers.node import Node

class MyNode(Node):
    pass

Use logging module to log unless within a node subclass

Rationale

Bringing ROS 2 specifics to code that is largely ROS 2 agnostic works against reuse.

Application
+import logging
from bdai_ros2_wrappers.process as ros_process

@ros_process.main()
def main():
-   main.node.get_logger().info("Logging!")
+   logging.info("Logging!")

Clone this wiki locally