Skip to main content

Your submission was sent successfully! Close

Thank you for signing up for our newsletter!
In these regular emails you will find the latest updates from Canonical and upcoming events where you can meet our team.Close

Thank you for contacting us. A member of our team will be in touch shortly. Close

  1. Blog
  2. Article

Kyle Fazzari
on 11 March 2019

ROS 2 launch: required nodes


Please note that this blog post has old information that may no longer be correct. We invite you to read the content as a starting point but please search for more updated information in the ROS documentation

When using the Robot Operating System (ROS), it’s fairly common to want to shut down a launched system if a specific node (or set of nodes) exits. This is pretty easy in ROS1, because launch files support the required attribute on each node. As a result, crafting a two-node system where one of the nodes is required is straightforward:

<launch>
<node name = "talker" pkg = "talker" type = "talker_node" />
<node name = "listener" pkg = "listener" type = "talker_node" required = "true" />
</launch>

This launch file creates a talker/listener system where, if the talker exits the system continues trucking along, but if the listener exits the entire launched system is shut down.

In ROS 2 Crystal’s launch system, getting similar functionality involves a lot more boilerplate:

import launch
import launch_ros.actions

def generate_launch_description():
talker = launch_ros.actions.Node(
package="demo_nodes_py",
node_executable="talker",
node_name="talker",
output="screen")

listener = launch_ros.actions.Node(
package="demo_nodes_py",
node_executable="listener_qos",
node_name="listener",
output="screen",
arguments=["--number_of_cycles", "1"])

return launch.LaunchDescription([
talker,
listener,
launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=listener,
on_exit=[
launch.actions.LogInfo(
msg="Listener exited; tearing down entire system."),
launch.actions.EmitEvent(
event=launch.events.Shutdown())]))
])
t

This also creates a talker/listener system where, if the talker exits the system continues, but if the listener exits the launched system is shut down. However, you can see that, unlike the ROS1 example, there are a few steps required to get there. Specifically, it requires the LaunchDescription to include an event handler to listen for an exit event for every required node which then emits a Shutdown event, which then FINALLY causes the launched system to shut down. That doesn’t scale particularly well to a real system where a large number of nodes may be required to run successfully.

We went through a few design iterations for how to best solve this, and decided that both the scaling and the boilerplate issues could be solved if the Node definitions could specify somehow that they were required. Rather than carry over that language from ROS1, though, we decided to keep some commonality with OnProcessExit and simply add an on_exit action list directly to the Node definition. We also added a new action called Shutdown. Using these two new features together allows one to very simply specify that, if a given node exits, it should shut the entire launched system down. This greatly reduces boilerplate and scales far better than adding an event handler for each node. Take a look:

import launch
import launch_ros.actions

def generate_launch_description():
return launch.LaunchDescription([
launch_ros.actions.Node(
package="demo_nodes_py",
node_executable="talker",
node_name="talker",
output="screen"),

launch_ros.actions.Node(
package="demo_nodes_py",
node_executable="listener_qos",
node_name="listener",
output="screen",
arguments=["--number_of_cycles", "1"],
on_exit=launch.actions.Shutdown())
])

This functionality is already available in master, and will of course be included in Dashing (scheduled for June).

This article originally appeared on Kyle Fazzari’s blog.

Related posts


gbeuzeboc
11 April 2023

Optimise your ROS snap – Part 2

Robotics Article

Welcome to Part 2 of the “optimise your ROS snap” blog series. Make sure to check Part 1 before reading this blog post. This second part is going to present initial optimisations already used in the Gazebo snap. We will present the benefit that they could bring to our ROS snaps as well as the ...


gbeuzeboc
6 April 2023

Optimise your ROS snap – Part 1

Robotics Article

Do you want to optimise the performance of your ROS snap? We reduced the size of the installed Gazebo snap by 95%! This is how you can do it for your snap. Welcome to Part 1 of the “optimise your ROS snap” blog series. This series of 6 blogs will show the tools and methodologies ...


gbeuzeboc
22 September 2022

ROS orchestration with snaps

Robotics Article

Application orchestration is the process of integrating applications together to automate and synchronise processes. In robotics, this is essential, especially on complex systems that involve a lot of different processes working together. But, ROS applications are usually launched all at once from one top-level launch file. With orchestra ...