rosrvizurdf

rviz2 doesnt detect one of the joint/link combos in the urdf while other urdf viewers do


I'm using ROS Jazzy on Ubuntu 24. I have a URDF file written with the help of xacro:

<?xml version="1.0"?>
<robot name="my_robot" xmlns:xacro="http://www.ros.org/wiki/xacro">

  <xacro:include filename="macros.xacro"/>

  <link name="world"></link>

  <joint name="base_joint" type="fixed">
    <origin xyz="1.5 1 0" rpy="0 0 0"/>
    <parent link="world"/>
    <child link="base_link"/>
  </joint>

  <link name="base_link">
    <visual>
      <origin xyz="0 0 0.05" rpy="0 0 0"/>
      <geometry>
        <box size="2.5 1.5 0.1"/>
      </geometry>
      <material name="green"/>
    </visual>
    <collision>
      <origin xyz="0 0 0.05" rpy="0 0 0"/>
      <geometry>
        <box size="2.5 1.5 0.1"/>
      </geometry>
    </collision>
    <xacro:inertial_box mass="12" x="2.5" y="1.5" z="0.1">
      <origin xyz="0 0 0.05" rpy="0 0 0"/>
    </xacro:inertial_box>
  </link>
  
  <joint name="slider_joint" type="prismatic">
    <origin xyz="-1.25 0 0.1" rpy="0 0 0"/>
    <parent link="base_link"/>
    <child link="slider_link"/>
    <axis xyz="1 0 0"/>
    <limit lower="0" upper="2" velocity="100" effort="100"/>
  </joint>

  <link name="slider_link">
    <visual>
      <origin xyz="0 0 0.075" rpy="0 0 0"/>
      <geometry>
          <box size="0.5 0.25 0.15"/>
      </geometry>
      <material name="blue"/>
    </visual>
    <collision>
      <origin xyz="0 0 0.075" rpy="0 0 0"/>
      <geometry>
          <box size="0.5 0.25 0.15"/>
      </geometry>
    </collision>
    <xacro:inertial_box mass="0.5" x="0.5" y="0.25" z="0.15">
      <origin xyz="0 0 0.075" rpy="0 0 0"/>
    </xacro:inertial_box>
  </link>

  <joint name="arm_joint" type="revolute">
    <origin xyz="0.25 0 0.15" rpy="0 0 0"/>
    <parent link="slider_link"/>
    <child link="arm_link"/>
    <axis xyz="0 -1 0"/>
    <limit lower="0" upper="${pi/2}" velocity="100" effort="100"/>
  </joint>

  <xacro:property name="arm_length" value="1"/>
  <xacro:property name="arm_radius" value="0.1"/>
  <link name="arm_link">
    <visual>
      <origin xyz="${arm_length/2} 0 0" rpy="0 ${pi/2} 0"/>
      <geometry>                
          <cylinder length="${arm_length}" radius="${arm_radius}"/>
      </geometry>
      <material name="orange"/>
    </visual>
    <collision>
      <origin xyz="${arm_length/2} 0 0" rpy="0 ${pi/2} 0"/>
      <geometry>                
          <cylinder length="${arm_length}" radius="${arm_radius}"/>
      </geometry>      
    </collision>
    <xacro:inertial_cylinder mass="1.0" length="${arm_length}" radius="${arm_radius}">
      <origin xyz="${arm_length/2} 0 0 " rpy="0 ${pi/2} 0"/>
    </xacro:inertial_cylinder>
  </link>

  <joint name="camera_joint" type="fixed">
        <origin xyz="${arm_length} 0 ${arm_radius + 0.075}"/>
        <parent link="arm_link"/>
        <child link="camera_link"/>        
  </joint>

  <link name="camera_link">
    <visual>
      <origin xyz="-0.03 0 0" rpy="0 0 0"/>
      <geometry>
        <box size="0.06 0.15 0.15" />
      </geometry>
      <material name="white"/>
    </visual>
    <visual>
      <origin xyz="0.03 0 0" rpy="0 ${pi/2} 0"/>
      <geometry>
        <cylinder length="0.06" radius="0.04"/>
      </geometry>
      <material name="blue"/>
    </visual>
    <collision>
      <origin xyz="0.0 0 0" rpy="0 0 0"/>
      <geometry>
        <box size="0.12 0.15 0.15"/>
      </geometry>
    </collision>
    <xacro:inertial_box mass="0.1" x="0.12" y="0.15" z="0.15">
      <origin xyz="0 0 0" rpy="0 0 0"/>
    </xacro:inertial_box>
  </link>

</robot>

This is the macros.xacro file:

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
  
  <!-- inertial calculations from wikipedia https://en.wikipedia.org/wiki/List_of_moments_of_inertia-->

  <xacro:macro name="inertial_sphere" params="mass radius *origin">
    <inertial>
      <xacro:insert_block name="origin"/>
      <mass value="${mass}"/>
      <inertia ixx="${(2/5) * mass * radius*radius}" ixy="0" ixz="0"
               iyy="${(2/5) * mass * radius*radius}" iyz="0"
               izz="${(2/5) * mass * radius*radius}"
      />
    </inertial>
  </xacro:macro>

  <xacro:macro name="inertial_box" params="mass x y z *origin">
    <inertial>
      <xacro:insert_block name="origin"/>
      <mass value="${mass}"/>
      <inertia ixx="${(1/12) * mass * (y*y + z*z)}" ixy="0" ixz="0"
               iyy="${(1/12) * mass * (x*x + z*z)}" iyz="0"
               izz="${(1/12) * mass * (x*x + y*y)}"
      />
    </inertial>
  </xacro:macro>

  <xacro:macro name="inertial_cylinder" params="mass length radius *origin">
    <inertial>
      <xacro:insert_block name="origin"/>
      <mass value="${mass}"/>
      <inertia ixx="${(1/12) * mass * (3*radius*radius + length*length)}" ixy="0" ixz="0"
               iyy="${(1/12) * mass * (3*radius*radius + length*length)}" iyz="0"
               izz="${(1/12) * mass * (3*radius*radius + length*length)}"
      />
    </inertial>
  </xacro:macro>


  <!-- colours -->

  <material name="green">
    <color rgba="0.2 1 0.2 1"/>
  </material>

  <material name="white">
    <color rgba="1 1 1 1"/>
  </material>

  <material name="orange">
    <color rgba="1 0.3 0.1 1"/>
  </material>

  <material name="blue">
    <color rgba="0.2 0.2 1 1"/>
  </material>


</robot>

Viewing this urdf using a VSCode extension works perfectly as expected:

viewing the urdf in VSCode

But, in rviz i get the following error:

viewing the urdf in rviz

I suspect it may have something to do with rviz not recognizing the prismatic joint? But that is just a baseless suspicion i have no idea.

I tried exporting the output of xacro to a file to see if it was an xacro issue, but it wasnt.


Solution

  • You have to broadcast your tf transformations for all the joints defined in the urdf file. You can publish these using a ROS node:

    #!/usr/bin/env python3
    import rclpy
    from rclpy.node import Node
    from geometry_msgs.msg import TransformStamped
    from tf2_ros import TransformBroadcaster
    import math
    
    class TFBroadcaster(Node):
        def __init__(self):
            super().__init__('tf_broadcaster')
            
            # Create a transform broadcaster
            self.broadcaster = TransformBroadcaster(self)
            
            # Create a timer to publish transforms periodically
            self.timer = self.create_timer(0.1, self.broadcast_transforms)  # 10Hz
            
            # Initialize joint states (you might want to subscribe to actual joint states)
            self.slider_position = 0.0
            self.arm_angle = 0.0
    
        def broadcast_transforms(self):
            current_time = self.get_clock().now().to_msg()
            
            # Base link transform
            t = TransformStamped()
            t.header.stamp = current_time
            t.header.frame_id = 'world'
            t.child_frame_id = 'base_link'
            t.transform.translation.x = 1.5
            t.transform.translation.y = 1.0
            t.transform.translation.z = 0.0
            t.transform.rotation.w = 1.0
            self.broadcaster.sendTransform(t)
            
            # Slider link transform
            t = TransformStamped()
            t.header.stamp = current_time
            t.header.frame_id = 'base_link'
            t.child_frame_id = 'slider_link'
            t.transform.translation.x = -1.25 + self.slider_position  # Add slider position
            t.transform.translation.y = 0.0
            t.transform.translation.z = 0.1
            t.transform.rotation.w = 1.0
            self.broadcaster.sendTransform(t)
            
            # Arm link transform
            t = TransformStamped()
            t.header.stamp = current_time
            t.header.frame_id = 'slider_link'
            t.child_frame_id = 'arm_link'
            t.transform.translation.x = 0.25
            t.transform.translation.y = 0.0
            t.transform.translation.z = 0.15
            # Convert arm angle to quaternion (rotation around Y axis)
            t.transform.rotation.w = math.cos(self.arm_angle/2)
            t.transform.rotation.x = 0.0
            t.transform.rotation.y = -math.sin(self.arm_angle/2)  # Negative because of axis direction
            t.transform.rotation.z = 0.0
            self.broadcaster.sendTransform(t)
            
            # Camera link transform
            t = TransformStamped()
            t.header.stamp = current_time
            t.header.frame_id = 'arm_link'
            t.child_frame_id = 'camera_link'
            t.transform.translation.x = 2.0  # arm_length
            t.transform.translation.y = 0.0
            t.transform.translation.z = 0.175  # arm_radius + 0.075
            t.transform.rotation.w = 1.0
            self.broadcaster.sendTransform(t)
    
    def main():
        rclpy.init()
        node = TFBroadcaster()
        try:
            rclpy.spin(node)
        except KeyboardInterrupt:
            pass
        
        node.destroy_node()
        rclpy.shutdown()
    
    if __name__ == '__main__':
        main()
    

    Launch the package

    ros2 run <your-package> <your-node>