UniversalRobots / Universal_Robots_ROS2_GZ_Simulation

BSD 3-Clause "New" or "Revised" License
24 stars 13 forks source link

Joint initial position not respected #14

Closed mrjogo closed 5 months ago

mrjogo commented 8 months ago

The UR URDF with ros2_control in simulation does not seem to be respecting the position initial values. Specifically:

<state_interface name="position">
  <param name="initial_value">0.785</param>
</state_interface>

for all joints still results in starting at 0.0.

I'm running Humble with Gazebo Fortress.

I ran https://github.com/ros-controls/gz_ros2_control/blob/humble/ign_ros2_control_demos/launch/gripper_mimic_joint_example.launch.py and the initial_value worked, so it seems to be something specific to the UR simulation.

Here is a self-contained launchfile to reproduce (the ur_description and ur_simulation_ignition paths will have to be updated for your workspace):

from launch import LaunchDescription
from launch.actions import (
    IncludeLaunchDescription,
    OpaqueFunction,
)
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare

def launch_setup(context, *args, **kwargs):
    robot_description_content = """
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from /home/ruddick/dev_ws/install/barbot_description/share/barbot_description/urdf/barbot.urdf.xacro | -->
<!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
<!-- =================================================================================== -->
<robot name="ur">  <!-- Base UR robot series xacro macro.

  NOTE this is NOT a URDF. It cannot directly be loaded by consumers expecting a flattened ''.urdf'' file. See the top-level ''.xacro'' for that (but note that .xacro must still be processed by the xacro command).

  This file models the base kinematic chain of a UR robot, which then gets parameterised by various configuration files to convert it into a UR3(e), UR5(e), UR10(e) or UR16e.

  NOTE the default kinematic parameters (i.e., link lengths, frame locations, offsets, etc) do not correspond to any particular robot. They are defaults only. There WILL be non-zero offsets between the Forward Kinematics results in TF (i.e., robot_state_publisher) and the values reported by the Teach Pendant.

  For accurate (and robot-specific) transforms, the ''kinematics_parameters_file'' parameter MUST point to a .yaml file containing the appropriate values for the targeted robot.

  If using the UniversalRobots/Universal_Robots_ROS_Driver, follow the steps described in the readme of that repository to extract the kinematic calibration from the controller and generate the required .yaml file.

  Main author of the migration to yaml configs Ludovic Delval.

  Contributors to previous versions (in no particular order)

  - Denis Stogl - Lovro Ivanov - Felix Messmer - Kelsey Hawkins - Wim Meeussen - Shaun Edwards - Nadia Hammoudeh Garcia - Dave Hershberger - G. vd. Hoorn - Philip Long - Dave Coleman - Miguel Prada - Mathias Luedtke - Marcel Schnirring - Felix von Drigalski - Felix Exner - Jimmy Da Silva - Ajit Krisshna N L - Muhammad Asif Rana -->
  <!-- NOTE the macro defined in this file is NOT part of the public API of this package. Users CANNOT rely on this file being available, or stored in this location. Nor can they rely on the existence of the macro. -->
  <!-- create link fixed to the "world" -->
  <link name="world"/>
  <ros2_control name="ur" type="system">
    <hardware>
      <plugin>ign_ros2_control/IgnitionSystem</plugin>
    </hardware>
    <joint name="shoulder_pan_joint">
      <command_interface name="position">
        <param name="min">{-2*pi}</param>
        <param name="max">{2*pi}</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.15</param>
        <param name="max">3.15</param>
      </command_interface>
      <state_interface name="position">        <!-- initial position for the FakeSystem and simulation -->
        <param name="initial_value">0.0</param>
      </state_interface>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="shoulder_lift_joint">
      <command_interface name="position">
        <param name="min">{-2*pi}</param>
        <param name="max">{2*pi}</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.15</param>
        <param name="max">3.15</param>
      </command_interface>
      <state_interface name="position">        <!-- initial position for the FakeSystem and simulation -->
        <param name="initial_value">-0.785</param>
      </state_interface>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="elbow_joint">
      <command_interface name="position">
        <param name="min">{-pi}</param>
        <param name="max">{pi}</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.15</param>
        <param name="max">3.15</param>
      </command_interface>
      <state_interface name="position">        <!-- initial position for the FakeSystem and simulation -->
        <param name="initial_value">0.785</param>
      </state_interface>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="wrist_1_joint">
      <command_interface name="position">
        <param name="min">{-2*pi}</param>
        <param name="max">{2*pi}</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.2</param>
        <param name="max">3.2</param>
      </command_interface>
      <state_interface name="position">        <!-- initial position for the FakeSystem and simulation -->
        <param name="initial_value">0.0</param>
      </state_interface>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="wrist_2_joint">
      <command_interface name="position">
        <param name="min">{-2*pi}</param>
        <param name="max">{2*pi}</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.2</param>
        <param name="max">3.2</param>
      </command_interface>
      <state_interface name="position">        <!-- initial position for the FakeSystem and simulation -->
        <param name="initial_value">1.57</param>
      </state_interface>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="wrist_3_joint">
      <command_interface name="position">
        <param name="min">{-2*pi}</param>
        <param name="max">{2*pi}</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.2</param>
        <param name="max">3.2</param>
      </command_interface>
      <state_interface name="position">        <!-- initial position for the FakeSystem and simulation -->
        <param name="initial_value">0.0</param>
      </state_interface>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
  </ros2_control>  <!-- Add URDF transmission elements (for ros_control) -->  <!--<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />-->  <!-- Placeholder for ros2_control transmission which don''t yet exist -->  <!-- links -  main serial chain -->
  <link name="base_link"/>
  <link name="base_link_inertia">
    <visual>
      <origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
      <geometry>
        <mesh filename="file:///home/ruddick/prebuilt_ws/install/ur_description/share/ur_description/meshes/ur5e/visual/base.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
      <geometry>
        <mesh filename="file:///home/ruddick/prebuilt_ws/install/ur_description/share/ur_description/meshes/ur5e/collision/base.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="4.0"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/>
    </inertial>
  </link>
  <link name="shoulder_link">
    <visual>
      <origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
      <geometry>
        <mesh filename="file:///home/ruddick/prebuilt_ws/install/ur_description/share/ur_description/meshes/ur5e/visual/shoulder.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
      <geometry>
        <mesh filename="file:///home/ruddick/prebuilt_ws/install/ur_description/share/ur_description/meshes/ur5e/collision/shoulder.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="3.7"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.010267495893" ixy="0.0" ixz="0.0" iyy="0.010267495893" iyz="0.0" izz="0.00666"/>
    </inertial>
  </link>
  <link name="upper_arm_link">
    <visual>
      <origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.138"/>
      <geometry>
        <mesh filename="file:///home/ruddick/prebuilt_ws/install/ur_description/share/ur_description/meshes/ur5e/visual/upperarm.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.138"/>
      <geometry>
        <mesh filename="file:///home/ruddick/prebuilt_ws/install/ur_description/share/ur_description/meshes/ur5e/collision/upperarm.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="8.393"/>
      <origin rpy="0 1.5707963267948966 0" xyz="-0.2125 0.0 0.138"/>
      <inertia ixx="0.1338857818623325" ixy="0.0" ixz="0.0" iyy="0.1338857818623325" iyz="0.0" izz="0.0151074"/>
    </inertial>
  </link>
  <link name="forearm_link">
    <visual>
      <origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.007"/>
      <geometry>
        <mesh filename="file:///home/ruddick/prebuilt_ws/install/ur_description/share/ur_description/meshes/ur5e/visual/forearm.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.007"/>
      <geometry>
        <mesh filename="file:///home/ruddick/prebuilt_ws/install/ur_description/share/ur_description/meshes/ur5e/collision/forearm.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="2.275"/>
      <origin rpy="0 1.5707963267948966 0" xyz="-0.1961 0.0 0.007"/>
      <inertia ixx="0.031209355099586295" ixy="0.0" ixz="0.0" iyy="0.031209355099586295" iyz="0.0" izz="0.004095"/>
    </inertial>
  </link>
  <link name="wrist_1_link">
    <visual>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.127"/>
      <geometry>
        <mesh filename="file:///home/ruddick/prebuilt_ws/install/ur_description/share/ur_description/meshes/ur5e/visual/wrist1.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.127"/>
      <geometry>
        <mesh filename="file:///home/ruddick/prebuilt_ws/install/ur_description/share/ur_description/meshes/ur5e/collision/wrist1.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="1.219"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.0025598989760400002" ixy="0.0" ixz="0.0" iyy="0.0025598989760400002" iyz="0.0" izz="0.0021942"/>
    </inertial>
  </link>
  <link name="wrist_2_link">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 -0.0997"/>
      <geometry>
        <mesh filename="file:///home/ruddick/prebuilt_ws/install/ur_description/share/ur_description/meshes/ur5e/visual/wrist2.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 -0.0997"/>
      <geometry>
        <mesh filename="file:///home/ruddick/prebuilt_ws/install/ur_description/share/ur_description/meshes/ur5e/collision/wrist2.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="1.219"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.0025598989760400002" ixy="0.0" ixz="0.0" iyy="0.0025598989760400002" iyz="0.0" izz="0.0021942"/>
    </inertial>
  </link>
  <link name="wrist_3_link">
    <visual>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.0989"/>
      <geometry>
        <mesh filename="file:///home/ruddick/prebuilt_ws/install/ur_description/share/ur_description/meshes/ur5e/visual/wrist3.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.0989"/>
      <geometry>
        <mesh filename="file:///home/ruddick/prebuilt_ws/install/ur_description/share/ur_description/meshes/ur5e/collision/wrist3.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1879"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 -0.0229"/>
      <inertia ixx="9.890410052167731e-05" ixy="0.0" ixz="0.0" iyy="9.890410052167731e-05" iyz="0.0" izz="0.0001321171875"/>
    </inertial>
  </link>  <!-- base_joint fixes base_link to the environment -->
  <joint name="base_joint" type="fixed">
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <parent link="world"/>
    <child link="base_link"/>
  </joint>  <!-- joints - main serial chain -->
  <joint name="base_link-base_link_inertia" type="fixed">
    <parent link="base_link"/>
    <child link="base_link_inertia"/>
    <!-- ''base_link'' is REP-103 aligned (so X+ forward), while the internal frames of the robot/controller have X+ pointing backwards. Use the joint between ''base_link'' and ''base_link_inertia'' (a dummy link/frame) to introduce the necessary rotation over Z (of pi rad). -->
    <origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
  </joint>
  <joint name="shoulder_pan_joint" type="revolute">
    <parent link="base_link_inertia"/>
    <child link="shoulder_link"/>
    <origin rpy="0 0 0" xyz="0 0 0.1625"/>
    <axis xyz="0 0 1"/>
    <limit effort="150.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.141592653589793"/>
    <safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-6.133185307179586" soft_upper_limit="6.133185307179586"/>
    <dynamics damping="0" friction="0"/>
  </joint>
  <joint name="shoulder_lift_joint" type="revolute">
    <parent link="shoulder_link"/>
    <child link="upper_arm_link"/>
    <origin rpy="1.570796327 0 0" xyz="0 0 0"/>
    <axis xyz="0 0 1"/>
    <limit effort="150.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.141592653589793"/>
    <safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-6.133185307179586" soft_upper_limit="6.133185307179586"/>
    <dynamics damping="0" friction="0"/>
  </joint>
  <joint name="elbow_joint" type="revolute">
    <parent link="upper_arm_link"/>
    <child link="forearm_link"/>
    <origin rpy="0 0 0" xyz="-0.425 0 0"/>
    <axis xyz="0 0 1"/>
    <limit effort="150.0" lower="-3.141592653589793" upper="3.141592653589793" velocity="3.141592653589793"/>
    <safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-2.991592653589793" soft_upper_limit="2.991592653589793"/>
    <dynamics damping="0" friction="0"/>
  </joint>
  <joint name="wrist_1_joint" type="revolute">
    <parent link="forearm_link"/>
    <child link="wrist_1_link"/>
    <origin rpy="0 0 0" xyz="-0.3922 0 0.1333"/>
    <axis xyz="0 0 1"/>
    <limit effort="28.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.141592653589793"/>
    <safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-6.133185307179586" soft_upper_limit="6.133185307179586"/>
    <dynamics damping="0" friction="0"/>
  </joint>
  <joint name="wrist_2_joint" type="revolute">
    <parent link="wrist_1_link"/>
    <child link="wrist_2_link"/>
    <origin rpy="1.570796327 0 0" xyz="0 -0.0997 -2.044881182297852e-11"/>
    <axis xyz="0 0 1"/>
    <limit effort="28.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.141592653589793"/>
    <safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-6.133185307179586" soft_upper_limit="6.133185307179586"/>
    <dynamics damping="0" friction="0"/>
  </joint>
  <joint name="wrist_3_joint" type="revolute">
    <parent link="wrist_2_link"/>
    <child link="wrist_3_link"/>
    <origin rpy="1.570796326589793 3.141592653589793 3.141592653589793" xyz="0 0.0996 -2.042830148012698e-11"/>
    <axis xyz="0 0 1"/>
    <limit effort="28.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.141592653589793"/>
    <safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-6.133185307179586" soft_upper_limit="6.133185307179586"/>
    <dynamics damping="0" friction="0"/>
  </joint>
  <link name="ft_frame"/>
  <joint name="wrist_3_link-ft_frame" type="fixed">
    <parent link="wrist_3_link"/>
    <child link="ft_frame"/>
    <origin rpy="3.141592653589793 0 0" xyz="0 0 0"/>
  </joint>  <!-- ROS-Industrial ''base'' frame - base_link to UR ''Base'' Coordinates transform -->
  <link name="base"/>
  <joint name="base_link-base_fixed_joint" type="fixed">    <!-- Note the rotation over Z of pi radians - as base_link is REP-103 aligned (i.e., has X+ forward, Y+ left and Z+ up), this is needed to correctly align ''base'' with the ''Base'' coordinate system of the UR controller. -->
    <origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
    <parent link="base_link"/>
    <child link="base"/>
  </joint>  <!-- ROS-Industrial ''flange'' frame - attachment point for EEF models -->
  <link name="flange"/>
  <joint name="wrist_3-flange" type="fixed">
    <parent link="wrist_3_link"/>
    <child link="flange"/>
    <origin rpy="0 -1.5707963267948966 -1.5707963267948966" xyz="0 0 0"/>
  </joint>  <!-- ROS-Industrial ''tool0'' frame - all-zeros tool frame -->
  <link name="tool0"/>
  <joint name="flange-tool0" type="fixed">    <!-- default toolframe - X+ left, Y+ up, Z+ front -->
    <origin rpy="1.5707963267948966 0 1.5707963267948966" xyz="0 0 0"/>
    <parent link="flange"/>
    <child link="tool0"/>
  </joint>  <!-- Gazebo plugins -->
  <gazebo reference="world"></gazebo>
  <gazebo>
    <plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin">
      <parameters>/home/ruddick/prebuilt_ws/install/ur_simulation_ignition/share/ur_simulation_ignition/config/ur_controllers.yaml</parameters>
      <controller_manager_node_name>controller_manager</controller_manager_node_name>
    </plugin>
  </gazebo>
</robot>
"""
    robot_description = {"robot_description": robot_description_content}

    robot_state_publisher_node = Node(
        package="robot_state_publisher",
        executable="robot_state_publisher",
        output="both",
        parameters=[{"use_sim_time": True}, robot_description],
    )

    joint_state_broadcaster_spawner = Node(
        package="controller_manager",
        executable="spawner",
        arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"],
    )

    # 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",
        arguments=["joint_trajectory_controller", "-c", "/controller_manager"],
    )

    # Gazebo (ignition) nodes
    gz_spawn_entity = Node(
        package="ros_gz_sim",
        executable="create",
        output="screen",
        arguments=[
            "-string",
            robot_description_content,
            "-name",
            "ur",
            "-allow_renaming",
            "true",
        ],
    )

    gz_launch_description = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            [FindPackageShare("ros_gz_sim"), "/launch/gz_sim.launch.py"]
        ),
        launch_arguments={"gz_args": " -r -v 3 empty.sdf"}.items(),
    )

    nodes_to_start = [
        robot_state_publisher_node,
        joint_state_broadcaster_spawner,
        initial_joint_controller_spawner_started,
        gz_spawn_entity,
        gz_launch_description,
    ]

    return nodes_to_start

def generate_launch_description():
    return LaunchDescription([OpaqueFunction(function=launch_setup)])

This should result in the robot shoulder at 45 degrees (and the rest horizontal), but instead everything is still at 0:

UrPosition

Here are the logs:

[INFO] [launch]: All log files can be found below /home/ruddick/.ros/log/2024-01-29-14-10-32-181481-primary-40113
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [robot_state_publisher-1]: process started with pid [40114]
[INFO] [spawner-2]: process started with pid [40116]
[INFO] [spawner-3]: process started with pid [40118]
[INFO] [create-4]: process started with pid [40120]
[INFO] [ruby $(which ign) gazebo-5]: process started with pid [40122]
[create-4] [INFO] [1706566232.280658239] [ros_gz_sim]: Requesting list of world names.
[robot_state_publisher-1] [INFO] [1706566232.300456043] [robot_state_publisher]: got segment base
[robot_state_publisher-1] [INFO] [1706566232.300858629] [robot_state_publisher]: got segment base_link
[robot_state_publisher-1] [INFO] [1706566232.301003339] [robot_state_publisher]: got segment base_link_inertia
[robot_state_publisher-1] [INFO] [1706566232.301111340] [robot_state_publisher]: got segment flange
[robot_state_publisher-1] [INFO] [1706566232.301209174] [robot_state_publisher]: got segment forearm_link
[robot_state_publisher-1] [INFO] [1706566232.301305508] [robot_state_publisher]: got segment ft_frame
[robot_state_publisher-1] [INFO] [1706566232.301397633] [robot_state_publisher]: got segment shoulder_link
[robot_state_publisher-1] [INFO] [1706566232.301486384] [robot_state_publisher]: got segment tool0
[robot_state_publisher-1] [INFO] [1706566232.301702760] [robot_state_publisher]: got segment upper_arm_link
[robot_state_publisher-1] [INFO] [1706566232.302223222] [robot_state_publisher]: got segment world
[robot_state_publisher-1] [INFO] [1706566232.302530933] [robot_state_publisher]: got segment wrist_1_link
[robot_state_publisher-1] [INFO] [1706566232.302791643] [robot_state_publisher]: got segment wrist_2_link
[robot_state_publisher-1] [INFO] [1706566232.303026269] [robot_state_publisher]: got segment wrist_3_link
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [QT] qrc:/qml/StyleDialog.qml:112:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [QT] qrc:/qml/StyleDialog.qml:105:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [QT] qrc:/qml/StyleDialog.qml:98:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:102:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [QT] qrc:/qml/PluginMenu.qml:27:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [QT] file::/Gazebo/GazeboDrawer.qml:242:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }
[create-4] [INFO] [1706566232.777164400] [ros_gz_sim]: Requested creation of entity.
[create-4] [INFO] [1706566232.777218817] [ros_gz_sim]: OK creation of entity.
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [QT] file::/EntityContextMenuPlugin/EntityContextMenuPlugin.qml:57:5: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[INFO] [create-4]: process has finished cleanly [pid 40120]
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [QT] file::/Spawn/Spawn.qml:32:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }
[ruby $(which ign) gazebo-5] [Msg] Ignition Gazebo GUI    v6.16.0
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loading config [/home/ruddick/.ignition/gazebo/6/gui.config]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [3D View] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [MinimalScene] from path [/usr/lib/aarch64-linux-gnu/ign-gui-6/plugins/libMinimalScene.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Entity Context Menu] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [EntityContextMenuPlugin] from path [/usr/lib/aarch64-linux-gnu/ign-gazebo-6/plugins/gui/libEntityContextMenuPlugin.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Scene Manager] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [GzSceneManager] from path [/usr/lib/aarch64-linux-gnu/ign-gazebo-6/plugins/gui/libGzSceneManager.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Camera view controller topic advertised on [/gui/camera/view_control]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Camera reference visual topic advertised on [/gui/camera/view_control/reference_visual]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Camera view control sensitivity advertised on [/gui/camera/view_control/sensitivity]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Interactive view control] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [InteractiveViewControl] from path [/usr/lib/aarch64-linux-gnu/ign-gui-6/plugins/libInteractiveViewControl.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Camera tracking] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [CameraTracking] from path [/usr/lib/aarch64-linux-gnu/ign-gui-6/plugins/libCameraTracking.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Listening to stats on [/world/empty/stats]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Marker Manager] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [MarkerManager] from path [/usr/lib/aarch64-linux-gnu/ign-gui-6/plugins/libMarkerManager.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Select entities] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [SelectEntities] from path [/usr/lib/aarch64-linux-gnu/ign-gazebo-6/plugins/gui/libSelectEntities.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Spawn] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [Spawn] from path [/usr/lib/aarch64-linux-gnu/ign-gazebo-6/plugins/gui/libSpawn.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] View as transparent service on [/gui/view/transparent]
[ruby $(which ign) gazebo-5] [GUI] [Msg] View as wireframes service on [/gui/view/wireframes]
[ruby $(which ign) gazebo-5] [GUI] [Msg] View center of mass service on [/gui/view/com]
[ruby $(which ign) gazebo-5] [GUI] [Msg] View inertia service on [/gui/view/inertia]
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [QT] file::/WorldControl/WorldControl.qml:30:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [QT] file::/TransformControl/TransformControl.qml:104:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [QT] file::/TransformControl/TransformControl.qml:99:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [QT] file::/TransformControl/TransformControl.qml:94:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [QT] file::/TransformControl/TransformControl.qml:89:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[ruby $(which ign) gazebo-5] [GUI] [Msg] View collisions service on [/gui/view/collisions]
[ruby $(which ign) gazebo-5] [GUI] [Msg] View joints service on [/gui/view/joints]
[ruby $(which ign) gazebo-5] [GUI] [Msg] View frames service on [/gui/view/frames]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Visualization capabilities] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [VisualizationCapabilities] from path [/usr/lib/aarch64-linux-gnu/ign-gazebo-6/plugins/gui/libVisualizationCapabilities.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Using world control service [/world/empty/control]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Listening to stats on [/world/empty/stats]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [World control] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [WorldControl] from path [/usr/lib/aarch64-linux-gnu/ign-gui-6/plugins/libWorldControl.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Listening to stats on [/world/empty/stats]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [World stats] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [WorldStats] from path [/usr/lib/aarch64-linux-gnu/ign-gui-6/plugins/libWorldStats.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Shapes] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [Shapes] from path [/usr/lib/aarch64-linux-gnu/ign-gazebo-6/plugins/gui/libShapes.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Lights] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [Lights] from path [/usr/lib/aarch64-linux-gnu/ign-gazebo-6/plugins/gui/libLights.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Transform control] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [TransformControl] from path [/usr/lib/aarch64-linux-gnu/ign-gazebo-6/plugins/gui/libTransformControl.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Screenshot service on [/gui/screenshot]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Screenshot] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [Screenshot] from path [/usr/lib/aarch64-linux-gnu/ign-gui-6/plugins/libScreenshot.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Copy/Paste] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [CopyPaste] from path [/usr/lib/aarch64-linux-gnu/ign-gazebo-6/plugins/gui/libCopyPaste.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Component inspector] to main window
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [ComponentInspector] from path [/usr/lib/aarch64-linux-gnu/ign-gazebo-6/plugins/gui/libComponentInspector.so]
[ruby $(which ign) gazebo-5] [GUI] [Msg] Added plugin [Entity tree] to main window
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [QT] file::/WorldStats/WorldStats.qml:53:3: QML RowLayout: Binding loop detected for property "x"
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Application.cc:797] [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.
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Ogre2RenderTarget.cc:574] Anti-aliasing level of '8' is not supported; valid FSAA levels are: [ 0 4 ]. Setting to 0
[ruby $(which ign) gazebo-5] [INFO] [1706566234.466362686] [gz_ros2_control]: [ign_ros2_control] Fixed joint [base_joint] (Entity=32)] is skipped
[spawner-2] [INFO] [1706566234.534008656] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' node to exist
[spawner-3] [INFO] [1706566234.534051323] [spawner_joint_trajectory_controller]: Waiting for '/controller_manager' node to exist
[ruby $(which ign) gazebo-5] [INFO] [1706566234.538773814] [gz_ros2_control]: connected to service!! robot_state_publisher asking for robot_description
[ruby $(which ign) gazebo-5] [INFO] [1706566234.540018948] [gz_ros2_control]: Received URDF from param server
[ruby $(which ign) gazebo-5] [WARN] [1706566234.543929100] [gz_ros2_control]: The position_proportional_gain parameter was not defined, defaulting to: 0.1
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544038101] [gz_ros2_control]: Loading joint: shoulder_pan_joint
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544045309] [gz_ros2_control]:   State:
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544070768] [gz_ros2_control]:        position
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544077351] [gz_ros2_control]:            found initial value: 0.000000
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544082351] [gz_ros2_control]:        velocity
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544086101] [gz_ros2_control]:        effort
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544089393] [gz_ros2_control]:   Command:
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544092518] [gz_ros2_control]:        position
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544096226] [gz_ros2_control]:        velocity
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544101809] [gz_ros2_control]: Loading joint: shoulder_lift_joint
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544105310] [gz_ros2_control]:   State:
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544108393] [gz_ros2_control]:        position
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544112393] [gz_ros2_control]:            found initial value: -0.785000
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544116185] [gz_ros2_control]:        velocity
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544119726] [gz_ros2_control]:        effort
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544122935] [gz_ros2_control]:   Command:
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544125935] [gz_ros2_control]:        position
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544129060] [gz_ros2_control]:        velocity
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544133726] [gz_ros2_control]: Loading joint: elbow_joint
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544137143] [gz_ros2_control]:   State:
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544140476] [gz_ros2_control]:        position
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544143601] [gz_ros2_control]:            found initial value: 0.785000
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544147393] [gz_ros2_control]:        velocity
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544150518] [gz_ros2_control]:        effort
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544154477] [gz_ros2_control]:   Command:
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544157602] [gz_ros2_control]:        position
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544160935] [gz_ros2_control]:        velocity
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544165477] [gz_ros2_control]: Loading joint: wrist_1_joint
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544168893] [gz_ros2_control]:   State:
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544172018] [gz_ros2_control]:        position
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544174893] [gz_ros2_control]:            found initial value: 0.000000
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544178310] [gz_ros2_control]:        velocity
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544181643] [gz_ros2_control]:        effort
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544184810] [gz_ros2_control]:   Command:
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544187810] [gz_ros2_control]:        position
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544190810] [gz_ros2_control]:        velocity
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544194852] [gz_ros2_control]: Loading joint: wrist_2_joint
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544198143] [gz_ros2_control]:   State:
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544201102] [gz_ros2_control]:        position
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544204310] [gz_ros2_control]:            found initial value: 1.570000
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544207769] [gz_ros2_control]:        velocity
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544210727] [gz_ros2_control]:        effort
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544213685] [gz_ros2_control]:   Command:
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544216935] [gz_ros2_control]:        position
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544220685] [gz_ros2_control]:        velocity
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544224769] [gz_ros2_control]: Loading joint: wrist_3_joint
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544227977] [gz_ros2_control]:   State:
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544230894] [gz_ros2_control]:        position
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544233685] [gz_ros2_control]:            found initial value: 0.000000
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544237185] [gz_ros2_control]:        velocity
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544240727] [gz_ros2_control]:        effort
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544243769] [gz_ros2_control]:   Command:
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544246811] [gz_ros2_control]:        position
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544249727] [gz_ros2_control]:        velocity
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544283894] [resource_manager]: Initialize hardware 'ur' 
[ruby $(which ign) gazebo-5] [WARN] [1706566234.544293394] [gz_ros2_control]: On init...
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544321228] [resource_manager]: Successful initialization of hardware 'ur'
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544440770] [resource_manager]: 'configure' hardware 'ur' 
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544446312] [gz_ros2_control]: System Successfully configured!
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544453729] [resource_manager]: Successful 'configure' of hardware 'ur'
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544458979] [resource_manager]: 'activate' hardware 'ur' 
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544462062] [resource_manager]: Successful 'activate' of hardware 'ur'
[ruby $(which ign) gazebo-5] [INFO] [1706566234.544466187] [gz_ros2_control]: Loading controller_manager
[ruby $(which ign) gazebo-5] [GUI] [Msg] Loaded plugin [EntityTree] from path [/usr/lib/aarch64-linux-gnu/ign-gazebo-6/plugins/gui/libEntityTree.so][Msg] Received world [empty.sdf] from the GUI.
[ruby $(which ign) gazebo-5] [Msg] Ignition Gazebo Server v6.16.0
[ruby $(which ign) gazebo-5] [Msg] Loading SDF world file[/usr/share/ignition/ignition-gazebo6/worlds/empty.sdf].
[ruby $(which ign) gazebo-5] [Msg] Serving entity system service on [/entity/system/add]
[ruby $(which ign) gazebo-5] [Msg] Create service on [/world/empty/create]
[ruby $(which ign) gazebo-5] [Msg] Remove service on [/world/empty/remove]
[ruby $(which ign) gazebo-5] [Msg] Pose service on [/world/empty/set_pose]
[ruby $(which ign) gazebo-5] [Msg] Pose service on [/world/empty/set_pose_vector]
[ruby $(which ign) gazebo-5] [Msg] Light configuration service on [/world/empty/light_config]
[ruby $(which ign) gazebo-5] [Msg] Physics service on [/world/empty/set_physics]
[ruby $(which ign) gazebo-5] [Msg] SphericalCoordinates service on [/world/empty/set_spherical_coordinates]
[ruby $(which ign) gazebo-5] [Msg] Enable collision service on [/world/empty/enable_collision]
[ruby $(which ign) gazebo-5] [Msg] Disable collision service on [/world/empty/disable_collision]
[ruby $(which ign) gazebo-5] [Msg] Material service on [/world/empty/visual_config]
[ruby $(which ign) gazebo-5] [Msg] Material service on [/world/empty/wheel_slip]
[ruby $(which ign) gazebo-5] [Msg] Loaded level [3]
[ruby $(which ign) gazebo-5] [Msg] Serving world controls on [/world/empty/control], [/world/empty/control/state] and [/world/empty/playback/control]
[ruby $(which ign) gazebo-5] [Msg] Serving GUI information on [/world/empty/gui/info]
[ruby $(which ign) gazebo-5] [Msg] World [empty] initialized with [1ms] physics profile.
[ruby $(which ign) gazebo-5] [Msg] Serving world SDF generation service on [/world/empty/generate_world_sdf]
[ruby $(which ign) gazebo-5] [Msg] Serving world names on [/gazebo/worlds]
[ruby $(which ign) gazebo-5] [Msg] Resource path add service on [/gazebo/resource_paths/add].
[ruby $(which ign) gazebo-5] [Msg] Resource path get service on [/gazebo/resource_paths/get].
[ruby $(which ign) gazebo-5] [Msg] Resource path resolve service on [/gazebo/resource_paths/resolve].
[ruby $(which ign) gazebo-5] [Msg] Resource paths published on [/gazebo/resource_paths].
[ruby $(which ign) gazebo-5] [Msg] Server control service on [/server_control].
[ruby $(which ign) gazebo-5] [Msg] Found no publishers on /stats, adding root stats topic
[ruby $(which ign) gazebo-5] [Msg] Found no publishers on /clock, adding root clock topic
[ruby $(which ign) gazebo-5] [Msg] Serving scene information on [/world/empty/scene/info]
[ruby $(which ign) gazebo-5] [Msg] Serving graph information on [/world/empty/scene/graph]
[ruby $(which ign) gazebo-5] [Msg] Serving full state on [/world/empty/state]
[ruby $(which ign) gazebo-5] [Msg] Serving full state (async) on [/world/empty/state_async]
[ruby $(which ign) gazebo-5] [Msg] Publishing scene information on [/world/empty/scene/info]
[ruby $(which ign) gazebo-5] [Msg] Publishing entity deletions on [/world/empty/scene/deletion]
[ruby $(which ign) gazebo-5] [Wrn] [Component.hh:144] Trying to serialize component with data type [N3sdf3v125WorldE], which doesn't have `operator<<`. Component will not be serialized.
[ruby $(which ign) gazebo-5] [WARN] [1706566234.576779578] [gz_ros2_control]:  Desired controller update period (0.002 s) is slower than the gazebo simulation period (0.001 s).
[ruby $(which ign) gazebo-5] [GUI] [Wrn] [Component.hh:189] Trying to deserialize component with data type [N3sdf3v125WorldE], which doesn't have `operator>>`. Component will not be deserialized.
[ruby $(which ign) gazebo-5] [INFO] [1706566234.742460605] [controller_manager]: Loading controller 'joint_state_broadcaster'
[ruby $(which ign) gazebo-5] [INFO] [1706566234.747343264] [controller_manager]: Setting use_sim_time=True for joint_state_broadcaster to match controller manager (see ros2_control#325 for details)
[ruby $(which ign) gazebo-5] [INFO] [1706566234.748179978] [controller_manager]: Loading controller 'joint_trajectory_controller'
[spawner-2] [INFO] [1706566234.748830483] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster
[ruby $(which ign) gazebo-5] [WARN] [1706566234.754325021] [joint_trajectory_controller]: [Deprecated]: "allow_nonzero_velocity_at_trajectory_end" is set to true. The default behavior will change to false.
[ruby $(which ign) gazebo-5] [INFO] [1706566234.754349688] [controller_manager]: Setting use_sim_time=True for joint_trajectory_controller to match controller manager (see ros2_control#325 for details)
[ruby $(which ign) gazebo-5] [INFO] [1706566234.757343875] [controller_manager]: Configuring controller 'joint_state_broadcaster'
[ruby $(which ign) gazebo-5] [INFO] [1706566234.757445043] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published
[spawner-3] [INFO] [1706566234.758058964] [spawner_joint_trajectory_controller]: Loaded joint_trajectory_controller
[ruby $(which ign) gazebo-5] [INFO] [1706566234.761712447] [controller_manager]: Configuring controller 'joint_trajectory_controller'
[ruby $(which ign) gazebo-5] [INFO] [1706566234.761800365] [joint_trajectory_controller]: No specific joint names are used for command interfaces. Using 'joints' parameter.
[ruby $(which ign) gazebo-5] [INFO] [1706566234.761813490] [joint_trajectory_controller]: Command interfaces are [position] and state interfaces are [position velocity].
[ruby $(which ign) gazebo-5] [INFO] [1706566234.761820323] [joint_trajectory_controller]: Using 'splines' interpolation method.
[ruby $(which ign) gazebo-5] [INFO] [1706566234.762274035] [joint_trajectory_controller]: Controller state will be published at 100.00 Hz.
[ruby $(which ign) gazebo-5] [INFO] [1706566234.762916706] [joint_trajectory_controller]: Action status changes will be monitored at 20.00 Hz.
[spawner-2] [INFO] [1706566234.771226639] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[spawner-3] [INFO] [1706566234.775898171] [spawner_joint_trajectory_controller]: Configured and activated joint_trajectory_controller
[INFO] [spawner-2]: process has finished cleanly [pid 40116]
[INFO] [spawner-3]: process has finished cleanly [pid 40118]
mrjogo commented 7 months ago

Probably related to https://github.com/ros-controls/gz_ros2_control/issues/167

fmauch commented 5 months ago

We've done some major rework of the description and gz simulation lately.

On Humble, when changing the https://github.com/UniversalRobots/Universal_Robots_ROS2_Description/blob/humble/config/initial_positions.yaml file, that values get respected by the simulation.

On rolling (pending #7) things will get a bit different, as we store a custom gz-related description inside this repo. However, changing the values here does also get reflected in the model.

So I assume this got fixed upstream?

fmauch commented 5 months ago

We tested this with #7 again today and it seems to be resolved with the latest gz_ros2_control. Hence marking this being closed by #7