diff --git a/gazebo_ros/launch/gazebo.launch.py b/gazebo_ros/launch/gazebo.launch.py
index 6fba9dd68..2e993c51b 100644
--- a/gazebo_ros/launch/gazebo.launch.py
+++ b/gazebo_ros/launch/gazebo.launch.py
@@ -15,21 +15,30 @@
"""Launch Gazebo server and client with command line arguments."""
from launch import LaunchDescription
+from launch.actions import DeclareLaunchArgument
from launch.actions import IncludeLaunchDescription
+from launch.conditions import IfCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch.substitutions import LaunchConfiguration
from launch.substitutions import ThisLaunchFileDir
def generate_launch_description():
- # (TODO) Allow conditional include of gzserver and gzclient, once supported
- # https://github.com/ros2/launch/issues/303
return LaunchDescription([
+ DeclareLaunchArgument('gui', default_value='true',
+ description='Set to "false" to run headless.'),
+
+ DeclareLaunchArgument('server', default_value='true',
+ description='Set to "false" not to run gzserver.'),
+
IncludeLaunchDescription(
PythonLaunchDescriptionSource([ThisLaunchFileDir(), '/gzserver.launch.py']),
+ condition=IfCondition(LaunchConfiguration('server'))
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource([ThisLaunchFileDir(), '/gzclient.launch.py']),
+ condition=IfCondition(LaunchConfiguration('gui'))
),
])
diff --git a/gazebo_ros/package.xml b/gazebo_ros/package.xml
index b483071b9..8035043b8 100644
--- a/gazebo_ros/package.xml
+++ b/gazebo_ros/package.xml
@@ -30,6 +30,8 @@
std_srvs
tinyxml_vendor
+ launch_ros
+
geometry_msgs
sensor_msgs