-
Notifications
You must be signed in to change notification settings - Fork 135
Open
Labels
Description
Launching Two UR Arms in Gazebo with Separate Controllers
Objective
I want to launch two UR arms in Gazebo with separate controller managers. The expected behavior is that each arm operates independently, managed by its own controller manager.
Steps Overview
- Launch Two UR Arms in Gazebo (Current Focus)
- Integrate the MoveIt Interface (Next Step)
- Deploy on Physical Hardware (Final Step)
Specifications
ROS2 Jazzy
Ubuntu 24
Launch Files
ur_sim_control.launch.py
from launch import LaunchDescription
from launch.actions import (
DeclareLaunchArgument,
IncludeLaunchDescription,
OpaqueFunction,
RegisterEventHandler,
)
from launch.conditions import IfCondition, UnlessCondition
from launch.event_handlers import OnProcessExit
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import (
Command,
FindExecutable,
LaunchConfiguration,
PathJoinSubstitution,
IfElseSubstitution,
)
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from launch.substitutions import LaunchConfiguration, PythonExpression
def launch_setup(context, *args, **kwargs):
# Initialize Arguments
ur_type = LaunchConfiguration("ur_type")
safety_limits = LaunchConfiguration("safety_limits")
safety_pos_margin = LaunchConfiguration("safety_pos_margin")
safety_k_position = LaunchConfiguration("safety_k_position")
# General arguments
controller_file = LaunchConfiguration("controller_file")
tf_prefix = LaunchConfiguration("tf_prefix")
activate_joint_controller = LaunchConfiguration("activate_joint_controller")
controller_manager_name = LaunchConfiguration("controller_manager_name")
initial_joint_controller = LaunchConfiguration("initial_joint_controller")
description_file = LaunchConfiguration("description_file")
launch_rviz = LaunchConfiguration("launch_rviz")
rviz_config_file = LaunchConfiguration("rviz_config_file")
gazebo_gui = LaunchConfiguration("gazebo_gui")
world_file = LaunchConfiguration("world_file")
namespace = LaunchConfiguration("namespace")
x = LaunchConfiguration("x")
y = LaunchConfiguration("y")
z = LaunchConfiguration("z")
Y = LaunchConfiguration("Y")
robot_controllers = PathJoinSubstitution(
[
FindPackageShare("multi_robot_arm"),
"config", 'ur', 'ur5e',
controller_file,
]
)
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
description_file,
" ",
"safety_limits:=",
safety_limits,
" ",
"safety_pos_margin:=",
safety_pos_margin,
" ",
"safety_k_position:=",
safety_k_position,
" ",
"name:=",
"ur",
" ",
"ur_type:=",
ur_type,
" ",
"tf_prefix:=",
tf_prefix,
" ",
"simulation_controllers:=",
robot_controllers,
" ",
# "sim_gazebo:=",
# "true",
]
)
robot_description = {"robot_description": robot_description_content}
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
namespace=namespace,
parameters=[robot_controllers, robot_description],
output="both",
)
robot_state_publisher_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
namespace=namespace,
output="both",
parameters=[robot_description],
)
joint_state_broadcaster_spawner = Node(
package="controller_manager",
executable="spawner",
namespace=namespace,
arguments=["joint_state_broadcaster", "--controller-manager", controller_manager_name],
)
rviz_node = Node(
package="rviz2",
executable="rviz2",
name="rviz2",
output="log",
arguments=["-d", rviz_config_file],
condition=IfCondition(launch_rviz),
)
# Delay rviz start after `joint_state_broadcaster`
delay_rviz_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[rviz_node],
),
condition=IfCondition(launch_rviz),
)
# There may be other controllers of the joints, but this is the initially-started one
initial_joint_controller_spawner_started = Node(
package="controller_manager",
executable="spawner",
namespace=namespace,
arguments=[initial_joint_controller, "-c", controller_manager_name],
condition=IfCondition(activate_joint_controller),
)
initial_joint_controller_spawner_stopped = Node(
package="controller_manager",
executable="spawner",
namespace=namespace,
arguments=[initial_joint_controller, "-c", controller_manager_name, "--stopped"],
condition=UnlessCondition(activate_joint_controller),
)
# GZ nodes
gz_spawn_entity = Node(
package="ros_gz_sim",
executable="create",
namespace=namespace,
output="screen",
arguments=[
"-string",
robot_description_content,
# PythonExpression(["'/", namespace, "/robot_description'"]),
"-name",
namespace,
"-allow_renaming",
"true",
"-x", x,
"-y", y,
"-z", z,
"-Y", Y
],
)
# gz_launch_description = IncludeLaunchDescription(
# PythonLaunchDescriptionSource(
# [FindPackageShare("ros_gz_sim"), "/launch/gz_sim.launch.py"]
# ),
# launch_arguments={
# "gz_args": IfElseSubstitution(
# gazebo_gui,
# if_value=[" -r -v 4 ", world_file],
# else_value=[" -s -r -v 4 ", world_file],
# )
# }.items(),
# )
# # Make the /clock topic available in ROS
# gz_sim_bridge = Node(
# package="ros_gz_bridge",
# executable="parameter_bridge",
# arguments=[
# "/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock",
# ],
# output="screen",
# )
nodes_to_start = [
control_node,
robot_state_publisher_node,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
initial_joint_controller_spawner_stopped,
initial_joint_controller_spawner_started,
gz_spawn_entity,
# gz_launch_description,
# gz_sim_bridge,
]
return nodes_to_start
def generate_launch_description():
declared_arguments = []
# UR specific arguments
declared_arguments.append(
DeclareLaunchArgument(
"ur_type",
description="Type/series of used UR robot.",
choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20", "ur30"],
default_value="ur5e",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"safety_limits",
default_value="true",
description="Enables the safety limits controller if true.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"safety_pos_margin",
default_value="0.15",
description="The margin to lower and upper limits in the safety controller.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"safety_k_position",
default_value="20",
description="k-position factor in the safety controller.",
)
)
# General arguments
declared_arguments.append(
DeclareLaunchArgument(
"controller_file",
default_value="ur_multi_controllers.yaml",
description="Absolute path to YAML file with the controllers configuration.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"tf_prefix",
default_value='""',
description="Prefix of the joint names, useful for "
"multi-robot setup. If changed than also joint names in the controllers' configuration "
"have to be updated.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"activate_joint_controller",
default_value="true",
description="Enable headless mode for robot control",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"initial_joint_controller",
default_value="scaled_joint_trajectory_controller",
description="Robot controller to start.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"description_file",
default_value=PathJoinSubstitution(
[FindPackageShare("multi_robot_arm"), "urdf", "ur", "ur5e", "ur_gz.urdf.xacro"]
),
description="URDF/XACRO description file (absolute path) with the robot.",
)
)
declared_arguments.append(
DeclareLaunchArgument("launch_rviz", default_value="true", description="Launch RViz?")
)
declared_arguments.append(
DeclareLaunchArgument(
"rviz_config_file",
default_value=PathJoinSubstitution(
[FindPackageShare("ur_description"), "rviz", "view_robot.rviz"]
),
description="Rviz config file (absolute path) to use when launching rviz.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"gazebo_gui", default_value="true", description="Start gazebo with GUI?"
)
)
declared_arguments.append(
DeclareLaunchArgument(
"world_file",
default_value="empty.sdf",
description="Gazebo world file (absolute path or filename from the gazebosim worlds collection) containing a custom world.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"namespace",
default_value="",
description="Gazebo world file (absolute path or filename from the gazebosim worlds collection) containing a custom world.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"controller_manager_name",
default_value="controller_manager",
description="Gazebo world file (absolute path or filename from the gazebosim worlds collection) containing a custom world.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"x",
default_value="0.0",
description="Gazebo world file (absolute path or filename from the gazebosim worlds collection) containing a custom world.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"y",
default_value="0.0",
description="Gazebo world file (absolute path or filename from the gazebosim worlds collection) containing a custom world.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"z",
default_value="0.0",
description="Gazebo world file (absolute path or filename from the gazebosim worlds collection) containing a custom world.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"Y",
default_value="0.0",
description="Gazebo world file (absolute path or filename from the gazebosim worlds collection) containing a custom world.",
)
)
return LaunchDescription(declared_arguments + [OpaqueFunction(function=launch_setup)])
test_gazebo.launch.py
# Copyright 2021 Stogl Robotics Consulting UG (haftungsbeschränkt)
#
# 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.
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.conditions import IfCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution, ThisLaunchFileDir
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from launch import LaunchDescription
from launch.actions import (
DeclareLaunchArgument,
IncludeLaunchDescription,
OpaqueFunction,
RegisterEventHandler,
)
from launch.conditions import IfCondition, UnlessCondition
from launch.event_handlers import OnProcessExit
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import (
Command,
FindExecutable,
LaunchConfiguration,
PathJoinSubstitution,
IfElseSubstitution,
)
def generate_launch_description():
# Declare arguments
declared_arguments = []
declared_arguments.append(
DeclareLaunchArgument(
"ur_type",
description="Type/series of used UR robot.",
choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20", "ur30"],
default_value="ur5e",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"safety_limits",
default_value="true",
description="Enables the safety limits controller if true.",
)
)
# General arguments
declared_arguments.append(
DeclareLaunchArgument(
"controller_file",
default_value=PathJoinSubstitution(
[FindPackageShare("multi_robot_arm"), "config", "ur", "ur5e", "ur_multi_controllers.yaml"]
),
description="Absolute path to YAML file with the controllers configuration.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"description_file",
default_value=PathJoinSubstitution(
[FindPackageShare("multi_robot_arm"), "urdf", "ur", "ur5e", "ur_gz.urdf.xacro"]
),
description="URDF/XACRO description file (absolute path) with the robot.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"moveit_launch_file",
default_value=PathJoinSubstitution(
[
FindPackageShare("ur_moveit_config"),
"launch",
"ur_moveit.launch.py",
]
),
description="Absolute path for MoveIt launch file, part of a config package with robot SRDF/XACRO files. Usually the argument "
"is not set, it enables use of a custom moveit config.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"tf_prefix",
default_value='""',
description="Prefix of the joint names, useful for "
"multi-robot setup. If changed than also joint names in the controllers' configuration "
"have to be updated.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"controller_manager_name",
default_value="controller_manager",
description="Gazebo world file (absolute path or filename from the gazebosim worlds collection) containing a custom world.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"gazebo_gui", default_value="true", description="Start gazebo with GUI?"
)
)
# gazebo_launch = IncludeLaunchDescription(
# PythonLaunchDescriptionSource(
# [FindPackageShare("multi_robot_arm"), "/launch/gazebo.launch.py"]
# )
# )
# Initialize Arguments
ur_type = LaunchConfiguration("ur_type")
safety_limits = LaunchConfiguration("safety_limits")
# General arguments
controller_file = LaunchConfiguration("controller_file")
description_file = LaunchConfiguration("description_file")
moveit_launch_file = LaunchConfiguration("moveit_launch_file")
ur_control_launch_1 = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
PathJoinSubstitution(
[FindPackageShare("multi_robot_arm"), "launch", "ur_sim_control.launch.py"]
)
),
launch_arguments={
"ur_type": ur_type,
"safety_limits": safety_limits,
"description_file": description_file,
"launch_rviz": "true",
"namespace": "ur1",
"tf_prefix": "ur1_",
"controller_manager_name": "/ur1/controller_manager",
"controller_file": "ur_multi_controllers.yaml",
"x": "0.0",
"y": "0.0",
"z": "0.0",
"Y": "0.0",
}.items(),
)
ur_control_launch_2 = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
PathJoinSubstitution(
[FindPackageShare("multi_robot_arm"), "launch", "ur_sim_control.launch.py"]
)
),
launch_arguments={
"ur_type": ur_type,
"safety_limits": safety_limits,
"description_file": description_file,
"launch_rviz": "true",
"namespace": "ur2",
"tf_prefix": "ur2_",
"controller_manager_name": "/ur2/controller_manager",
"controller_file": "ur_multi_controllers.yaml",
"x": "1.0",
"y": "0.0",
"z": "0.0",
"Y": "0.0",
}.items(),
)
# rrbot_1_launch = IncludeLaunchDescription(
# PythonLaunchDescriptionSource([ThisLaunchFileDir(), "/rrbot_base.launch.py"]),
# launch_arguments={
# "namespace": "rrbot_1",
# "description_package": "ros2_control_demo_example_1",
# "description_file": "rrbot.urdf.xacro",
# "runtime_config_package": "ros2_control_demo_example_15",
# "controller_file": "multi_controller_manager_rrbot_generic_controllers.yaml",
# "prefix": "rrbot_1_",
# "use_mock_hardware": use_mock_hardware,
# "mock_sensor_commands": mock_sensor_commands,
# "slowdown": slowdown,
# "controller_manager_name": "/rrbot_1/controller_manager",
# "robot_controller": robot_controller,
# "start_rviz": "false",
# }.items(),
# )
# rrbot_1_position_trajectory_controller_spawner = Node(
# package="controller_manager",
# executable="spawner",
# namespace="rrbot_1",
# arguments=[
# "position_trajectory_controller",
# "--inactive",
# "--param-file",
# PathJoinSubstitution(
# [
# FindPackageShare("ros2_control_demo_example_15"),
# "config",
# "multi_controller_manager_rrbot_generic_controllers.yaml",
# ]
# ),
# ],
# )
# rrbot_2_launch = IncludeLaunchDescription(
# PythonLaunchDescriptionSource([ThisLaunchFileDir(), "/rrbot_base.launch.py"]),
# launch_arguments={
# "namespace": "rrbot_2",
# "description_package": "ros2_control_demo_example_5",
# "description_file": "rrbot_system_with_external_sensor.urdf.xacro",
# "runtime_config_package": "ros2_control_demo_example_15",
# "controller_file": "multi_controller_manager_rrbot_generic_controllers.yaml",
# "prefix": "rrbot_2_",
# "use_mock_hardware": use_mock_hardware,
# "mock_sensor_commands": mock_sensor_commands,
# "slowdown": slowdown,
# "controller_manager_name": "/rrbot_2/controller_manager",
# "robot_controller": robot_controller,
# "start_rviz": "false",
# }.items(),
# )
# rrbot_2_position_trajectory_controller_spawner = Node(
# package="controller_manager",
# executable="spawner",
# namespace="rrbot_2",
# arguments=[
# "position_trajectory_controller",
# "--inactive",
# "--param-file",
# PathJoinSubstitution(
# [
# FindPackageShare("ros2_control_demo_example_15"),
# "config",
# "multi_controller_manager_rrbot_generic_controllers.yaml",
# ]
# ),
# ],
# )
# rviz_config_file = PathJoinSubstitution(
# [FindPackageShare("ros2_control_demo_example_15"), "rviz", "multi_controller_manager.rviz"]
# )
# rviz_node_multi = Node(
# package="rviz2",
# executable="rviz2",
# name="rviz2_multi",
# output="log",
# arguments=["-d", rviz_config_file],
# condition=IfCondition(start_rviz_lc),
# )
gazebo_gui = LaunchConfiguration("gazebo_gui")
gz_launch_description = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[FindPackageShare("ros_gz_sim"), "/launch/gz_sim.launch.py"]
),
launch_arguments={
"gz_args": IfElseSubstitution(
gazebo_gui,
if_value=[" -r -v 4 ", "empty.sdf"],
else_value=[" -s -r -v 4 ", "empty.sdf"],
)
}.items(),
)
# Make the /clock topic available in ROS
gz_sim_bridge = Node(
package="ros_gz_bridge",
executable="parameter_bridge",
arguments=[
"/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock",
],
output="screen",
)
included_launch_files = [
# gazebo_launch,
ur_control_launch_1,
ur_control_launch_2,
gz_launch_description,
gz_sim_bridge,
]
# nodes_to_start = [
# rrbot_1_position_trajectory_controller_spawner,
# rrbot_2_position_trajectory_controller_spawner,
# rviz_node_multi,
# ]
return LaunchDescription(declared_arguments + included_launch_files)
Log result of launching test_gazebo.launch.py
[INFO] [launch]: All log files can be found below /home/lee/.ros/log/2025-01-29-16-27-52-962277-lee-XPS-15-9520-22951
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_control_node-1]: process started with pid [22971]
[INFO] [robot_state_publisher-2]: process started with pid [22972]
[INFO] [spawner-3]: process started with pid [22973]
[INFO] [spawner-4]: process started with pid [22974]
[INFO] [create-5]: process started with pid [22975]
[INFO] [ros2_control_node-6]: process started with pid [22976]
[INFO] [robot_state_publisher-7]: process started with pid [22977]
[INFO] [spawner-8]: process started with pid [22978]
[INFO] [spawner-9]: process started with pid [22979]
[INFO] [create-10]: process started with pid [22980]
[INFO] [gazebo-11]: process started with pid [22981]
[INFO] [parameter_bridge-12]: process started with pid [22982]
[create-5] [INFO] [1738189673.800643785] [ur1.ros_gz_sim]: Requesting list of world names.
[robot_state_publisher-2] [INFO] [1738189673.800749975] [ur1.robot_state_publisher]: Robot initialized
[robot_state_publisher-7] [INFO] [1738189673.804692035] [ur2.robot_state_publisher]: Robot initialized
[ros2_control_node-1] [INFO] [1738189673.805877046] [ur1.controller_manager]: Subscribing to '/ur1/robot_description' topic for robot description.
[ros2_control_node-1] [INFO] [1738189673.806045532] [ur1.controller_manager]: update rate is 500 Hz
[ros2_control_node-1] [INFO] [1738189673.806059292] [ur1.controller_manager]: Spawning controller_manager RT thread with scheduler priority: 50
[ros2_control_node-1] [WARN] [1738189673.806158808] [ur1.controller_manager]: Could not enable FIFO RT scheduling policy: with error number <1>(Operation not permitted). See [https://control.ros.org/master/doc/ros2_control/controller_manager/doc/userdoc.html] for details on how to enable realtime scheduling.
[ros2_control_node-6] [INFO] [1738189673.806488635] [ur2.controller_manager]: Subscribing to '/ur2/robot_description' topic for robot description.
[ros2_control_node-6] [INFO] [1738189673.806635513] [ur2.controller_manager]: update rate is 500 Hz
[ros2_control_node-6] [INFO] [1738189673.806649848] [ur2.controller_manager]: Spawning controller_manager RT thread with scheduler priority: 50
[ros2_control_node-6] [WARN] [1738189673.806723453] [ur2.controller_manager]: Could not enable FIFO RT scheduling policy: with error number <1>(Operation not permitted). See [https://control.ros.org/master/doc/ros2_control/controller_manager/doc/userdoc.html] for details on how to enable realtime scheduling.
[create-10] [INFO] [1738189673.810662023] [ur2.ros_gz_sim]: Requesting list of world names.
[parameter_bridge-12] [INFO] [1738189673.813913625] [ros_gz_bridge]: Creating GZ->ROS Bridge: [/clock (gz.msgs.Clock) -> /clock (rosgraph_msgs/msg/Clock)] (Lazy 0)
[ros2_control_node-1] [INFO] [1738189673.816535393] [ur1.controller_manager]: Received robot description from topic.
[ros2_control_node-6] [INFO] [1738189673.817095904] [ur2.controller_manager]: Received robot description from topic.
[ros2_control_node-1] [INFO] [1738189673.819229008] [ur1.controller_manager.resource_manager]: Loading hardware 'ur'
[ros2_control_node-1] [ERROR] [1738189673.819283059] [ur1.controller_manager.resource_manager]: Caught exception of type : N9pluginlib20LibraryLoadExceptionE while loading hardware: According to the loaded plugin descriptions the class gz_ros2_control/GazeboSimSystem with base class type hardware_interface::SystemInterface does not exist. Declared types are mock_components/GenericSystem ur_robot_driver/URPositionHardwareInterface
[ros2_control_node-1] [WARN] [1738189673.819327653] [ur1.controller_manager]: Could not load and initialize hardware. Please check previous output for more details. After you have corrected your URDF, try to publish robot description again.
[ros2_control_node-6] [INFO] [1738189673.819368457] [ur2.controller_manager.resource_manager]: Loading hardware 'ur'
[ros2_control_node-6] [ERROR] [1738189673.819404608] [ur2.controller_manager.resource_manager]: Caught exception of type : N9pluginlib20LibraryLoadExceptionE while loading hardware: According to the loaded plugin descriptions the class gz_ros2_control/GazeboSimSystem with base class type hardware_interface::SystemInterface does not exist. Declared types are mock_components/GenericSystem ur_robot_driver/URPositionHardwareInterface
[ros2_control_node-6] [WARN] [1738189673.819430464] [ur2.controller_manager]: Could not load and initialize hardware. Please check previous output for more details. After you have corrected your URDF, try to publish robot description again.
[spawner-8] [INFO] [1738189674.055953854] [ur2.spawner_joint_state_broadcaster]: waiting for service /ur2/controller_manager/list_controllers to become available...
[spawner-4] [INFO] [1738189674.058499265] [ur1.spawner_scaled_joint_trajectory_controller]: waiting for service /ur1/controller_manager/list_controllers to become available...
[spawner-9] [INFO] [1738189674.070257028] [ur2.spawner_scaled_joint_trajectory_controller]: waiting for service /ur2/controller_manager/list_controllers to become available...
[spawner-3] [INFO] [1738189674.070728763] [ur1.spawner_joint_state_broadcaster]: waiting for service /ur1/controller_manager/list_controllers to become available...
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:413:17: QML ToolButton: Binding loop detected for property "implicitHeight"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:309:21: QML Button: Binding loop detected for property "implicitHeight"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:309:21: QML Button: Binding loop detected for property "implicitHeight"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:413:17: QML ToolButton: Binding loop detected for property "implicitHeight"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:309:21: QML Button: Binding loop detected for property "implicitHeight"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:309:21: QML Button: Binding loop detected for property "implicitHeight"
[gazebo-11] [Dbg] [gz.cc:166] Subscribing to [/gazebo/starting_world].
[gazebo-11] [Dbg] [gz.cc:168] Waiting for a world to be set from the GUI...
[gazebo-11] [Msg] Received world [empty.sdf] from the GUI.
[gazebo-11] [Dbg] [gz.cc:172] Unsubscribing from [/gazebo/starting_world].
[gazebo-11] [Msg] Gazebo Sim Server v8.8.0
[gazebo-11] [Msg] Loading SDF world file[/opt/ros/jazzy/opt/gz_sim_vendor/share/gz/gz-sim8/worlds/empty.sdf].
[gazebo-11] [Msg] Serving entity system service on [/entity/system/add]
[gazebo-11] [Dbg] [Physics.cc:871] Loaded [gz::physics::dartsim::Plugin] from library [/opt/ros/jazzy/opt/gz_physics_vendor/lib/gz-physics-7/engine-plugins/libgz-physics-dartsim-plugin.so]
[gazebo-11] [Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::Physics] for entity [1]
[gazebo-11] [Msg] Create service on [/world/empty/create]
[gazebo-11] [Msg] Remove service on [/world/empty/remove]
[gazebo-11] [Msg] Pose service on [/world/empty/set_pose]
[gazebo-11] [Msg] Pose service on [/world/empty/set_pose_vector]
[gazebo-11] [Msg] Light configuration service on [/world/empty/light_config]
[gazebo-11] [Msg] Physics service on [/world/empty/set_physics]
[gazebo-11] [Msg] SphericalCoordinates service on [/world/empty/set_spherical_coordinates]
[gazebo-11] [Msg] Enable collision service on [/world/empty/enable_collision]
[gazebo-11] [Msg] Disable collision service on [/world/empty/disable_collision]
[gazebo-11] [Msg] Material service on [/world/empty/visual_config]
[gazebo-11] [Msg] Material service on [/world/empty/wheel_slip]
[gazebo-11] [Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::UserCommands] for entity [1]
[gazebo-11] [Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::SceneBroadcaster] for entity [1]
[gazebo-11] [Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::Contact] for entity [1]
[gazebo-11] [Msg] Loaded level [default]
[gazebo-11] [Msg] Serving world controls on [/world/empty/control], [/world/empty/control/state] and [/world/empty/playback/control]
[gazebo-11] [Msg] Serving GUI information on [/world/empty/gui/info]
[gazebo-11] [Msg] World [empty] initialized with [1ms] physics profile.
[gazebo-11] [Msg] Serving world SDF generation service on [/world/empty/generate_world_sdf]
[gazebo-11] [Msg] Serving world names on [/gazebo/worlds]
[gazebo-11] [Msg] Resource path add service on [/gazebo/resource_paths/add].
[gazebo-11] [Msg] Resource path get service on [/gazebo/resource_paths/get].
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:413:17: QML ToolButton: Binding loop detected for property "implicitHeight"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:309:21: QML Button: Binding loop detected for property "implicitHeight"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:309:21: QML Button: Binding loop detected for property "implicitHeight"
[create-10] [INFO] [1738189674.534787470] [ur2.ros_gz_sim]: Entity creation successfull.
[create-5] [INFO] [1738189674.534872098] [ur1.ros_gz_sim]: Entity creation successfull.
[INFO] [create-10]: process has finished cleanly [pid 22980]
[INFO] [create-5]: process has finished cleanly [pid 22975]
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:52:3: QML RenderWindowOverlay: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:67:3: QML EntityContextMenu: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:52:3: QML RenderWindowOverlay: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:67:3: QML EntityContextMenu: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:52:3: QML RenderWindowOverlay: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:67:3: QML EntityContextMenu: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:52:3: QML RenderWindowOverlay: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:67:3: QML EntityContextMenu: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:52:3: QML RenderWindowOverlay: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:67:3: QML EntityContextMenu: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:52:3: QML RenderWindowOverlay: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:67:3: QML EntityContextMenu: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [Msg] Resource path resolve service on [/gazebo/resource_paths/resolve[Msg] Gazebo Sim GUI v8.8.0
[gazebo-11] [Msg] Detected Wayland. Setting Qt to use the xcb plugin: 'QT_QPA_PLATFORM=xcb'.
[gazebo-11] [Dbg] [Gui.cc:275] Waiting for subscribers to [/gazebo/starting_world]...
[gazebo-11] [Dbg] [Application.cc:96] Initializing application.
[gazebo-11] [Dbg] [Application.cc:170] Qt using OpenGL graphics interface
[gazebo-11] [GUI] [Dbg] [Application.cc:657] Create main window
[gazebo-11] [GUI] [Dbg] [PathManager.cc:68] Requesting resource paths through [/gazebo/resource_paths/get]
[gazebo-11] [GUI] [Dbg] [Gui.cc:355] GUI requesting list of world names. The server may be busy downloading resources. Please be patient.
[gazebo-11] [GUI] [Dbg] [PathManager.cc:57] Received resource paths.
[gazebo-11] [GUI] [Dbg] [Gui.cc:413] Requesting GUI from [/world/empty/gui/info]...
[gazebo-11] [GUI] [Dbg] [GuiRunner.cc:149] Requesting initial state from [/world/empty/state]...
[gazebo-11] [GUI] [Msg] Loading config [/home/lee/.gz/sim/8/gui.config]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [MinimalScene]
[gazebo-11] [GUI] [Dbg] [MinimalScene.cc:802] Creating gz-rendering interface for OpenGL
[gazebo-11] [GUI] [Dbg] [MinimalScene.cc:802] Creating gz-rendering interface for OpenGL
[gazebo-11] [GUI] [Dbg] [MinimalScene.cc:986] Creating render thread interface for OpenGL
[gazebo-11] [GUI] [Dbg] [MinimalScene.cc:802] Creating gz-rendering interface for OpenGL
[gazebo-11] [GUI] [Dbg] [MinimalScene.cc:986] Creating render thread interface for OpenGL
[gazebo-11] [GUI] [Msg] Added plugin [3D View] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [MinimalScene] from path [/opt/ros/jazzy/opt/gz_gui_vendor/lib/gz-gui-8/plugins/libMinimalScene.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [EntityContextMenuPlugin]
[gazebo-11] [GUI] [Msg] Currently tracking topic on [/gui/currently_tracked]
[gazebo-11] [GUI] [Msg] Added plugin [Entity Context Menu] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [EntityContextMenuPlugin] from path [/opt/ros/jazzy/opt/gz_sim_vendor/lib/gz-sim-8/plugins/gui/libEntityContextMenuPlugin.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [GzSceneManager]
[gazebo-11] [GUI] [Msg] Added plugin [Scene Manager] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [GzSceneManager] from path [/opt/ros/jazzy/opt/gz_sim_vendor/lib/gz-sim-8/plugins/gui/libGzSceneManager.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [InteractiveViewControl]
[gazebo-11] [GUI] [Msg] Camera view controller topic advertised on [/gui/camera/view_control]
[gazebo-11] [GUI] [Msg] Camera reference visual topic advertised on [/gui/camera/view_control/reference_visual]
[gazebo-11] [GUI] [Msg] Camera view control sensitivity advertised on [/gui/camera/view_control/sensitivity]
[ros2_control_node-1] [WARN] [1738189674.805261322] [ur1.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-6] [WARN] [1738189674.806080893] [ur2.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [GUI] [Msg] Added plugin [Interactive view control] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [InteractiveViewControl] from path [/opt/ros/jazzy/opt/gz_gui_vendor/lib/gz-gui-8/plugins/libInteractiveViewControl.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [CameraTracking]
[gazebo-11] [GUI] [Msg] Added plugin [Camera tracking] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [CameraTracking] from path [/opt/ros/jazzy/opt/gz_gui_vendor/lib/gz-gui-8/plugins/libCameraTracking.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [MarkerManager]
[gazebo-11] [GUI] [Msg] Listening to stats on [/world/empty/stats]
[gazebo-11] [GUI] [Msg] Added plugin [Marker Manager] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [MarkerManager] from path [/opt/ros/jazzy/opt/gz_gui_vendor/lib/gz-gui-8/plugins/libMarkerManager.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [SelectEntities]
[gazebo-11] [GUI] [Msg] Added plugin [Select entities] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [SelectEntities] from path [/opt/ros/jazzy/opt/gz_sim_vendor/lib/gz-sim-8/plugins/gui/libSelectEntities.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [Spawn]
[gazebo-11] [GUI] [Msg] Added plugin [Spawn] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [Spawn] from path [/opt/ros/jazzy/opt/gz_sim_vendor/lib/gz-sim-8/plugins/gui/libSpawn.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [VisualizationCapabilities]
[gazebo-11] [GUI] [Msg] View as transparent service on [/gui/view/transparent]
[gazebo-11] [GUI] [Msg] View as wireframes service on [/gui/view/wireframes]
[gazebo-11] [GUI] [Msg] View center of mass service on [/gui/view/com]
[gazebo-11] [GUI] [Msg] View inertia service on [/gui/view/inertia]
[gazebo-11] [GUI] [Msg] View collisions service on [/gui/view/collisions]
[gazebo-11] [GUI] [Msg] View joints service on [/gui/view/joints]
[gazebo-11] [GUI] [Msg] View frames service on [/gui/view/frames]
[gazebo-11] [GUI] [Msg] Added plugin [Visualization capabilities] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [VisualizationCapabilities] from path [/opt/ros/jazzy/opt/gz_sim_vendor/lib/gz-sim-8/plugins/gui/libVisualizationCapabilities.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [WorldControl]
[gazebo-11] [GUI] [Msg] Using world control service [/world/empty/control]
[gazebo-11] [GUI] [Msg] Listening to stats on [/world/empty/stats]
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:413:17: QML ToolButton: Binding loop detected for property "implicitHeight"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:309:21: QML Button: Binding loop detected for property "implicitHeight"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:309:21: QML Button: Binding loop detected for property "implicitHeight"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/ComponentInspector/ComponentInspector.qml:251:3: QML Dialog: Binding loop detected for property "implicitHeight"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:413:17: QML ToolButton: Binding loop detected for property "implicitHeight"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:309:21: QML Button: Binding loop detected for property "implicitHeight"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file:///usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:309:21: QML Button: Binding loop detected for property "implicitHeight"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityTree/EntityTree.qml:148:7: QML ToolButton: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [GUI] [Dbg] [WorldControl.cc:237] Using an event to share WorldControl msgs with the server
[gazebo-11] [GUI] [Msg] Added plugin [World control] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [WorldControl] from path [/opt/ros/jazzy/opt/gz_gui_vendor/lib/gz-gui-8/plugins/libWorldControl.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [WorldStats]
[gazebo-11] [GUI] [Msg] Listening to stats on [/world/empty/stats]
[gazebo-11] [GUI] [Msg] Added plugin [World stats] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [WorldStats] from path [/opt/ros/jazzy/opt/gz_gui_vendor/lib/gz-gui-8/plugins/libWorldStats.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [Shapes]
[gazebo-11] [GUI] [Msg] Added plugin [Shapes] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [Shapes] from path [/opt/ros/jazzy/opt/gz_sim_vendor/lib/gz-sim-8/plugins/gui/libShapes.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [Lights]
[gazebo-11] [GUI] [Msg] Added plugin [Lights] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [Lights] from path [/opt/ros/jazzy/opt/gz_sim_vendor/lib/gz-sim-8/plugins/gui/libLights.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [TransformControl]
[gazebo-11] [GUI] [Msg] Added plugin [Transform control] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [TransformControl] from path [/opt/ros/jazzy/opt/gz_sim_vendor/lib/gz-sim-8/plugins/gui/libTransformControl.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [Screenshot]
[gazebo-11] [GUI] [Msg] Screenshot service on [/gui/screenshot]
[gazebo-11] [GUI] [Msg] Added plugin [Screenshot] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [Screenshot] from path [/opt/ros/jazzy/opt/gz_gui_vendor/lib/gz-gui-8/plugins/libScreenshot.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [CopyPaste]
[gazebo-11] [GUI] [Msg] Added plugin [Copy/Paste] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [CopyPaste] from path [/opt/ros/jazzy/opt/gz_sim_vendor/lib/gz-sim-8/plugins/gui/libCopyPaste.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [ComponentInspector]
[gazebo-11] [GUI] [Msg] Added plugin [Component inspector] to main window
[gazebo-11] [GUI] [Msg] Loaded plugin [ComponentInspector] from path [/opt/ros/jazzy/opt/gz_sim_vendor/lib/gz-sim-8/plugins/gui/libComponentInspector.so]
[gazebo-11] [GUI] [Dbg] [Application.cc:528] Loading plugin [EntityTree]
[gazebo-11] [GUI] [Msg] Currently tracking topic on [/gui/currently_tracked]
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityTree/EntityTree.qml:148:7: QML ToolButton: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/WorldStats/WorldStats.qml:53:3: QML RowLayout: Binding loop detected for property "x"
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:52:3: QML RenderWindowOverlay: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[gazebo-11] [GUI] [Wrn] [Application.cc:908] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:67:3: QML EntityContextMenu: Detected anchors on an item that is managed by a layout. This is undefined behavior; use Layout.alignment instead.
[ros2_control_node-1] [WARN] [1738189675.805255509] [ur1.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-6] [WARN] [1738189675.805992594] [ur2.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [INFO] [1738189676.347011066] [gz_ros_control]: [gz_ros2_control] Fixed joint [ur2_base_joint] (Entity=32)] is skipped
[gazebo-11] [INFO] [1738189676.347517654] [gz_ros_control]: Loading controller_manager
[gazebo-11] [INFO] [1738189676.356866052] [controller_manager]: Subscribing to '/robot_description' topic for robot description.
[gazebo-11] [WARN] [1738189676.356988653] [gz_ros_control]: Waiting RM to load and initialize hardware...
[ros2_control_node-1] [WARN] [1738189676.805144949] [ur1.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-6] [WARN] [1738189676.806046482] [ur2.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [WARN] [1738189677.356570939] [controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-1] [WARN] [1738189677.805199766] [ur1.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-6] [WARN] [1738189677.806036819] [ur2.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [WARN] [1738189678.356722896] [controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [WARN] [1738189678.357204998] [gz_ros_control]: Waiting RM to load and initialize hardware...
[ros2_control_node-1] [WARN] [1738189678.805145607] [ur1.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-6] [WARN] [1738189678.806133012] [ur2.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [WARN] [1738189679.356570697] [controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-1] [WARN] [1738189679.805168615] [ur1.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-6] [WARN] [1738189679.806043721] [ur2.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [WARN] [1738189680.356592488] [controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [WARN] [1738189680.357514285] [gz_ros_control]: Waiting RM to load and initialize hardware...
[ros2_control_node-1] [WARN] [1738189680.805150932] [ur1.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-6] [WARN] [1738189680.806115775] [ur2.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [GUI] [Msg] 0m].
[gazebo-11] [Msg] Resource paths published on [/gazebo/resource_paths].
[gazebo-11] [Msg] Server control service on [/server_control].
[gazebo-11] [Msg] Found no publishers on /stats, adding root stats topic
[gazebo-11] [Msg] Found no publishers on /clock, adding root clock topic
[gazebo-11] [Dbg] [SimulationRunner.cc:533] Creating PostUpdate worker threads: 3
[gazebo-11] [Dbg] [SimulationRunner.cc:544] Creating postupdate worker thread (0)
[gazebo-11] [Dbg] [SimulationRunner.cc:544] Creating postupdate worker thread (1)
[gazebo-11] [WARN] [1738189681.356738824] [controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-1] [WARN] [1738189681.805094196] [ur1.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-6] [WARN] [1738189681.806092175] [ur2.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [WARN] [1738189682.356742968] [controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [WARN] [1738189682.357693942] [gz_ros_control]: Waiting RM to load and initialize hardware...
[ros2_control_node-1] [WARN] [1738189682.805208323] [ur1.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-6] [WARN] [1738189682.806309366] [ur2.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [WARN] [1738189683.356735285] [controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-1] [WARN] [1738189683.805360591] [ur1.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-6] [WARN] [1738189683.806341961] [ur2.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[spawner-8] [WARN] [1738189684.067779401] [ur2.spawner_joint_state_broadcaster]: Could not contact service /ur2/controller_manager/list_controllers
[spawner-8] [INFO] [1738189684.068945377] [ur2.spawner_joint_state_broadcaster]: waiting for service /ur2/controller_manager/list_controllers to become available...
[spawner-4] [WARN] [1738189684.070417920] [ur1.spawner_scaled_joint_trajectory_controller]: Could not contact service /ur1/controller_manager/list_controllers
[spawner-4] [INFO] [1738189684.071227625] [ur1.spawner_scaled_joint_trajectory_controller]: waiting for service /ur1/controller_manager/list_controllers to become available...
[spawner-3] [WARN] [1738189684.079436654] [ur1.spawner_joint_state_broadcaster]: Could not contact service /ur1/controller_manager/list_controllers
[spawner-3] [INFO] [1738189684.079663861] [ur1.spawner_joint_state_broadcaster]: waiting for service /ur1/controller_manager/list_controllers to become available...
[spawner-9] [WARN] [1738189684.079688990] [ur2.spawner_scaled_joint_trajectory_controller]: Could not contact service /ur2/controller_manager/list_controllers
[spawner-9] [INFO] [1738189684.079863493] [ur2.spawner_scaled_joint_trajectory_controller]: waiting for service /ur2/controller_manager/list_controllers to become available...
[gazebo-11] [WARN] [1738189684.356755867] [controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [WARN] [1738189684.357958367] [gz_ros_control]: Waiting RM to load and initialize hardware...
[ros2_control_node-1] [WARN] [1738189684.805254461] [ur1.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-6] [WARN] [1738189684.806338577] [ur2.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [WARN] [1738189685.356751242] [controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-1] [WARN] [1738189685.805195614] [ur1.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-6] [WARN] [1738189685.806131753] [ur2.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [WARN] [1738189686.356939237] [controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [WARN] [1738189686.358347284] [gz_ros_control]: Waiting RM to load and initialize hardware...
[ros2_control_node-1] [WARN] [1738189686.805151914] [ur1.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[ros2_control_node-6] [WARN] [1738189686.806240723] [ur2.controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
[gazebo-11] [WARN] [1738189687.356987524] [controller_manager]: Waiting for data on 'robot_description' topic to finish initialization
^C[WARNING] [launch]: user interrupted with ctrl-c (SIGINT)
Thank you in advance!
kbrameld and vdovetzi