Skip to content

Robot Model Visualization

indy7_description package

1
2
3
4
5
6
├── indy7_description
    ├── urdf
    ├── launch
    ├── rviz_config
    ├── meshes
    └──  ...

The indy7_description package includes the model files (URDF) for use with RViz and Gazebo simulator.

Robot Model

URDF (The Universal Robotic Description Format)is an XML-format file describing the kinematic and dynamic elements of the robot. Xacro is an XML macro language that constructs shorter and more readable XML files by using macros that expand to larger XML expressions. In the urdf folder of the indy7_description package, There's a xacro file(indy7.xacro) describing Indy7 robot.

The code below is link0, joint0 element of indy7.xacro.

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
...

<link name="link0">
  <visual>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <mesh filename="package://indy7_description/meshes/stl/Indy7_0.stl"/>
    </geometry>
    <material name="${indy_material}"/>
  </visual>
  <collision>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <cylinder length="0.06" radius="0.102"/>
    </geometry>
  </collision>
  <inertial>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <mass value="1.59306955"/>
    <inertia ixx="+0.00572623" iyy="+0.00558959" izz="+0.00966674" ixy="+0.00000251" iyz="-0.00000014" ixz="-0.00011380"/>
  </inertial>
</link>

...

<joint name="joint0" type="continuous">
  <parent link="link0"/>
  <child link="link1"/>
  <origin xyz="0 0 0.03000000" rpy="0 0 0"/>
  <axis xyz="0 0 1"/>
</joint>

...
  • visual : This element specifies the shape of the object for visualization purposes. example above loads a stl model saved in meshes folder as visual element.

  • collision : Collision model is required to check collision, for example with MoveIt. It is posseble to use the same model as visual element, but simpler collision models are often used to reduce computation time. the example above uses a cylinder with 0.102[m]diameter, 0.06[m]height. the unit of geometry is [m](meter).

  • inertia : this element describes the dynamic property of robot.

  • joint : this element connects a link to another link.

For more information about xacro, please visit ROS tutorial xacro.

Launching RViz

Indy7 model can be visualized with RViz. launch file is a file for launching a number of ROS nodes at the same time. The launch file that visualizes Indy7 model in RViz is located in launch folder of indy7_description package. and can be launched with this command.

1
$ roslaunch indy7_description display_indy7.launch

Now you should see 2 windows launched.



by tweaking the joint position value of joint_states_publisher, the position of the robot in RViz can be changed.


Launch File

The code below is display_indy7.launch, from the command above.

1
2
3
4
5
6
7
8
<launch>
    <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find indy7_description)/urdf/indy7.xacro'"/>
    <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
        <param name="use_gui" value="TRUE"/>
    </node>
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher"/>
    <node name="rviz" pkg="rviz" type="rviz" args="-d $(find indy7_description)/rviz_config/indy7.rviz"/>
</launch>
  • robot_description : Reads indy7.xacro. also, It is a parameter for joint_state_publisher node.

  • joint_state_publisher : publishes the joint positions of robot_descriptioin, with /joint_states topic. by setting the value of parameter use_gui TRUE, You can launch the GUI like the picture.

  • robot_state_publisher : Subscribes /joint_states topic, and publishes transform of each link.

  • rviz : launches RViz node, loading rviz configuration file (indy7_description/rviz_config/indy7.rviz). subscribes tf published by robot_state_publisher node, and visualizes them.

Note

To launch a ROS node, roscore should be launched before. However, If you use roslaunch, it will automatically start roscore if it detects that it is not already running.