diff --git a/ros_gz_bridge/CMakeLists.txt b/ros_gz_bridge/CMakeLists.txt
index f46f50cc..44911577 100644
--- a/ros_gz_bridge/CMakeLists.txt
+++ b/ros_gz_bridge/CMakeLists.txt
@@ -22,6 +22,9 @@ find_package(gz-transport REQUIRED)
find_package(gz_msgs_vendor REQUIRED)
find_package(gz-msgs REQUIRED)
+# Install the python module for this package
+ament_python_install_package(${PROJECT_NAME})
+
set(GZ_MSGS_VERSION_FULL ${gz-msgs_VERSION})
set(BRIDGE_MESSAGE_TYPES
diff --git a/ros_gz_bridge/launch/ros_gz_bridge.launch b/ros_gz_bridge/launch/ros_gz_bridge.launch
new file mode 100644
index 00000000..f1a99158
--- /dev/null
+++ b/ros_gz_bridge/launch/ros_gz_bridge.launch
@@ -0,0 +1,16 @@
+
+
+
+
+
+
+
+
+
+
diff --git a/ros_gz_bridge/package.xml b/ros_gz_bridge/package.xml
index fe402448..b51c3282 100644
--- a/ros_gz_bridge/package.xml
+++ b/ros_gz_bridge/package.xml
@@ -11,14 +11,18 @@
Shivesh Khaitan
Louise Poubel
+ Carlos Agüero
ament_cmake
+ ament_cmake_python
pkg-config
rosidl_pycommon
actuator_msgs
geometry_msgs
gps_msgs
+ launch
+ launch_ros
nav_msgs
rclcpp
rclcpp_components
diff --git a/ros_gz_bridge/resource/ros_gz_bridge b/ros_gz_bridge/resource/ros_gz_bridge
new file mode 100644
index 00000000..e69de29b
diff --git a/ros_gz_bridge/ros_gz_bridge/__init__.py b/ros_gz_bridge/ros_gz_bridge/__init__.py
index d1cf4289..b6234079 100644
--- a/ros_gz_bridge/ros_gz_bridge/__init__.py
+++ b/ros_gz_bridge/ros_gz_bridge/__init__.py
@@ -20,6 +20,12 @@
from rosidl_pycommon import expand_template
+from . import actions
+
+__all__ = [
+ 'actions',
+]
+
@dataclass
class MessageMapping:
diff --git a/ros_gz_bridge/ros_gz_bridge/actions/__init__.py b/ros_gz_bridge/ros_gz_bridge/actions/__init__.py
new file mode 100644
index 00000000..0a2c2665
--- /dev/null
+++ b/ros_gz_bridge/ros_gz_bridge/actions/__init__.py
@@ -0,0 +1,22 @@
+# Copyright 2024 Open Source Robotics Foundation, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+"""Actions module."""
+
+from .ros_gz_bridge import RosGzBridge
+
+
+__all__ = [
+ 'RosGzBridge',
+]
diff --git a/ros_gz_bridge/ros_gz_bridge/actions/ros_gz_bridge.py b/ros_gz_bridge/ros_gz_bridge/actions/ros_gz_bridge.py
new file mode 100644
index 00000000..e9cf15ee
--- /dev/null
+++ b/ros_gz_bridge/ros_gz_bridge/actions/ros_gz_bridge.py
@@ -0,0 +1,135 @@
+# Copyright 2024 Open Source Robotics Foundation, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+"""Module for the ros_gz bridge action."""
+
+from typing import List
+from typing import Optional
+
+from launch.action import Action
+from launch.actions import IncludeLaunchDescription
+from launch.frontend import Entity, expose_action, Parser
+from launch.launch_context import LaunchContext
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch.some_substitutions_type import SomeSubstitutionsType
+from launch.substitutions import PathJoinSubstitution
+from launch_ros.substitutions import FindPackageShare
+
+
+@expose_action('ros_gz_bridge')
+class RosGzBridge(Action):
+ """Action that executes a ros_gz bridge ROS [composable] node."""
+
+ def __init__(
+ self,
+ *,
+ config_file: Optional[SomeSubstitutionsType] = None,
+ container_name: Optional[SomeSubstitutionsType] = None,
+ namespace: Optional[SomeSubstitutionsType] = None,
+ use_composition: Optional[SomeSubstitutionsType] = None,
+ use_respawn: Optional[SomeSubstitutionsType] = None,
+ log_level: Optional[SomeSubstitutionsType] = None,
+ **kwargs
+ ) -> None:
+ """
+ Construct a ros_gz bridge action.
+
+ All arguments are forwarded to `ros_gz_bridge.launch.ros_gz_bridge.launch.py`,
+ so see the documentation of that class for further details.
+
+ :param: config_file YAML config file.
+ :param: container_name Name of container that nodes will load in if use composition.
+ :param: namespace Top-level namespace.
+ :param: use_composition Use composed bringup if True.
+ :param: use_respawn Whether to respawn if a node crashes (when composition is disabled).
+ :param: log_level Log level.
+ """
+ super().__init__(**kwargs)
+ self.__config_file = config_file
+ self.__container_name = container_name
+ self.__namespace = namespace
+ self.__use_composition = use_composition
+ self.__use_respawn = use_respawn
+ self.__log_level = log_level
+
+ @classmethod
+ def parse(cls, entity: Entity, parser: Parser):
+ """Parse ros_gz_bridge."""
+ _, kwargs = super().parse(entity, parser)
+
+ config_file = entity.get_attr(
+ 'config_file', data_type=str,
+ optional=False)
+
+ container_name = entity.get_attr(
+ 'container_name', data_type=str,
+ optional=True)
+
+ namespace = entity.get_attr(
+ 'namespace', data_type=str,
+ optional=True)
+
+ use_composition = entity.get_attr(
+ 'use_composition', data_type=str,
+ optional=True)
+
+ use_respawn = entity.get_attr(
+ 'use_respawn', data_type=str,
+ optional=True)
+
+ log_level = entity.get_attr(
+ 'log_level', data_type=str,
+ optional=True)
+
+ if isinstance(config_file, str):
+ config_file = parser.parse_substitution(config_file)
+ kwargs['config_file'] = config_file
+
+ if isinstance(container_name, str):
+ container_name = parser.parse_substitution(container_name)
+ kwargs['container_name'] = container_name
+
+ if isinstance(namespace, str):
+ namespace = parser.parse_substitution(namespace)
+ kwargs['namespace'] = namespace
+
+ if isinstance(use_composition, str):
+ use_composition = parser.parse_substitution(use_composition)
+ kwargs['use_composition'] = use_composition
+
+ if isinstance(use_respawn, str):
+ use_respawn = parser.parse_substitution(use_respawn)
+ kwargs['use_respawn'] = use_respawn
+
+ if isinstance(log_level, str):
+ log_level = parser.parse_substitution(log_level)
+ kwargs['log_level'] = log_level
+
+ return cls, kwargs
+
+ def execute(self, context: LaunchContext) -> Optional[List[Action]]:
+ """Execute the action."""
+ ros_gz_bridge_description = IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ [PathJoinSubstitution([FindPackageShare('ros_gz_bridge'),
+ 'launch',
+ 'ros_gz_bridge.launch.py'])]),
+ launch_arguments=[('config_file', self.__config_file),
+ ('container_name', self.__container_name),
+ ('namespace', self.__namespace),
+ ('use_composition', self.__use_composition),
+ ('use_respawn', self.__use_respawn),
+ ('log_level', self.__log_level), ])
+
+ return [ros_gz_bridge_description]
diff --git a/ros_gz_bridge/setup.cfg b/ros_gz_bridge/setup.cfg
new file mode 100644
index 00000000..1f707813
--- /dev/null
+++ b/ros_gz_bridge/setup.cfg
@@ -0,0 +1,3 @@
+[options.entry_points]
+launch.frontend.launch_extension =
+ ros_gz_bridge = ros_gz_bridge
diff --git a/ros_gz_sim/CMakeLists.txt b/ros_gz_sim/CMakeLists.txt
index a9b3a1cc..0b7e2c25 100644
--- a/ros_gz_sim/CMakeLists.txt
+++ b/ros_gz_sim/CMakeLists.txt
@@ -100,6 +100,7 @@ install(FILES
"launch/gz_server.launch"
"launch/gz_server.launch.py"
"launch/gz_spawn_model.launch.py"
+ "launch/ros_gz_sim.launch"
"launch/ros_gz_sim.launch.py"
"launch/ros_gz_spawn_model.launch.py"
DESTINATION share/${PROJECT_NAME}/launch
diff --git a/ros_gz_sim/launch/ros_gz_sim.launch b/ros_gz_sim/launch/ros_gz_sim.launch
new file mode 100644
index 00000000..83c055df
--- /dev/null
+++ b/ros_gz_sim/launch/ros_gz_sim.launch
@@ -0,0 +1,24 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+