티스토리 뷰

이번 게시물의 목표는 Mujoco XML 파일(MJCF)에 대해서 알아보는 것이다.

필자에게 MJCF에 기술되어 있는 각 요소나 기능이 무엇인지 물어본다면, 정확한 답변은 불가능하다.

각 기능을 세세하게 설명하는 것보다 초보자로서 어떻게 이해하였는지와 경험에 초점을 두면서 설명하고자 한다.

작성하다보니 내용이 너무 길어져서 Chapter 2는 나누어서 작성하려 한다.


Mujoco에서 로봇을 시각화 하기 위해 각 body가 어떻게 연결되어 있는지 정의해야 한다.

ROS에서는 이를 위해 URDF라는 XML 파일 포맷을 사용한다.

 

urdf - ROS Wiki

kinetic melodic noetic   Show EOL distros:  EOL distros:   electric fuerte groovy hydro indigo jade lunar diamondback: Only showing information from the released package extracted on Unknown. No API documentation available. Please see this page for in

wiki.ros.org

Mujoco에서도 URDF 파일을 사용해서 모델을 불러올 수 있지만, 기본적으로 MJCF 파일을 사용한다.

아래의 페이지로 들어가보면 Mujoco 로봇 모델을 만들기 위한 XML 요소, 속성과 관련된 레퍼런스가 나와있다.

 

XML Reference — MuJoCo documentation

This is not a model element, but rather a macro which expands into multiple model elements representing a composite object. These elements are bodies (with their own joints, geoms and sites) that become children of the parent body containing the macro, as

mujoco.readthedocs.io

처음부터 레퍼런스를 보게 되면 무슨 말인지 모르겠고 내용이 너무 많아 머리가 아프다..

따라서, 잘 정리되어 있는 mujoco 엔진 기반 시뮬레이터 프레임워크를 찾는게 중요하다.

 

다행히도 robosuite 라는 로봇 학습을 위한 프레임워크가 있다.

robosuite는 2017년에 스탠포드 대학 비전 연구진(http://svl.stanford.edu/)과 텍사스 대학 AI 연구진(https://rpl.cs.utexas.edu/)에 의해 개발되었고, 현재 최신 버전은 1.3 버전이다.

데모만 돌려봤을 뿐인데 정말 신기했고 코드를 살펴보니 쉽지가 않아 보였다.

그래서 선택한 방법은 첫 버전인 0.1.0 버전부터 보는 것이었다. 그나마 로봇의 종류도 적고, 코드 양이 적어서 어떻게 구현했는지 감이라도 잡을 수 있었다.

 

앞으로 필자는 robosuite를 바탕으로 어떻게 Pick and Place 모듈을 개발했는지 설명하고자 한다. (사실 아직 구현 중이지만 올해 안에 모듈을 완성하는게 목표이다.) robosuite 코드 중 필요하다고 생각하는 부분을 가져와서 재구성하고 있다.

 

GitHub - ARISE-Initiative/robosuite: robosuite: A Modular Simulation Framework and Benchmark for Robot Learning

robosuite: A Modular Simulation Framework and Benchmark for Robot Learning - GitHub - ARISE-Initiative/robosuite: robosuite: A Modular Simulation Framework and Benchmark for Robot Learning

github.com

robosuite를 다운로드해서 다음의 경로(robosuite/robosuite/models/assets)로 들어가보자.

$ git clone https://github.com/ARISE-Initiative/robosuite.git
$ cd robosuite/robosuite/models/assets
$ ls -al
├── arenas
├── base.xml
├── bullet_data
├── demonstrations
├── grippers
├── light_maps
├── mounts
├── objects
├── robots
└── textures

base.xml이라는 파일 1개와 나머지 9개의 디렉토리들로 구성되어 있다.

robots 디렉토리로 들어가보면 7가지의 로봇이 있는데 필자는 Franka Emika에서 만든 panda를 선택했다.

robot의 mjcf 파일에 해당하는 robot.xml과 world의 mjcf 파일에 해당하는 base.xml에 대해 분석해 보자.


robot.xml

먼저 panda 로봇의 mjcf 파일(robot.xml)을 살펴보고자 한다.

<mujoco model="panda">
    <actuator>
        <!-- Physical limits of the actuator. -->
        <motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint1" name="torq_j1"/>
        <motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint2" name="torq_j2"/>
        <motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint3" name="torq_j3"/>
        <motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint4" name="torq_j4"/>
        <motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint5" name="torq_j5"/>
        <motor ctrllimited="true" ctrlrange="-12.0 12.0" joint="joint6" name="torq_j6"/>
        <motor ctrllimited="true" ctrlrange="-12.0 12.0" joint="joint7" name="torq_j7"/>
    </actuator>
    <asset>
        <mesh name="link0" file="meshes/link0.stl" />
        <mesh name="link1" file="meshes/link1.stl" />
        <mesh name="link2" file="meshes/link2.stl" />
        <mesh name="link3" file="meshes/link3.stl" />
        <mesh name="link4" file="meshes/link4.stl" />
        <mesh name="link5" file="meshes/link5.stl" />
        <mesh name="link6" file="meshes/link6.stl" />
        <mesh name="link7" file="meshes/link7.stl" />
        <mesh name="link0_vis" file="meshes/link0_vis.stl" />
        <mesh name="link1_vis" file="meshes/link1_vis.stl" />
        <mesh name="link2_vis" file="meshes/link2_vis.stl" />
        <mesh name="link3_vis" file="meshes/link3_vis.stl" />
        <mesh name="link4_vis" file="meshes/link4_vis.stl" />
        <mesh name="link5_vis" file="meshes/link5_vis.stl" />
        <mesh name="link6_vis" file="meshes/link6_vis.stl" />
        <mesh name="link7_vis" file="meshes/link7_vis.stl" />
    </asset>
    <worldbody>
        <body name="base" pos="0 0 0">
            <!-- robot view -->
            <camera mode="fixed" name="robotview" pos="1.0 0 0.4" quat="0.653 0.271 0.271 0.653"/>
            <inertial diaginertia="0 0 0" mass="0" pos="0 0 0"/>
            <!-- mount attached here -->
            <body name="link0" pos="0 0 0">
                <inertial pos="0 0 0.05" mass="4" diaginertia="0.4 0.4 0.4" />
                <geom type="mesh" contype="0" conaffinity="0" group="1" mesh="link0_vis" name="link0_visual" rgba="1 1 1 1" />
                <geom type="mesh" group="0" mesh="link0" name="link0_collision"/>
                <body name="link1" pos="0 0 0.333">
                    <inertial pos="0 0 -0.07" mass="3" diaginertia="0.3 0.3 0.3" />
                    <joint name="joint1" pos="0 0 0" axis="0 0 1" limited="true" range="-2.8973 2.8973" damping="0.1"/>
                    <geom type="mesh" contype="0" conaffinity="0" group="1" mesh="link1_vis" name="link1_visual" rgba="1 1 1 1" />
                    <geom type="mesh" group="0" mesh="link1" name="link1_collision"/>
                    <body name="link2" pos="0 0 0" quat="0.707107 -0.707107 0 0">
                        <inertial pos="0 -0.1 0" mass="3" diaginertia="0.3 0.3 0.3" />
                        <joint name="joint2" pos="0 0 0" axis="0 0 1" limited="true" range="-1.7628 1.7628" damping="0.1"/>
                        <geom type="mesh" contype="0" conaffinity="0" group="1" mesh="link2_vis" name="link2_visual" rgba="1 1 1 1" />
                        <geom type="mesh" group="0" mesh="link2" name="link2_collision"/>
                        <body name="link3" pos="0 -0.316 0" quat="0.707107 0.707107 0 0">
                            <inertial pos="0.04 0 -0.05" mass="2" diaginertia="0.2 0.2 0.2" />
                            <joint name="joint3" pos="0 0 0" axis="0 0 1" limited="true" range="-2.8973 2.8973" damping="0.1"/>
                            <geom type="mesh" contype="0" conaffinity="0" group="1" mesh="link3_vis" name="link3_visual" rgba="1 1 1 1" />
                            <geom type="mesh" group="0" mesh="link3" name="link3_collision"/>
                            <body name="link4" pos="0.0825 0 0" quat="0.707107 0.707107 0 0">
                                <inertial pos="-0.04 0.05 0" mass="2" diaginertia="0.2 0.2 0.2" />
                                <joint name="joint4" pos="0 0 0" axis="0 0 1" limited="true" range="-3.0718 -0.0698" damping="0.1"/>
                                <geom type="mesh" contype="0" conaffinity="0" group="1" mesh="link4_vis" name="link4_visual" rgba="1 1 1 1" />
                                <geom type="mesh" group="0" mesh="link4" name="link4_collision"/>
                                <body name="link5" pos="-0.0825 0.384 0" quat="0.707107 -0.707107 0 0">
                                    <inertial pos="0 0 -0.15" mass="2" diaginertia="0.2 0.2 0.2" />
                                    <joint name="joint5" pos="0 0 0" axis="0 0 1" limited="true" range="-2.8973 2.8973" damping="0.1"/>
                                    <geom type="mesh" contype="0" conaffinity="0" group="1" mesh="link5_vis" name="link5_visual" rgba="1 1 1 1" />
                                    <geom type="mesh" group="0" mesh="link5" name="link5_collision"/>
                                    <body name="link6" pos="0 0 0" quat="0.707107 0.707107 0 0">
                                        <inertial pos="0.06 0 0" mass="1.5" diaginertia="0.1 0.1 0.1" />
                                        <joint name="joint6" pos="0 0 0" axis="0 0 1" limited="true" range="-0.0175 3.7525" damping="0.01"/>
                                        <geom type="mesh" contype="0" conaffinity="0" group="1" mesh="link6_vis" name="link6_visual" rgba="1 1 1 1" />
                                        <geom type="mesh" group="0" mesh="link6" name="link6_collision"/>
                                        <body name="link7" pos="0.088 0 0" quat="0.707107 0.707107 0 0">
                                            <inertial pos="0 0 0.08" mass="0.5" diaginertia="0.05 0.05 0.05" />
                                            <joint name="joint7" pos="0 0 0" axis="0 0 1" limited="true" range="-2.8973 2.8973" damping="0.01"/>
                                            <geom type="mesh" contype="0" conaffinity="0" group="1" mesh="link7_vis" name="link7_visual" rgba="1. 1. 1. 1." />
                                            <geom type="mesh" group="0" mesh="link7" name="link7_collision"/>
                                            <!-- rotate 135deg to align physically to the tool-->
                                            <body name="right_hand" pos="0 0 0.1065" quat="0.924 0 0 -0.383">
                                                <inertial pos="0 0 0" mass="0.5" diaginertia="0.05 0.05 0.05" />
                                                <!-- This camera points out from the eef. -->
                                                <camera mode="fixed" name="eye_in_hand" pos="0.05 0 0" quat="0 0.707108 0.707108 0" fovy="75"/>
                                                <!-- to add gripper -->
                                            </body>
                                        </body>
                                    </body>
                                </body>
                            </body>
                        </body>
                    </body>
                </body>
            </body>
        </body>
    </worldbody>
</mujoco>

굉장히 길지만 어렵지는 않다. 오히려 urdf보다 직관적이기에 보기 편하다는 생각이 든다.


더보기

여기서 각각의 속성들의 value를 어떻게 얻어냈는지 궁금해 할 수 있다. panda urdf 파일을 mjcf 파일로 변환해주면 된다.

.mujoco/mujoco210/bin 안에 compile 바이너리 파일을 실행하면 mjcf 파일로 변환된다. 만약 에러가 나온다면 해당 경로에 stl 또는 dae 파일을 못 찾는다는 에러가 나올 수 있는데 파일을 해당 경로로 복사해서 해결하면 된다.

$ cd .mujoco/mujoco210/bin
$ ./complie
 Usage:  compile infile outfile
   infile can be in mjcf, urdf, mjb format
   outfile can be in mjcf, mjb, txt format

 Example:  compile model.xml model.mjb

$ ./compile (your_urdf_path)/panda.urdf (save_path)/robot.xml

최상위 태그를 보면 mjcf 파일이라는 것을 나타내기 위해 시작과 끝을 <mujoco model="panda">, </mujoco> 로 감싸준 것을 볼 수 있다. 그리고 이 로봇 모델의 이름은 panda라는 것도 알 수 있다.

 

그 다음 태그는 actuator, asset, worldbody 태그로 구분되어 있다.

 

1. worldbody tag

 

XML Reference — MuJoCo documentation

This is not a model element, but rather a macro which expands into multiple model elements representing a composite object. These elements are bodies (with their own joints, geoms and sites) that become children of the parent body containing the macro, as

mujoco.readthedocs.io

먼저 worldbody 태그의 일부만 보자. 

<worldbody>
    <body name="base" pos="0 0 0">
        <!-- robot view -->
        <camera mode="fixed" name="robotview" pos="1.0 0 0.4" quat="0.653 0.271 0.271 0.653"/>
        <inertial diaginertia="0 0 0" mass="0" pos="0 0 0"/>
        <!-- mount attached here -->
        <body name="link0" pos="0 0 0">
            <inertial pos="0 0 0.05" mass="4" diaginertia="0.4 0.4 0.4" />
            <geom type="mesh" contype="0" conaffinity="0" group="1" mesh="link0_vis" name="link0_visual" rgba="1 1 1 1" />
            <geom type="mesh" group="0" mesh="link0" name="link0_collision"/>
            <body name="link1" pos="0 0 0.333">
                <inertial pos="0 0 -0.07" mass="3" diaginertia="0.3 0.3 0.3" />
                <joint name="joint1" pos="0 0 0" axis="0 0 1" limited="true" range="-2.8973 2.8973" damping="0.1"/>
                <geom type="mesh" contype="0" conaffinity="0" group="1" mesh="link1_vis" name="link1_visual" rgba="1 1 1 1" />
                <geom type="mesh" group="0" mesh="link1" name="link1_collision"/>
                <body name="link2" pos="0 0 0" quat="0.707107 -0.707107 0 0">

로봇의 body(link), body의 inertial, body의 geometry(collision, visual), body와 body를 연결해주는 joint 태그가 기술되어있다. 각 태그의 속성은 태그마다 다르며 자세한 내용은 레퍼런스를 찾아보자.

알게된 내용을 정리해보면

  • body
    • offset은 position(위치)과 orientation(방향)으로 결정되며 orientation은 quaternion을 이용한다. robosuite에서는 orientation 기술 방법으로 quaternion을 사용했지만 axisangle, euler와 같은 방법으로도 가능하다. 
 

Modeling — MuJoCo documentation

MJCF uses several mechanisms for model creation which span multiple model elements. To avoid repetition we describe them in detail only once in this section. These mechanisms do not correspond to new simulation concepts beyond those introduced in the Compu

mujoco.readthedocs.io

  • geom
    • 충돌 체크를 위한 collision과 시각화를 위한 visual 부분으로 나뉘어 있다.
    • collision과 visual의 속성 중 group, contype, conaffinity을 보자.
      • group(default '0')
        • group은 렌더링 활성화를 위한 속성이다.
        • 값이 0이라고 해서 비활성화를 하는 것이 아니다.
        • 렌더링할 geom이 collision인지 visual인지 group을 짓는 것이 목적이다.
        • collision(group='0') 렌더링을 비활성화 하고자 한다면 코드에 viewer.vopt.geomgroup[0] = 0 이라고 적어주면 된다.
        • 예시
      • contype(default '1'), conaffinity(default '1')
        • 충돌 감지 여부를 위한 속성으로 contype, conaffinity이 모두 0이라면 충돌이 일어나지 않는다.
        • 따라서, visual geometry는 오직 시각화만을 위한 용도이다.
  • joint(default 'hinge')
    • joint의 type은 [free, ball, slide, hinge]로 구성되며 default 값은 hinge joint(=revolute joint)이다.
  • camera
    • camera는 option 태그이다.
    • mode가 fixed일 경우 카메라의 시점은 카메라가 정의된 body의 z축과 일치하게 된다.
    • 카메라의 시야각(fovy), 카메라 프레임 위치(pos), 방향(quat)을 조절할 수 있다.
    • 파일을 실행하여 Tab 키를 누르면 카메라 시점이 바뀌게 되며, 해당 시점으로 고정된다.
    • 예시

2. actuator tag

 

Modeling — MuJoCo documentation

MJCF uses several mechanisms for model creation which span multiple model elements. To avoid repetition we describe them in detail only once in this section. These mechanisms do not correspond to new simulation concepts beyond those introduced in the Compu

mujoco.readthedocs.io

다음은 actuator 태그에 대한 설명이다.

 

로봇의 관절을 구동하기 위해 Actuator가 필요하다. 모든 joint에 대해 actuator를 작성해야 한다.

actuator의 종류는 총 5가지로 motor, position, velocity, cylinder, muscle이 있다.

매니퓰레이터의 경우 대부분 motor, position, velocity를 사용한다.

 

아래의 actuator 예시를 보자.

panda robot의 joint는 joint1, joint2, ..., joint7가 있으며 각 joint를 움직이기 위해 motor라는 태그로 토크 범위 까지 지정해주었다.

이처럼 motor를 사용한다면 제어 목적에 맞게 joint position, velocity, torque 제어를 위한 코드를 작성해 주어야 한다.

<actuator>
    <!-- Physical limits of the actuator. -->
    <motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint1" name="torq_j1"/>
    <motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint2" name="torq_j2"/>
    <motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint3" name="torq_j3"/>
    <motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint4" name="torq_j4"/>
    <motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint5" name="torq_j5"/>
    <motor ctrllimited="true" ctrlrange="-12.0 12.0" joint="joint6" name="torq_j6"/>
    <motor ctrllimited="true" ctrlrange="-12.0 12.0" joint="joint7" name="torq_j7"/>
</actuator>

반면 position, velocity의 경우 서보 제어를 위한 태그이다.

ctrlrange 안의 값만 넣어 준다면 position, velocity 제어가 가능하다.

아래의 actuator는 panda robot의 gripper에 해당하며, position 제어를 하기 위해 position 태그를 이용하였다.

<actuator>
    <position name='finger_1' ctrllimited="true" kp="20" joint='finger_joint' ctrlrange='0 0.7'/>
    <position name='finger_2' ctrllimited="true" kp="20" joint='right_outer_knuckle_joint' ctrlrange='-0.7 0'/>
</actuator>

 

3. asset tag

 

Overview — MuJoCo documentation

In the modern approach to contact dynamics, the forces or impulses caused by frictional contacts are usually defined as the solution to a linear or non-linear complementarity problem (LCP or NCP), both of which are NP-hard. MuJoCo is based on a different f

mujoco.readthedocs.io

마지막으로 asset 태그에 대한 설명이다.

asset은 mesh, skin, texture, material 등에 해당하는 파일의 경로나 속성을 한 번에 모아주는 역할을 한다.

아래의 예시는 panda robot의 asset 일부이며, link0 mesh 파일 경로는 meshes/link0.stl 라는 것이다.

<asset>
    <mesh name="link0" file="meshes/link0.stl" />
    <mesh name="link1" file="meshes/link1.stl" />
    <mesh name="link2" file="meshes/link2.stl" />
    <mesh name="link3" file="meshes/link3.stl" />
    <mesh name="link4" file="meshes/link4.stl" />
    <mesh name="link5" file="meshes/link5.stl" />
    <mesh name="link6" file="meshes/link6.stl" />
    <mesh name="link7" file="meshes/link7.stl" />
</asset>

base.xml

지금까지 robot의 mjcf 파일에 대해 설명하였고, 이 글의 마지막 부분인 base.xml에 대한 설명이다.

 

mujoco에서 Robot, Arena, Object, Gripper, Mount 등 환경을 구성하는 모든 요소를 시뮬레이션 하려면 한데 모아야 한다.

다시 말해서, robot.xml, arena.xml, object.xml, gripper.xml, mount.xml 등 mjcf 파일을 한 곳에 모아 시뮬레이션 모델을 만드는 것이다. robosuite에서는 base.xml 파일에 모든 asset, actuator, worldbody 태그를 모은다.

이를 위해서, 코드를 작성해야 하는데 다음 챕터에서 설명하고자 한다.

 

아래의 예시는 base.xml 예시이며, compiler, option, size 태그가 추가된 것을 볼 수 있다.

이 내용은 레퍼런스를 참고하여 이해했으면 좋겠다.

<!-- This is the base xml for all physics simulations. Set global configs here. -->
<mujoco model="base">
  <compiler angle="radian" meshdir="meshes/" inertiagrouprange="0 0"/>
  <option impratio="20" cone="elliptic" density="1.2" viscosity="0.00002"/>
  <size nconmax="5000" njmax="5000"/>

  <asset>
  </asset>

  <visual>
    <map znear="0.001" />
  </visual>

  <actuator>
  </actuator>

  <worldbody>
  </worldbody>

  <equality>
  </equality>
</mujoco>

 

이상으로 Mujoco XML 파일 분석을 마무리한다.

분석할 때, 레퍼런스를 참고하면서 값도 바꿔보고 무슨 내용인지 모르겠다면 robosuite 깃허브나 deepmind 깃허브 이슈를 활용해 질문하는 것을 추천한다.

 

다음 글에서는 코드 예시를 통해 기본 시뮬레이션 데모를 보여줄 예정이다.

긴 글 읽어주셔서 감사드리며, 피드백은 언제나 환영이다.

댓글
공지사항
최근에 올라온 글
최근에 달린 댓글
Total
Today
Yesterday
링크
«   2024/11   »
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