Skip to content

unique_multi_tb3_simulation does not work when Gazebo GUI is enabled #5315

Open
@antonTan96

Description

@antonTan96

Bug report

Required Info:

  • Operating System:
    • WSL2 running Ubuntu 24.04
  • Computer:
    • 12th Gen Intel(R) Core(TM) i7-12700H 2.30 GHz, NVIDIA GeForce RTX 3080 Ti
  • ROS2 Version:
    • Jazzy with binaries, Gazebo Harmonic if relevant
  • Version or commit hash:
  • DDS implementation:
    • cyclone DDS

Steps to reproduce issue

Replace unique_multi_tb3_simulation_launch.py with the following and rebuild nav2_bringup (changes on line 140)

# Copyright (c) 2018 Intel Corporation
#
# 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.

"""
Example for spawning multiple robots in Gazebo.

This is an example on how to create a launch file for spawning multiple robots into Gazebo
and launch multiple instances of the navigation stack, each controlling one robot.
The robots co-exist on a shared environment and are controlled by independent nav stacks.
"""

import os
from pathlib import Path
import tempfile

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import (AppendEnvironmentVariable, DeclareLaunchArgument, ExecuteProcess,
                            GroupAction, IncludeLaunchDescription, LogInfo, OpaqueFunction,
                            RegisterEventHandler)
from launch.conditions import IfCondition
from launch.event_handlers import OnShutdown
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, TextSubstitution


def generate_launch_description() -> LaunchDescription:
    # Get the launch directory
    bringup_dir = get_package_share_directory('nav2_bringup')
    launch_dir = os.path.join(bringup_dir, 'launch')
    sim_dir = get_package_share_directory('nav2_minimal_tb3_sim')

    # Names and poses of the robots
    robots = [
        {
            'name': 'robot1',
            'x_pose': 0.0,
            'y_pose': 0.5,
            'z_pose': 0.01,
            'roll': 0.0,
            'pitch': 0.0,
            'yaw': 0.0,
        },
        # {
        #     'name': 'robot2',
        #     'x_pose': 0.0,
        #     'y_pose': -0.5,
        #     'z_pose': 0.01,
        #     'roll': 0.0,
        #     'pitch': 0.0,
        #     'yaw': 0.0,
        # },
    ]

    # Simulation settings
    world = LaunchConfiguration('world')

    # On this example all robots are launched with the same settings
    map_yaml_file = LaunchConfiguration('map')
    graph_filepath = LaunchConfiguration('graph')

    autostart = LaunchConfiguration('autostart')
    rviz_config_file = LaunchConfiguration('rviz_config')
    use_robot_state_pub = LaunchConfiguration('use_robot_state_pub')
    use_rviz = LaunchConfiguration('use_rviz')
    log_settings = LaunchConfiguration('log_settings', default='true')

    # Declare the launch arguments
    declare_world_cmd = DeclareLaunchArgument(
        'world',
        default_value=os.path.join(sim_dir, 'worlds', 'tb3_sandbox.sdf.xacro'),
        description='Full path to world file to load',
    )

    declare_map_yaml_cmd = DeclareLaunchArgument(
        'map',
        default_value=os.path.join(bringup_dir, 'maps', 'tb3_sandbox.yaml'),
        description='Full path to map file to load',
    )

    declare_graph_file_cmd = DeclareLaunchArgument(
        'graph',
        default_value=os.path.join(bringup_dir, 'graphs', 'turtlebot3_graph.geojson'),
    )

    declare_robot1_params_file_cmd = DeclareLaunchArgument(
        'robot1_params_file',
        default_value=os.path.join(
            bringup_dir, 'params', 'nav2_params.yaml'
        ),
        description='Full path to the ROS2 parameters file to use for robot1 launched nodes',
    )

    declare_robot2_params_file_cmd = DeclareLaunchArgument(
        'robot2_params_file',
        default_value=os.path.join(
            bringup_dir, 'params', 'nav2_params.yaml'
        ),
        description='Full path to the ROS2 parameters file to use for robot2 launched nodes',
    )

    declare_autostart_cmd = DeclareLaunchArgument(
        'autostart',
        default_value='false',
        description='Automatically startup the stacks',
    )

    declare_rviz_config_file_cmd = DeclareLaunchArgument(
        'rviz_config',
        default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'),
        description='Full path to the RVIZ config file to use.',
    )

    declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
        'use_robot_state_pub',
        default_value='True',
        description='Whether to start the robot state publisher',
    )

    declare_use_rviz_cmd = DeclareLaunchArgument(
        'use_rviz', default_value='True', description='Whether to start RVIZ'
    )

    # Start Gazebo with plugin providing the robot spawning service
    world_sdf = tempfile.mktemp(prefix='nav2_', suffix='.sdf')
    world_sdf_xacro = ExecuteProcess(
        cmd=['xacro', '-o', world_sdf, ['headless:=', 'False'], world])
    start_gazebo_cmd = ExecuteProcess(
        cmd=['gz', 'sim', '-r', '-g', world_sdf], #change made here from -s to -g to enable GUI
        output='screen',
    )

    remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
        on_shutdown=[
            OpaqueFunction(function=lambda _: os.remove(world_sdf))
        ]))

    # Define commands for launching the navigation instances
    nav_instances_cmds = []
    for robot in robots:
        params_file = LaunchConfiguration(f"{robot['name']}_params_file")

        group = GroupAction(
            [
                IncludeLaunchDescription(
                    PythonLaunchDescriptionSource(
                        os.path.join(launch_dir, 'rviz_launch.py')
                    ),
                    condition=IfCondition(use_rviz),
                    launch_arguments={
                        'namespace': TextSubstitution(text=robot['name']),
                        'rviz_config': rviz_config_file,
                    }.items(),
                ),
                IncludeLaunchDescription(
                    PythonLaunchDescriptionSource(
                        os.path.join(bringup_dir, 'launch', 'tb3_simulation_launch.py')
                    ),
                    launch_arguments={
                        'namespace': robot['name'],
                        'map': map_yaml_file,
                        'graph': graph_filepath,
                        'use_sim_time': 'True',
                        'params_file': params_file,
                        'autostart': autostart,
                        'use_rviz': 'False',
                        'use_simulator': 'False',
                        'headless': 'False',
                        'use_robot_state_pub': use_robot_state_pub,
                        'x_pose': TextSubstitution(text=str(robot['x_pose'])),
                        'y_pose': TextSubstitution(text=str(robot['y_pose'])),
                        'z_pose': TextSubstitution(text=str(robot['z_pose'])),
                        'roll': TextSubstitution(text=str(robot['roll'])),
                        'pitch': TextSubstitution(text=str(robot['pitch'])),
                        'yaw': TextSubstitution(text=str(robot['yaw'])),
                        'robot_name': TextSubstitution(text=robot['name']),
                    }.items(),
                ),
                LogInfo(
                    condition=IfCondition(log_settings),
                    msg=['Launching ', robot['name']],
                ),
                LogInfo(
                    condition=IfCondition(log_settings),
                    msg=[robot['name'], ' map yaml: ', map_yaml_file],
                ),
                LogInfo(
                    condition=IfCondition(log_settings),
                    msg=[robot['name'], ' params yaml: ', params_file],
                ),
                LogInfo(
                    condition=IfCondition(log_settings),
                    msg=[robot['name'], ' rviz config file: ', rviz_config_file],
                ),
                LogInfo(
                    condition=IfCondition(log_settings),
                    msg=[
                        robot['name'],
                        ' using robot state pub: ',
                        use_robot_state_pub,
                    ],
                ),
                LogInfo(
                    condition=IfCondition(log_settings),
                    msg=[robot['name'], ' autostart: ', autostart],
                ),
            ]
        )

        nav_instances_cmds.append(group)

    set_env_vars_resources = AppendEnvironmentVariable(
        'GZ_SIM_RESOURCE_PATH', os.path.join(sim_dir, 'models'))
    set_env_vars_resources2 = AppendEnvironmentVariable(
            'GZ_SIM_RESOURCE_PATH',
            str(Path(os.path.join(sim_dir)).parent.resolve()))

    # Create the launch description and populate
    ld = LaunchDescription()
    ld.add_action(set_env_vars_resources)
    ld.add_action(set_env_vars_resources2)

    # Declare the launch options
    ld.add_action(declare_world_cmd)
    ld.add_action(declare_map_yaml_cmd)
    ld.add_action(declare_graph_file_cmd)
    ld.add_action(declare_robot1_params_file_cmd)
    ld.add_action(declare_robot2_params_file_cmd)
    ld.add_action(declare_use_rviz_cmd)
    ld.add_action(declare_autostart_cmd)
    ld.add_action(declare_rviz_config_file_cmd)
    ld.add_action(declare_use_robot_state_pub_cmd)

    # Add the actions to start gazebo, robots and simulations
    ld.add_action(world_sdf_xacro)
    ld.add_action(start_gazebo_cmd)
    ld.add_action(remove_temp_sdf_file)

    for simulation_instance_cmd in nav_instances_cmds:
        ld.add_action(simulation_instance_cmd)

    return ld

After building, launch the simulation with ros2 launch nav2_bringup unique_multi_tb3_simulation_launch.py

Expected behavior

Gazebo GUI should pop up with turtlebot world and turtlebot waffle models loaded

Actual behavior

Gazebo GUI does not load (hangs on blank screen) and turtlebot waffle does not get spawned

Additional information

I want to see the namespaced models actually move in a simulated environment for my project but this theoretically possible example does not work, and it keeps on requesting list of world names. Additional logs when I run this file are as follows:

[INFO] [launch]: All log files can be found below /home/edic/.ros/log/2025-06-30-01-16-32-138305-DESKTOP-1V2T8RI-55987
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [launch.user]: Launching robot1
[INFO] [launch.user]: robot1 map yaml: /home/edic/nav2_ws/install/nav2_bringup/share/nav2_bringup/maps/tb3_sandbox.yaml
[INFO] [launch.user]: robot1 params yaml: /home/edic/nav2_ws/install/nav2_bringup/share/nav2_bringup/params/nav2_params.yaml
[INFO] [launch.user]: robot1 rviz config file: /home/edic/nav2_ws/install/nav2_bringup/share/nav2_bringup/rviz/nav2_default_view.rviz
[INFO] [launch.user]: robot1 using robot state pub: True
[INFO] [launch.user]: robot1 autostart: false
[INFO] [xacro-1]: process started with pid [56011]
[INFO] [gz-2]: process started with pid [56012]
[INFO] [rviz2-3]: process started with pid [56013]
[INFO] [xacro-4]: process started with pid [56014]
[INFO] [parameter_bridge-5]: process started with pid [56015]
[INFO] [create-6]: process started with pid [56016]
[INFO] [robot_state_publisher-7]: process started with pid [56017]
[INFO] [component_container_isolated-8]: process started with pid [56018]
[INFO] [xacro-1]: process has finished cleanly [pid 56011]
[INFO] [xacro-4]: process has finished cleanly [pid 56014]
[rviz2-3] QStandardPaths: wrong permissions on runtime directory /run/user/1000/, 0755 instead of 0700
[robot_state_publisher-7] [INFO] [1751217393.253013480] [robot1.robot_state_publisher]: Robot initialized
[component_container_isolated-8] [INFO] [1751217393.284693992] [robot1.nav2_container]: Load Library: /home/edic/nav2_ws/install/nav2_map_server/lib/libmap_server_core.so
[component_container_isolated-8] [INFO] [1751217393.321109576] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_map_server::CostmapFilterInfoServer>
[component_container_isolated-8] [INFO] [1751217393.321181394] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_map_server::MapSaver>
[component_container_isolated-8] [INFO] [1751217393.321189103] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_map_server::MapServer>
[component_container_isolated-8] [INFO] [1751217393.321192423] [robot1.nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_map_server::MapServer>
[component_container_isolated-8] [INFO] [1751217393.329759981] [robot1.map_server]:
[component_container_isolated-8]        map_server lifecycle node launched.
[component_container_isolated-8]        Waiting on external lifecycle transitions to activate
[component_container_isolated-8]        See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-8] [INFO] [1751217393.329806621] [robot1.map_server]: Creating
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/robot1/map_server' in container 'robot1/nav2_container'
[component_container_isolated-8] [INFO] [1751217393.387790153] [robot1.nav2_container]: Load Library: /home/edic/nav2_ws/install/nav2_controller/lib/libcontroller_server_core.so
[component_container_isolated-8] [INFO] [1751217393.409018632] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_controller::ControllerServer>
[component_container_isolated-8] [INFO] [1751217393.409117935] [robot1.nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_controller::ControllerServer>
[component_container_isolated-8] [INFO] [1751217393.424278811] [robot1.controller_server]:
[component_container_isolated-8]        controller_server lifecycle node launched.
[component_container_isolated-8]        Waiting on external lifecycle transitions to activate
[component_container_isolated-8]        See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-8] [INFO] [1751217393.445290559] [robot1.controller_server]: Creating controller server
[component_container_isolated-8] [INFO] [1751217393.457081693] [robot1.local_costmap.local_costmap]:
[component_container_isolated-8]        local_costmap lifecycle node launched.
[component_container_isolated-8]        Waiting on external lifecycle transitions to activate
[component_container_isolated-8]        See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-8] [INFO] [1751217393.459486192] [robot1.local_costmap.local_costmap]: Creating Costmap
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/robot1/controller_server' in container 'robot1/nav2_container'
[component_container_isolated-8] [INFO] [1751217393.462382932] [robot1.nav2_container]: Load Library: /home/edic/nav2_ws/install/nav2_amcl/lib/libamcl_core.so
[component_container_isolated-8] [INFO] [1751217393.470401886] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_amcl::AmclNode>
[component_container_isolated-8] [INFO] [1751217393.470446226] [robot1.nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_amcl::AmclNode>
[component_container_isolated-8] [INFO] [1751217393.478151713] [robot1.amcl]:
[component_container_isolated-8]        amcl lifecycle node launched.
[component_container_isolated-8]        Waiting on external lifecycle transitions to activate
[component_container_isolated-8]        See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-8] [INFO] [1751217393.480249886] [robot1.amcl]: Creating
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/robot1/amcl' in container 'robot1/nav2_container'
[component_container_isolated-8] [INFO] [1751217393.485858690] [robot1.nav2_container]: Load Library: /home/edic/nav2_ws/install/nav2_smoother/lib/libsmoother_server_core.so
[component_container_isolated-8] [INFO] [1751217393.491985463] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_smoother::SmootherServer>
[component_container_isolated-8] [INFO] [1751217393.492022537] [robot1.nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_smoother::SmootherServer>
[component_container_isolated-8] [INFO] [1751217393.498790621] [robot1.smoother_server]:
[component_container_isolated-8]        smoother_server lifecycle node launched.
[component_container_isolated-8]        Waiting on external lifecycle transitions to activate
[component_container_isolated-8]        See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-8] [INFO] [1751217393.501182700] [robot1.smoother_server]: Creating smoother server
[component_container_isolated-8] [INFO] [1751217393.502371642] [robot1.nav2_container]: Load Library: /home/edic/nav2_ws/install/nav2_lifecycle_manager/lib/libnav2_lifecycle_manager_core.so
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/robot1/smoother_server' in container 'robot1/nav2_container'
[component_container_isolated-8] [INFO] [1751217393.506246450] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_lifecycle_manager::LifecycleManager>
[component_container_isolated-8] [INFO] [1751217393.506273818] [robot1.nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_lifecycle_manager::LifecycleManager>
[component_container_isolated-8] [INFO] [1751217393.514590685] [robot1.lifecycle_manager_localization]: Creating
[component_container_isolated-8] [INFO] [1751217393.515685196] [robot1.lifecycle_manager_localization]: Creating and initializing lifecycle service clients
[component_container_isolated-8] [INFO] [1751217393.516011053] [robot1.nav2_container]: Load Library: /home/edic/nav2_ws/install/nav2_planner/lib/libplanner_server_core.so
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/robot1/lifecycle_manager_localization' in container 'robot1/nav2_container'
[component_container_isolated-8] [INFO] [1751217393.518997205] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_planner::PlannerServer>
[component_container_isolated-8] [INFO] [1751217393.519032076] [robot1.nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_planner::PlannerServer>
[component_container_isolated-8] [INFO] [1751217393.520324387] [robot1.lifecycle_manager_localization]: Creating and initializing lifecycle service servers
[component_container_isolated-8] [INFO] [1751217393.533844415] [robot1.planner_server]:
[component_container_isolated-8]        planner_server lifecycle node launched.
[component_container_isolated-8]        Waiting on external lifecycle transitions to activate
[component_container_isolated-8]        See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-8] [INFO] [1751217393.536549269] [robot1.planner_server]: Creating
[component_container_isolated-8] [INFO] [1751217393.544065927] [robot1.global_costmap.global_costmap]:
[component_container_isolated-8]        global_costmap lifecycle node launched.
[component_container_isolated-8]        Waiting on external lifecycle transitions to activate
[component_container_isolated-8]        See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-8] [INFO] [1751217393.544803041] [robot1.global_costmap.global_costmap]: Creating Costmap
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/robot1/planner_server' in container 'robot1/nav2_container'
[gz-2] QStandardPaths: wrong permissions on runtime directory /run/user/1000/, 0755 instead of 0700
[create-6] [INFO] [1751217393.698014744] [robot1.ros_gz_sim]: Requesting list of world names.
[component_container_isolated-8] [INFO] [1751217393.705683049] [robot1.nav2_container]: Load Library: /home/edic/nav2_ws/install/nav2_route/lib/libroute_server_core.so
[component_container_isolated-8] [INFO] [1751217393.711017661] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_route::RouteServer>
[component_container_isolated-8] [INFO] [1751217393.711066210] [robot1.nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_route::RouteServer>
[component_container_isolated-8] [INFO] [1751217393.718483436] [robot1.route_server]:
[component_container_isolated-8]        route_server lifecycle node launched.
[component_container_isolated-8]        Waiting on external lifecycle transitions to activate
[component_container_isolated-8]        See https://design.ros2.org/articles/node_lifecycle.html for more information.
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/robot1/route_server' in container 'robot1/nav2_container'
[component_container_isolated-8] [INFO] [1751217393.906956640] [robot1.nav2_container]: Load Library: /home/edic/nav2_ws/install/nav2_behaviors/lib/libbehavior_server_core.so
[component_container_isolated-8] [INFO] [1751217393.908780715] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<behavior_server::BehaviorServer>
[component_container_isolated-8] [INFO] [1751217393.908821379] [robot1.nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<behavior_server::BehaviorServer>
[component_container_isolated-8] [INFO] [1751217393.915909589] [robot1.behavior_server]:
[component_container_isolated-8]        behavior_server lifecycle node launched.
[component_container_isolated-8]        Waiting on external lifecycle transitions to activate
[component_container_isolated-8]        See https://design.ros2.org/articles/node_lifecycle.html for more information.
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/robot1/behavior_server' in container 'robot1/nav2_container'
[component_container_isolated-8] [INFO] [1751217394.108919359] [robot1.nav2_container]: Load Library: /home/edic/nav2_ws/install/nav2_bt_navigator/lib/libbt_navigator_core.so
[component_container_isolated-8] [INFO] [1751217394.111567702] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_bt_navigator::BtNavigator>
[component_container_isolated-8] [INFO] [1751217394.111602088] [robot1.nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_bt_navigator::BtNavigator>
[component_container_isolated-8] [INFO] [1751217394.122235531] [robot1.bt_navigator]:
[component_container_isolated-8]        bt_navigator lifecycle node launched.
[component_container_isolated-8]        Waiting on external lifecycle transitions to activate
[component_container_isolated-8]        See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-8] [INFO] [1751217394.124792990] [robot1.bt_navigator]: Creating
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/robot1/bt_navigator' in container 'robot1/nav2_container'
[component_container_isolated-8] [INFO] [1751217394.127063358] [robot1.nav2_container]: Load Library: /home/edic/nav2_ws/install/nav2_waypoint_follower/lib/libwaypoint_follower_core.so
[component_container_isolated-8] [INFO] [1751217394.130912810] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_waypoint_follower::WaypointFollower>
[component_container_isolated-8] [INFO] [1751217394.130949435] [robot1.nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_waypoint_follower::WaypointFollower>
[component_container_isolated-8] [INFO] [1751217394.138983268] [robot1.waypoint_follower]:
[component_container_isolated-8]        waypoint_follower lifecycle node launched.
[component_container_isolated-8]        Waiting on external lifecycle transitions to activate
[component_container_isolated-8]        See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-8] [INFO] [1751217394.140860037] [robot1.waypoint_follower]: Creating
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/robot1/waypoint_follower' in container 'robot1/nav2_container'
[component_container_isolated-8] [INFO] [1751217394.144568894] [robot1.nav2_container]: Load Library: /home/edic/nav2_ws/install/nav2_velocity_smoother/lib/libvelocity_smoother_core.so
[component_container_isolated-8] [INFO] [1751217394.147902869] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_velocity_smoother::VelocitySmoother>
[component_container_isolated-8] [INFO] [1751217394.147937757] [robot1.nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_velocity_smoother::VelocitySmoother>
[component_container_isolated-8] [INFO] [1751217394.155515165] [robot1.velocity_smoother]:
[component_container_isolated-8]        velocity_smoother lifecycle node launched.
[component_container_isolated-8]        Waiting on external lifecycle transitions to activate
[component_container_isolated-8]        See https://design.ros2.org/articles/node_lifecycle.html for more information.
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/robot1/velocity_smoother' in container 'robot1/nav2_container'
[component_container_isolated-8] [INFO] [1751217394.310279568] [robot1.nav2_container]: Load Library: /home/edic/nav2_ws/install/nav2_collision_monitor/lib/libcollision_monitor_core.so
[component_container_isolated-8] [INFO] [1751217394.317993295] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_collision_monitor::CollisionMonitor>
[component_container_isolated-8] [INFO] [1751217394.318031230] [robot1.nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_collision_monitor::CollisionMonitor>
[component_container_isolated-8] [INFO] [1751217394.328328436] [robot1.collision_monitor]:
[component_container_isolated-8]        collision_monitor lifecycle node launched.
[component_container_isolated-8]        Waiting on external lifecycle transitions to activate
[component_container_isolated-8]        See https://design.ros2.org/articles/node_lifecycle.html for more information.
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/robot1/collision_monitor' in container 'robot1/nav2_container'
[component_container_isolated-8] [INFO] [1751217394.509524228] [robot1.nav2_container]: Load Library: /home/edic/nav2_ws/install/opennav_docking/lib/libopennav_docking_core.so
[component_container_isolated-8] [INFO] [1751217394.517938678] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<opennav_docking::DockingServer>
[component_container_isolated-8] [INFO] [1751217394.517979665] [robot1.nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<opennav_docking::DockingServer>
[component_container_isolated-8] [INFO] [1751217394.528012961] [robot1.docking_server]:
[component_container_isolated-8]        docking_server lifecycle node launched.
[component_container_isolated-8]        Waiting on external lifecycle transitions to activate
[component_container_isolated-8]        See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-8] [INFO] [1751217394.528066407] [robot1.docking_server]: Creating docking_server
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/robot1/docking_server' in container 'robot1/nav2_container'
[component_container_isolated-8] [INFO] [1751217394.532738620] [robot1.nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_lifecycle_manager::LifecycleManager>
[component_container_isolated-8] [INFO] [1751217394.532772503] [robot1.nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_lifecycle_manager::LifecycleManager>
[component_container_isolated-8] [INFO] [1751217394.541798045] [robot1.lifecycle_manager_navigation]: Creating
[component_container_isolated-8] [INFO] [1751217394.542763097] [robot1.lifecycle_manager_navigation]: Creating and initializing lifecycle service clients
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/robot1/lifecycle_manager_navigation' in container 'robot1/nav2_container'
[component_container_isolated-8] [INFO] [1751217394.549073513] [robot1.lifecycle_manager_navigation]: Creating and initializing lifecycle service servers
[parameter_bridge-5] [INFO] [1751217394.709504617] [robot1.ros_gz_bridge]: Creating GZ->ROS Bridge: [/clock (gz.msgs.Clock) -> /clock (rosgraph_msgs/msg/Clock)] (Lazy 0)
[parameter_bridge-5] [INFO] [1751217394.712787252] [robot1.ros_gz_bridge]: Creating GZ->ROS Bridge: [/robot1/joint_states (gz.msgs.Model) -> joint_states (sensor_msgs/msg/JointState)] (Lazy 0)
[parameter_bridge-5] [INFO] [1751217394.715791990] [robot1.ros_gz_bridge]: Creating GZ->ROS Bridge: [/robot1/odom (gz.msgs.Odometry) -> odom (nav_msgs/msg/Odometry)] (Lazy 0)
[parameter_bridge-5] [INFO] [1751217394.717418153] [robot1.ros_gz_bridge]: Creating GZ->ROS Bridge: [/robot1/tf (gz.msgs.Pose_V) -> tf (tf2_msgs/msg/TFMessage)] (Lazy 0)
[parameter_bridge-5] [INFO] [1751217394.720188659] [robot1.ros_gz_bridge]: Creating GZ->ROS Bridge: [/robot1/imu (gz.msgs.IMU) -> imu (sensor_msgs/msg/Imu)] (Lazy 0)
[parameter_bridge-5] [INFO] [1751217394.720693876] [robot1.ros_gz_bridge]: Creating GZ->ROS Bridge: [/robot1/scan (gz.msgs.LaserScan) -> scan (sensor_msgs/msg/LaserScan)] (Lazy 0)
[parameter_bridge-5] [INFO] [1751217394.721280381] [robot1.ros_gz_bridge]: Creating ROS->GZ Bridge: [cmd_vel (geometry_msgs/msg/TwistStamped) -> /robot1/cmd_vel (gz.msgs.Twist)] (Lazy 0)
[create-6] [INFO] [1751217398.698427607] [robot1.ros_gz_sim]: Requesting list of world names.
[create-6] [INFO] [1751217403.698804288] [robot1.ros_gz_sim]: Requesting list of world names.
[create-6] [INFO] [1751217408.699101166] [robot1.ros_gz_sim]: Requesting list of world names.
[create-6] [INFO] [1751217413.699524383] [robot1.ros_gz_sim]: Requesting list of world names.
[create-6] [INFO] [1751217418.699735414] [robot1.ros_gz_sim]: Requesting list of world names.
[create-6] [INFO] [1751217423.700624119] [robot1.ros_gz_sim]: Requesting list of world names.
[create-6] [INFO] [1751217428.701289676] [robot1.ros_gz_sim]: Requesting list of world names.
[create-6] [INFO] [1751217433.702048194] [robot1.ros_gz_sim]: Requesting list of world names.
[create-6] [INFO] [1751217438.702325403] [robot1.ros_gz_sim]: Requesting list of world names.
[create-6] [INFO] [1751217443.702549827] [robot1.ros_gz_sim]: Requesting list of world names.
[create-6] [INFO] [1751217448.702864146] [robot1.ros_gz_sim]: Requesting list of world names.
[create-6] [INFO] [1751217453.703526502] [robot1.ros_gz_sim]: Requesting list of world names.
[create-6] [INFO] [1751217458.704236164] [robot1.ros_gz_sim]: Requesting list of world names.
[create-6] [INFO] [1751217463.704539074] [robot1.ros_gz_sim]: Requesting list of world names.

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions