Skip to content
eterpega edited this page Feb 18, 2018 · 9 revisions

Table Of Contents

URDF vs. SDF

- 기본 구성요소 
  - Links
     - 'Link'는 모델상의 하나의 body의 물리적인 속성을 포함한다.(바퀴,링크,실린더,구 등) 
        각각의 'link'는 다수의 collision, visual 및 sensor 요소를 하위요소로 가질 수 있다.
     - Collision : 'collision' 요소는 다른 요소와의 충돌을 체크하기 위한 geometry 요소를 지닌다.
                   'collision geometry'는 단순형상 혹은 삼각형의 메쉬가 될 수 있다. (*.dae, *.stl)  
     - Visual : 'visual' 요소는 'link'요소의 시각화를 위해 사용되어 진다. (*.dae, *.stl 지원)
     - Inertial : 'inertial' 요소는 'link'의 동적 속성을 기술한다. (질량, 회전관성모멘트 등)
  - Sensor
     - 'sensor' 요소는 추가된 plugin을 통해 'world'로부터 특정 가상 센서의 데이터를 취득한다.
  - Joints
     - 'joint' 요소는 서로다른 두개의 'link'간의 구속관계를 표현한다. 
     - 'parent' 와 'child' 간의 회전축/이동조인트/고정조인트 등의 구속조건을 제공한다.
     - 'joint limit' 을 통해 조인트의 이동가능 범위를 제한한다.
  - Transmission
     - link와 link간의 연결되는 joint의 감속기를 적용할때 사용한다.
  - Plugins
     - 모델을 제어하기 위해 controller와 'shared library'를 통해 토픽/프레임 등을 공유한다..  
  • URDF(Unified Robot Description Format)

    • An XML format for representing a robot model
    • The description of a robot consists of a set of link (part) elements, and a set of joint elements connecting the links together
      • description of kinematic and dynamic description of the robot
      • description of visual representation of the robot
      • description of collision model of the robot
      • http://wiki.ros.org/urdf/Examples
  • SDF(Simulation Description Format)

    • An XML format that describes objects and environments for robot simulators, visualization, and control
    • It contains a complete description for everything from the world level down to the robot level, including:
      • Scene: Ambient lighting, sky properties, shadows.
      • Physics: Gravity, time step, physics engine.
      • Models: Collection of links, collision objects, joints, and sensors.
      • Lights: Point, spot, and directional light sources.
      • Plugins: World, model, sensor, and system plugins.
      • http://gazebosim.org/sdf.html
  • URDF vs. SDF

    • URDF는 하나의 'robot' 모델에 대해 기술하는 포맷이며, 'world'상에서 'robot'의 포즈를 결정 할 수 없는 단점이 있다.

    • SDF는 'world'상에서 여러개의 'robot' 모델의 포즈를 정의할 수 있을 뿐 만 아니라, 모델간의 'friction' 및 'light', 'heightmaps' 등의 'world'속성 정의도 가능하다.

    • 구조적 차이점

      URDF

      <?xml version="1.0"?>
      <robot name="my_robot">
      
         <link name="link">
           <visual>
             <origin rpy="1.57075 0 0" xyz="0 0 0"/> 
           </visual>
          ...
         </link>
      
         <joint name="joint1" type="fixed">
          ...
         </joint>
      
         <plugin filename="libMyPlugin.so" name="my_plugin"/>
      
      </robot>
      

      SDF

      <?xml version="1.0" ?>
      <sdf version="1.5">
        <world name="default">
          <physics type="ode">
           ...
          </physics>
      
          <scene>
           ...
          </scene>  
      
          <light>
           ...
          </light>
        </world>
      
        <model name="box">
          <pose>0 0 0.5 0 0 0</pose>
          <static>false</static>
      
          <link name="link">
            <pose>0 0 0 0 0 0</pose>
            ...
          </link>
      
          <joint type="revolute" name="my_joint">
            ...
          </joint>
      
          <plugin filename="libMyPlugin.so" name="my_plugin"/>
      
        </model>
      </sdf>
      

xacro

  • Xacro (XML Macros)

    • Xacro 는 XML macro 언어로써, 반복되는 작업을 모듈화하여 재사용성이 용이하도록 도와준다.
    • http://wiki.ros.org/xacro
  • example

  • sample

    <xacro:macro name="pr2_arm" params="suffix parent reflect">
      <pr2_upperarm suffix="${suffix}" reflect="${reflect}" parent="${parent}" />
      <pr2_forearm suffix="${suffix}" reflect="${reflect}" parent="elbow_flex_${suffix}" />
    </xacro:macro>
    
    <xacro:pr2_arm suffix="left" reflect="1" parent="torso" />
    <xacro:pr2_arm suffix="right" reflect="-1" parent="torso" />
    

    original

    <pr2_upperarm suffix="left" reflect="1" parent="torso" />
    <pr2_forearm suffix="left" reflect="1" parent="elbow_flex_left" />
    <pr2_upperarm suffix="right" reflect="-1" parent="torso" />
    <pr2_forearm suffix="right" reflect="-1" parent="elbow_flex_right" />
    

URDF & SDF structure

  • URDF structure

    • 기본 구조
    <robot>
      <link>
        <visual>
           <origin/>
           <geometry/>
           <meterial/>
        </visual>
        <inetial>
           <origin/> 
           <mass/>
           <inertia/>
        </inertial>
        <collision>
           <origin/>
           <geometry/>
        </collision>
      </link>
    
      <joint name=" " type="fixed">
        <origin/>
        <parent/>
        <child/>
        <axis/>
        <dynamics>
           <damping/>
           <friction/>
        </dynamics>
        <limit>
           <upper/>
           <lower/>
           <effort/>
           <velocity/>
      </joint>
      <sensor>
        <camera>
           <image>
              <width/><height/><format/><hfov/><near/><far/>
           </image>
        </camera>
      </sensor>
    </robot>
    

    .

    • link 예제
    <link name="base_link">
        <visual>
          <origin rpy="1.57075 0 0" xyz="0 0 0"/>
          <geometry>
            <cylinder length="0.6" radius="0.2"/>
          </geometry>
          <material name="blue">
            <color rgba="0 0 .8 1"/>
          </material>
        </visual>
        <collision>
          <origin rpy="1.57075 0 0" xyz="0 0 0"/>
          <geometry>
            <cylinder length="0.6" radius="0.2"/>
          </geometry>
        </collision>
        <inertial>
          <mass value="10"/>
          <origin xyz="-0.001201 0.024513 -0.098231" rpy="0 0 0"/>
          <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
        </inertial>
      </link>
    
    • joint 예제
    <joint name="right_gripper_joint" type="revolute">
        <axis xyz="0 0 -1"/>
        <limit effort="1000.0" lower="0.0" upper="0.548" velocity="0.5"/>
        <origin rpy="0 0 0" xyz="0.2 -0.01 0"/>
        <parent link="gripper_pole"/>
        <child link="right_gripper"/>
    </joint>
    
    • plugin 예제
    <gazebo>
      <plugin name="differential_drive_controller" filename="libdiffdrive_plugin.so">
        ... plugin parameters ...
      </plugin>
    </gazebo>
    
  • SDF structure

    • (example) Gazebo-9DOF-arm

    • (example) Willowgarage Model SDF File

      <?xml version="1.0" ?>
      <sdf version="1.4">
        <model name="willowgarage">
          <static>true</static>
          <pose>-20 -20 0 0 0 0</pose>
          <link name="walls">
            <collision name="collision">
              <geometry>
                <mesh>
                  <uri>model://willowgarage/meshes/willowgarage_collision.dae</uri>
                </mesh>
              </geometry>
            </collision>
            <visual name="visual">
              <geometry>
                <mesh>
                  <uri>model://willowgarage/meshes/willowgarage_visual.dae</uri>
                </mesh>
              </geometry>
              <cast_shadows>false</cast_shadows>
            </visual>
          </link>
        </model>
      </sdf>  
      
    • link 예제 (link)

      <link name="trunk">
        <pose>0.0 0.0 1.051 0.0 0.0 0.0</pose>
        <!-- Height of leg + thigh + 0.5 * trunk-->
        <inertial>
          <mass>37.0762</mass>
          <pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
          <!-- Link mass is centered -->
          <inertia>
            <ixx>1.674614776</ixx>
            <ixy>0.0</ixy>
            <ixz>0.0</ixz>
            <iyz>0.0</iyz>
            <iyy>0.01679029</iyy>
            <izz>1.674614776</izz>
          </inertia>
        </inertial>
        <collision name="collision">
          <pose>0 0 0.5 0 0 0</pose>
          <geometry>
            <cylinder>
              <length>0.376</length>
              <radius>0.02</radius>
            </cylinder>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <cylinder>
              <length>0.376</length>
              <radius>0.02</radius>
            </cylinder>
          </geometry>
        </visual>
        <sensor name="trunk_contact" type="contact">
          <contact>
            <collision>collision</collision>
          </contact>
        </sensor>
      </link>
      
    • joint 예제 (link)

      <joint name="right_ankle" type="revolute">
        <parent>right_leg</parent>
        <child>right_foot</child>
        <pose>0.0 0.0 -0.041 0.0 -1.570796327 0.0</pose>
        <axis>
          <xyz>0.0 1 0.0</xyz>
          <limit>
            <lower>-0.680678408</lower>
            <upper>0.726056969</upper>
          </limit>
          <dynamics>
            <damping>0.05</damping>
          </dynamics>
        </axis>
      </joint>
      
    • plugin 예제

      <model name="your_robot_model">
        <plugin name="differential_drive_controller" filename="libdiffdrive_plugin.so">
        ... plugin parameters ...
        </plugin>
      </model>
      

URDF Check

  • 설치
    sudo apt-get install liburdfdom-tools

  • URDF 문법검사

    • 방법1 $ check_urdf myrobot.urdf
    • 방법2 $ rosrun urdf_parser check_urdf myrobot.urdf
  • URDF 그래프표시

    • 방법1 $ urdf_to_graphiz myrobot.urdf $ evince myrobot.pdf
    • 방법2 $ rosrun urdf_parser urdf_to_graphiz brazo.urdf

URDF-SDF converter

  • Gazebbo 7.0 이전 버전 $ gzsdf print urdfname.urdf > newname.sdf
  • Gazebbo 7.0 이전 버전 $ gz sdf --print my_urdf.urdf > my_sdf.sdf
  • alt) $ /usr/local/Cellar/gazebo8/8.1.0/bin/gz sdf --convert simple_box.urdf

Additional Readings

Table of Contents




Clone this wiki locally