Skip to content

Commit

Permalink
Merge branch 'gz_sim_ros_node_composition' into launch_gz
Browse files Browse the repository at this point in the history
Signed-off-by: Carlos Agüero <[email protected]>
  • Loading branch information
caguero committed May 15, 2024
2 parents 53c024a + 6a73faa commit 7bcbd32
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 7 deletions.
3 changes: 1 addition & 2 deletions ros_gz_sim/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@ find_package(gz-msgs REQUIRED)
find_package(gz_sim_vendor REQUIRED)
find_package(gz-sim REQUIRED)
# Needed in launch/gz_sim.launch.py.in
set(GZ_SIM_VER ${gz-sim_VERSION_MAJOR})

gz_find_package(gflags
REQUIRED
Expand Down Expand Up @@ -69,7 +68,7 @@ ament_target_dependencies(gzserver_component
std_msgs
)
target_link_libraries(gzserver_component
${GZ_TARGET_PREFIX}-sim${GZ_SIM_VER}::core
gz-sim::core
)
ament_target_dependencies(gzserver_component std_msgs)
rclcpp_components_register_node(
Expand Down
10 changes: 5 additions & 5 deletions ros_gz_sim/launch/ros_gz_sim.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ def generate_launch_description():
namespace = LaunchConfiguration('namespace')
use_composition = LaunchConfiguration('use_composition')
use_respawn = LaunchConfiguration('use_respawn')
log_level = LaunchConfiguration('log_level')
bridge_log_level = LaunchConfiguration('bridge_log_level')

world_sdf_file = LaunchConfiguration('world_sdf_file')
world_sdf_string = LaunchConfiguration('world_sdf_string')
Expand Down Expand Up @@ -57,8 +57,8 @@ def generate_launch_description():
description='Whether to respawn if a node crashes. Applied when composition is disabled.',
)

declare_log_level_cmd = DeclareLaunchArgument(
'log_level', default_value='info', description='log level'
declare_bridge_log_level_cmd = DeclareLaunchArgument(
'bridge_log_level', default_value='info', description='Bridge log level'
)

declare_world_sdf_file_cmd = DeclareLaunchArgument(
Expand All @@ -81,7 +81,7 @@ def generate_launch_description():
('namespace', namespace),
('use_composition', use_composition),
('use_respawn', use_respawn),
('log_level', log_level)])
('bridge_log_level', bridge_log_level)])

gzserver_description = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
Expand All @@ -101,7 +101,7 @@ def generate_launch_description():
ld.add_action(declare_namespace_cmd)
ld.add_action(declare_use_composition_cmd)
ld.add_action(declare_use_respawn_cmd)
ld.add_action(declare_log_level_cmd)
ld.add_action(declare_bridge_log_level_cmd)
ld.add_action(declare_world_sdf_file_cmd)
ld.add_action(declare_world_sdf_string_cmd)
# Add the actions to launch all of the bridge + gzserver nodes
Expand Down

0 comments on commit 7bcbd32

Please sign in to comment.