ros-simulation / gazebo_ros_pkgs

Wrappers, tools and additional API's for using ROS with Gazebo
http://wiki.ros.org/gazebo_ros_pkgs
742 stars 766 forks source link

gazebo compains about duplicated / already registered #1397

Open muttistefano opened 2 years ago

muttistefano commented 2 years ago

Hi all, i have been trying to load this urdf using the spawn entity scripts , in ros2 galactic :

<?xml version="1.0"?>
<robot name="eureca">
<xacro:ur_ros2_control name="${name}" prefix="${prefix}" use_fake_hardware="${use_fake_hardware}" initial_positions="${initial_positions}" fake_sensor_commands="${fake_sensor_commands}" headless_mode="${headless_mode}" sim_gazebo="${sim_gazebo}" sim_ignition="${sim_ignition}" script_filename="${script_filename}" output_recipe_filename="${output_recipe_filename}" input_recipe_filename="${input_recipe_filename}" tf_prefix="" hash_kinematics="${kinematics_hash}" robot_ip="${robot_ip}" use_tool_communication="${use_tool_communication}" tool_voltage="${tool_voltage}" tool_parity="${tool_parity}" tool_baud_rate="${tool_baud_rate}" tool_stop_bits="${tool_stop_bits}" tool_rx_idle_chars="${tool_rx_idle_chars}" tool_tx_idle_chars="${tool_tx_idle_chars}" tool_device_name="${tool_device_name}" tool_tcp_port="${tool_tcp_port}" reverse_port="${reverse_port}" script_sender_port="${script_sender_port}" /> -->
  <!-- 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="sweepee_1/base_link"/>
  <link name="sweepee_1/base_link_inertia">
    <visual>
      <origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
      <geometry>
        <mesh filename="file:///home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/ur_description/share/ur_description/meshes/ur10/visual/base.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
      <geometry>
        <mesh filename="file:///home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/ur_description/share/ur_description/meshes/ur10/collision/base.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="4.0"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.0061063308908" ixy="0.0" ixz="0.0" iyy="0.0061063308908" iyz="0.0" izz="0.01125"/>
    </inertial>
  </link>
  <link name="sweepee_1/shoulder_link">
    <visual>
      <origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
      <geometry>
        <mesh filename="file:///home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/ur_description/share/ur_description/meshes/ur10/visual/shoulder.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
      <geometry>
        <mesh filename="file:///home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/ur_description/share/ur_description/meshes/ur10/collision/shoulder.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="7.778"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.03147431257693659" ixy="0.0" ixz="0.0" iyy="0.03147431257693659" iyz="0.0" izz="0.021875624999999996"/>
    </inertial>
  </link>
  <link name="sweepee_1/upper_arm_link">
    <visual>
      <origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.220941"/>
      <geometry>
        <mesh filename="file:///home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/ur_description/share/ur_description/meshes/ur10/visual/upperarm.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.220941"/>
      <geometry>
        <mesh filename="file:///home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/ur_description/share/ur_description/meshes/ur10/collision/upperarm.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="12.93"/>
      <origin rpy="0 1.5707963267948966 0" xyz="-0.306 0.0 0.175"/>
      <inertia ixx="0.42175380379841093" ixy="0.0" ixz="0.0" iyy="0.42175380379841093" iyz="0.0" izz="0.03636562499999999"/>
    </inertial>
  </link>
  <link name="sweepee_1/forearm_link">
    <visual>
      <origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.049042"/>
      <geometry>
        <mesh filename="file:///home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/ur_description/share/ur_description/meshes/ur10/visual/forearm.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.049042"/>
      <geometry>
        <mesh filename="file:///home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/ur_description/share/ur_description/meshes/ur10/collision/forearm.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="3.87"/>
      <origin rpy="0 1.5707963267948966 0" xyz="-0.28615 0.0 0.049042"/>
      <inertia ixx="0.11106969409710458" ixy="0.0" ixz="0.0" iyy="0.11106969409710458" iyz="0.0" izz="0.010884375"/>
    </inertial>
  </link>
  <link name="sweepee_1/wrist_1_link">
    <visual>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.1149"/>
      <geometry>
        <mesh filename="file:///home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/ur_description/share/ur_description/meshes/ur10/visual/wrist1.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.1149"/>
      <geometry>
        <mesh filename="file:///home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/ur_description/share/ur_description/meshes/ur10/collision/wrist1.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="1.96"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.005108247956699999" ixy="0.0" ixz="0.0" iyy="0.005108247956699999" iyz="0.0" izz="0.005512499999999999"/>
    </inertial>
  </link>
  <link name="sweepee_1/wrist_2_link">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 -0.1158"/>
      <geometry>
        <mesh filename="file:///home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/ur_description/share/ur_description/meshes/ur10/visual/wrist2.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 -0.1158"/>
      <geometry>
        <mesh filename="file:///home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/ur_description/share/ur_description/meshes/ur10/collision/wrist2.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="1.96"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.0040792483683" ixy="0.0" ixz="0.0" iyy="0.0040792483683" iyz="0.0" izz="0.005512499999999999"/>
    </inertial>
  </link>
  <link name="sweepee_1/wrist_3_link">
    <visual>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.0922"/>
      <geometry>
        <mesh filename="file:///home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/ur_description/share/ur_description/meshes/ur10/visual/wrist3.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.0922"/>
      <geometry>
        <mesh filename="file:///home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/ur_description/share/ur_description/meshes/ur10/collision/wrist3.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.202"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 -0.01525"/>
      <inertia ixx="0.00011792166116465" ixy="0.0" ixz="0.0" iyy="0.00011792166116465" iyz="0.0" izz="0.00020452500000000002"/>
    </inertial>
  </link>
  <!-- base_joint fixes base_link to the environment -->
  <joint name="sweepee_1/base_joint" type="fixed">
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <parent link="sweepee_1/base_footprint"/>
    <child link="sweepee_1/base_link"/>
  </joint>
  <!-- joints - main serial chain -->
  <joint name="sweepee_1/base_link-base_link_inertia" type="fixed">
    <parent link="sweepee_1/base_link"/>
    <child link="sweepee_1/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="sweepee_1/shoulder_pan_joint" type="revolute">
    <parent link="sweepee_1/base_link_inertia"/>
    <child link="sweepee_1/shoulder_link"/>
    <origin rpy="0 0 0" xyz="0 0 0.1273"/>
    <axis xyz="0 0 1"/>
    <limit effort="330.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="2.0943951023931953"/>
    <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="sweepee_1/shoulder_lift_joint" type="revolute">
    <parent link="sweepee_1/shoulder_link"/>
    <child link="sweepee_1/upper_arm_link"/>
    <origin rpy="1.570796327 0 0" xyz="0 0 0"/>
    <axis xyz="0 0 1"/>
    <limit effort="330.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="2.0943951023931953"/>
    <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="sweepee_1/elbow_joint" type="revolute">
    <parent link="sweepee_1/upper_arm_link"/>
    <child link="sweepee_1/forearm_link"/>
    <origin rpy="0 0 0" xyz="-0.612 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="sweepee_1/wrist_1_joint" type="revolute">
    <parent link="sweepee_1/forearm_link"/>
    <child link="sweepee_1/wrist_1_link"/>
    <origin rpy="0 0 0" xyz="-0.5723 0 0.163941"/>
    <axis xyz="0 0 1"/>
    <limit effort="56.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="sweepee_1/wrist_2_joint" type="revolute">
    <parent link="sweepee_1/wrist_1_link"/>
    <child link="sweepee_1/wrist_2_link"/>
    <origin rpy="1.570796327 0 0" xyz="0 -0.1157 -2.373046667922381e-11"/>
    <axis xyz="0 0 1"/>
    <limit effort="56.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="sweepee_1/wrist_3_joint" type="revolute">
    <parent link="sweepee_1/wrist_2_link"/>
    <child link="sweepee_1/wrist_3_link"/>
    <origin rpy="1.570796326589793 3.141592653589793 3.141592653589793" xyz="0 0.0922 -1.891053610911353e-11"/>
    <axis xyz="0 0 1"/>
    <limit effort="56.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="sweepee_1/ft_frame"/>
  <joint name="sweepee_1/wrist_3_link-ft_frame" type="fixed">
    <parent link="sweepee_1/wrist_3_link"/>
    <child link="sweepee_1/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="sweepee_1/base"/>
  <joint name="sweepee_1/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="sweepee_1/base_link"/>
    <child link="sweepee_1/base"/>
  </joint>
  <!-- ROS-Industrial 'flange' frame - attachment point for EEF models -->
  <link name="sweepee_1/flange"/>
  <joint name="sweepee_1/wrist_3-flange" type="fixed">
    <parent link="sweepee_1/wrist_3_link"/>
    <child link="sweepee_1/flange"/>
    <origin rpy="0 -1.5707963267948966 -1.5707963267948966" xyz="0 0 0"/>
  </joint>
  <!-- ROS-Industrial 'tool0' frame - all-zeros tool frame -->
  <link name="sweepee_1/tool0"/>
  <joint name="sweepee_1/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="sweepee_1/flange"/>
    <child link="sweepee_1/tool0"/>
  </joint>
  <gazebo reference="world"> </gazebo>
  <gazebo>
    <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
      <robot_param>robot_description</robot_param>
      <robot_namespace>sweepee_1/</robot_namespace>
      <parameters>/home/kolmogorov/Documents/2ROS/lampo_ws_ros2/install/lampo_description/share/lampo_description/config/ur_controllers_1.yaml</parameters>
      <robot_param_node>robot_state_publisher</robot_param_node>
    </plugin>
  </gazebo>
  <!-- <xacro:if value="$(arg sim_ignition)"> <gazebo reference="world"> </gazebo> <gazebo> <plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin"> <parameters>$(arg simulation_controllers)</parameters> <controller_manager_node_name>$(arg prefix)controller_manager</controller_manager_node_name> </plugin> </gazebo> </xacro:if> -->
  <!-- Base footprint is on the ground under the robot -->
  <link name="sweepee_1/base_footprint">
    <inertial>
      <mass value="1000"/>
      <inertia ixx="0.001" ixy="0.01" ixz="0.01" iyy="0.001" iyz="0.01" izz="0.001"/>
    </inertial>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0.005"/>
      <geometry>
        <box size="1.02 0.55 0.01"/>
      </geometry>
    </collision>
  </link>
  <!-- Base link is the center of the robot's bottom plate -->
  <link name="sweepee_1/base_link_sweepee">
    <visual>
      <origin rpy="0 0 -1.570795" xyz="0 0 0.032"/>
      <geometry>
        <mesh filename="package://lampo_description/meshes/sweepee/visual/sweepee.dae"/>
      </geometry>
      <material name="Gray">
        <color rgba="0.5 0.5 0.5 1.0"/>
      </material>
    </visual>
    <inertial>
      <mass value="4000"/>
      <inertia ixx="1.48454" ixy="0.01" ixz="0.01" iyy="3.02861" iyz="0.01" izz="4.10178"/>
    </inertial>
  </link>
  <joint name="sweepee_1/base_footprint_joint" type="fixed">
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <parent link="sweepee_1/base_footprint"/>
    <child link="sweepee_1/base_link_sweepee"/>
    <dynamics damping="0.7"/>
  </joint>
  <link name="sweepee_1/front_laser"/>
  <joint name="sweepee_1/front_laser_joint" type="fixed">
    <origin rpy="0 0 0" xyz="0.36 0.0 0.26"/>
    <parent link="sweepee_1/base_link_sweepee"/>
    <child link="sweepee_1/front_laser"/>
  </joint>
  <link name="sweepee_1/rear_laser"/>
  <joint name="sweepee_1/rear_laser_joint" type="fixed">
    <origin rpy="0 0 3.14159" xyz="-0.36 0.0 0.26"/>
    <parent link="sweepee_1/base_link_sweepee"/>
    <child link="sweepee_1/rear_laser"/>
  </joint>
  <gazebo reference="sweepee_1/rear_laser">
    <sensor name="sweepee_1/rear_laser" type="ray">
      <!-- <pose>0 0 0 0 0 0</pose> -->
      <!-- <visualize>false</visualize> -->
      <update_rate>10</update_rate>
      <ray>
        <scan display="false">
          <horizontal>
            <samples>750</samples>
            <resolution>1</resolution>
            <min_angle>-1.570795</min_angle>
            <max_angle> 1.570795</max_angle>
          </horizontal>
        </scan>
        <range>
          <min>0.25</min>
          <max>59.0</max>
        </range>
      </ray>
      <plugin filename="libgazebo_ros_ray_sensor.so" name="rear_laser_plugin">
        <!-- <robotNamespace></robotNamespace> -->
        <noise>
          <type>gaussian</type>
          <mean>0.0</mean>
          <stddev>0.01</stddev>
        </noise>
        <ros>
          <namespace>sweepee_1/</namespace>
          <argument>~out:=sweepee_1/rear_scan</argument>
        </ros>
        <alwaysOn>true</alwaysOn>
        <updateRate>15</updateRate>
        <!-- <frameName>rear_laser</frameName> -->
        <frame_name>sweepee_1/rear_laser</frame_name>
        <output_type>sensor_msgs/LaserScan</output_type>
      </plugin>
    </sensor>
  </gazebo>
  <gazebo reference="sweepee_1/front_laser">
    <sensor name="sweepee_1/front_laser" type="ray">
      <!-- <pose>0 0 0 0 0 0</pose> -->
      <!-- <visualize>false</visualize> -->
      <update_rate>10</update_rate>
      <ray>
        <scan display="false">
          <horizontal>
            <samples>750</samples>
            <resolution>1</resolution>
            <min_angle>-1.570795</min_angle>
            <max_angle> 1.570795</max_angle>
          </horizontal>
        </scan>
        <range>
          <min>0.25</min>
          <max>59.0</max>
        </range>
      </ray>
      <plugin filename="libgazebo_ros_ray_sensor.so" name="front_laser_plugin">
        <!-- <robotNamespace></robotNamespace> -->
        <noise>
          <type>gaussian</type>
          <mean>0.0</mean>
          <stddev>0.01</stddev>
        </noise>
        <ros>
          <namespace>sweepee_1/</namespace>
          <argument>~out:=sweepee_1/rear_scan</argument>
        </ros>
        <alwaysOn>true</alwaysOn>
        <updateRate>15</updateRate>
        <!-- <frameName>front_laser</frameName> -->
        <frame_name>sweepee_1/front_laser</frame_name>
        <output_type>sensor_msgs/LaserScan</output_type>
      </plugin>
    </sensor>
  </gazebo>
  <gazebo reference="base_link">
    <gravity>true</gravity>
    <material>Gazebo/White</material>
    <mu1>0.0</mu1>
    <mu2>0.0</mu2>
  </gazebo>
  <gazebo reference="base_footprint">
    <gravity>true</gravity>
    <material>Gazebo/Orange</material>
    <mu1>0.0</mu1>
    <mu2>0.0</mu2>
  </gazebo>
  <joint name="sweepee_1/lifter" type="fixed">
    <parent link="sweepee_1/base_footprint"/>
    <child link="sweepee_1/base_link"/>
    <origin rpy=" 0 0 0" xyz="0 0 0.28"/>
    <axis xyz="0 0 1"/>
  </joint>
  <gazebo>
    <plugin filename="libgazebo_ros_planar_move.so" name="object_controller">
      <ros>
        <!-- Add a namespace -->
        <!-- <namespace>/</namespace> -->
        <!-- Remap the default topic -->
        <argument>~cmd_vel:=custom_cmd_vel</argument>
        <argument>~odom:=custom_odom</argument>
      </ros>
      <update_rate>100</update_rate>
      <publish_rate>10</publish_rate>
      <publish_odom>true</publish_odom>
      <publish_odom_tf>true</publish_odom_tf>
      <odometry_frame>sweepee_1/odom</odometry_frame>
      <robot_base_frame>sweepee_1/base_footprint</robot_base_frame>
      <covariance_x>0.0001</covariance_x>
      <covariance_y>0.0001</covariance_y>
      <covariance_yaw>0.01</covariance_yaw>
    </plugin>
  </gazebo>
</robot>

using :

Node(package='gazebo_ros', executable='spawn_entity.py',
                            arguments=['-entity', 'sw1',"-topic", "sweepee_1/robot_description",
                                       "-robot_namespace","sweepee_1",
                                       "-y"," 2"],
                            output='screen')

but gazebo compains I am adding all links and joints twice :

gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fshoulder_link?p=pose3d/world_pose] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fshoulder_link?p=vector3d/world_linear_velocity] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fshoulder_link?p=vector3d/world_angular_velocity] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fshoulder_link?p=vector3d/world_linear_acceleration] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fshoulder_link?p=vector3d/world_angular_acceleration] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fupper_arm_link?p=pose3d/world_pose] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fupper_arm_link?p=vector3d/world_linear_velocity] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fupper_arm_link?p=vector3d/world_angular_velocity] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fupper_arm_link?p=vector3d/world_linear_acceleration] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fupper_arm_link?p=vector3d/world_angular_acceleration] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fforearm_link?p=pose3d/world_pose] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fforearm_link?p=vector3d/world_linear_velocity] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fforearm_link?p=vector3d/world_angular_velocity] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fforearm_link?p=vector3d/world_linear_acceleration] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fforearm_link?p=vector3d/world_angular_acceleration] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_1_link?p=pose3d/world_pose] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_1_link?p=vector3d/world_linear_velocity] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_1_link?p=vector3d/world_angular_velocity] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_1_link?p=vector3d/world_linear_acceleration] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_1_link?p=vector3d/world_angular_acceleration] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_2_link?p=pose3d/world_pose] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_2_link?p=vector3d/world_linear_velocity] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_2_link?p=vector3d/world_angular_velocity] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_2_link?p=vector3d/world_linear_acceleration] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_2_link?p=vector3d/world_angular_acceleration] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_3_link?p=pose3d/world_pose] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_3_link?p=vector3d/world_linear_velocity] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_3_link?p=vector3d/world_angular_velocity] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_3_link?p=vector3d/world_linear_acceleration] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/link/sweepee_1%2fwrist_3_link?p=vector3d/world_angular_acceleration] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/joint/sweepee_1%2fshoulder_pan_joint?p=axis/0/double/position] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/joint/sweepee_1%2fshoulder_pan_joint?p=axis/0/double/velocity] already registered
[gzserver-1] [Err] [Model.cc:982] can't have two joint with the same name
[gzserver-1] [Err] [Model.cc:983] EXCEPTION: can't have two joints with the same name [sw1::sweepee_1/shoulder_pan_joint]
[gzserver-1] 
[gzserver-1] 
[gzserver-1] [Err] [Model.cc:272] LoadJoint Failed
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/joint/sweepee_1%2fshoulder_lift_joint?p=axis/0/double/position] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/joint/sweepee_1%2fshoulder_lift_joint?p=axis/0/double/velocity] already registered
[gzserver-1] [Err] [Model.cc:982] can't have two joint with the same name
[gzserver-1] [Err] [Model.cc:983] EXCEPTION: can't have two joints with the same name [sw1::sweepee_1/shoulder_lift_joint]
[gzserver-1] 
[gzserver-1] 
[gzserver-1] [Err] [Model.cc:272] LoadJoint Failed
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/joint/sweepee_1%2felbow_joint?p=axis/0/double/position] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/joint/sweepee_1%2felbow_joint?p=axis/0/double/velocity] already registered
[gzserver-1] [Err] [Model.cc:982] can't have two joint with the same name
[gzserver-1] [Err] [Model.cc:983] EXCEPTION: can't have two joints with the same name [sw1::sweepee_1/elbow_joint]
[gzserver-1] 
[gzserver-1] 
[gzserver-1] [Err] [Model.cc:272] LoadJoint Failed
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/joint/sweepee_1%2fwrist_1_joint?p=axis/0/double/position] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/joint/sweepee_1%2fwrist_1_joint?p=axis/0/double/velocity] already registered
[gzserver-1] [Err] [Model.cc:982] can't have two joint with the same name
[gzserver-1] [Err] [Model.cc:983] EXCEPTION: can't have two joints with the same name [sw1::sweepee_1/wrist_1_joint]
[gzserver-1] 
[gzserver-1] 
[gzserver-1] [Err] [Model.cc:272] LoadJoint Failed
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/joint/sweepee_1%2fwrist_2_joint?p=axis/0/double/position] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/joint/sweepee_1%2fwrist_2_joint?p=axis/0/double/velocity] already registered
[gzserver-1] [Err] [Model.cc:982] can't have two joint with the same name
[gzserver-1] [Err] [Model.cc:983] EXCEPTION: can't have two joints with the same name [sw1::sweepee_1/wrist_2_joint]
[gzserver-1] 
[gzserver-1] 
[gzserver-1] [Err] [Model.cc:272] LoadJoint Failed
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/joint/sweepee_1%2fwrist_3_joint?p=axis/0/double/position] already registered
[gzserver-1] [Wrn] [IntrospectionManager.cc:109] Item [data://world/default/model/sw1/joint/sweepee_1%2fwrist_3_joint?p=axis/0/double/velocity] already registered
[gzserver-1] [Err] [Model.cc:982] can't have two joint with the same name
[gzserver-1] [Err] [Model.cc:983] EXCEPTION: can't have two joints with the same name [sw1::sweepee_1/wrist_3_joint]
[gzserver-1] 
[gzserver-1] 
[gzserver-1] [Err] [Model.cc:272] LoadJoint Failed
[spawn_entity.py-3] [INFO] [1653338001.272152704] [spawn_entity]: Spawn status: SpawnEntity: Successfully spawned entity [sw1]

What am I missing ? Thanks

scpeters commented 1 year ago

how many robots are you spawning? These error messages seem like you are spawning multiple robots with the same name