SDF 파일 포맷 이해

SDF(Simulation Description Format)는 로봇 및 물리 기반 시뮬레이션을 정의하기 위한 XML 기반의 파일 포맷이다. 주로 로봇의 구조와 물리적 특성을 기술하는 데 사용되며, 가제보(Gazebo)와 같은 시뮬레이션 환경에서 널리 사용된다. Unity는 SDF 포맷을 직접적으로 지원하지 않지만, SDF 파일을 Unity로 변환하는 방법을 사용하여 로봇 모델을 가져올 수 있다.

SDF 파일의 주요 구성 요소는 다음과 같다:

SDF 파일의 구조적 변환

Unity로의 변환을 위해서는 SDF 파일의 각 구성 요소를 Unity의 구조체로 매핑해야 한다. 주요 변환 대상은 로봇의 각 링크와 조인트이다.

링크 변환

SDF의 <link>는 Unity의 GameObject에 해당한다. SDF에서 로봇의 각 링크는 Unity에서 다음과 같은 구성 요소로 변환된다:

SDF 파일에서의 질량 설정:

xml <link name="base_link"> <inertial> <mass>1.0</mass> <inertia> <ixx>0.1</ixx> <iyy>0.1</iyy> <izz>0.1</izz> </inertia> </inertial> </link>

Unity에서는 이 질량 정보를 다음과 같이 적용한다:

csharp Rigidbody rb = gameObject.AddComponent<Rigidbody>(); rb.mass = 1.0f; rb.inertiaTensor = new Vector3(0.1f, 0.1f, 0.1f);

링크의 관성 변환

SDF에서 정의된 관성 행렬은 Unity의 Rigidbody.inertiaTensor에 매핑된다. SDF에서 관성 텐서는 3 \times 3 대칭 행렬로 주어진다. 이는 Unity에서 축에 맞는 관성 텐서 값으로 변환된다.

SDF에서의 관성 행렬은 다음과 같이 정의된다:

\mathbf{I} = \begin{pmatrix} I_{xx} & I_{xy} & I_{xz} \\ I_{xy} & I_{yy} & I_{yz} \\ I_{xz} & I_{yz} & I_{zz} \end{pmatrix}

이 중 대각 성분인 \mathbf{I_{xx}}, \mathbf{I_{yy}}, \mathbf{I_{zz}}를 Unity의 Rigidbody.inertiaTensor로 변환한다. Unity에서는 직교 좌표계로만 처리하므로, 대각 성분만 사용한다.

SDF에서 정의된 관성 텐서:

<inertia>
  <ixx>0.1</ixx>
  <iyy>0.1</iyy>
  <izz>0.1</izz>
</inertia>

Unity에서 적용 예시:

rb.inertiaTensor = new Vector3(0.1f, 0.1f, 0.1f);

조인트 변환

SDF에서 정의된 <joint>는 Unity에서 ConfigurableJoint 또는 HingeJoint로 변환할 수 있다. 두 조인트 시스템의 변환은 다음과 같은 기본 절차로 진행된다:

SDF의 revolute 조인트 정의:

xml <joint name="joint1" type="revolute"> <parent>link1</parent> <child>link2</child> <axis> <xyz>0 0 1</xyz> </axis> </joint>

Unity에서의 조인트 설정:

csharp HingeJoint joint = gameObject.AddComponent<HingeJoint>(); joint.axis = new Vector3(0, 0, 1);

조인트 제약

SDF에서 조인트의 회전 각도나 이동 거리 제한이 있다면, Unity에서 이를 설정해야 한다. HingeJoint의 경우, 각도 제한을 설정할 수 있다. SDF의 <limit> 태그는 Unity의 limits 속성으로 변환된다.

SDF에서의 조인트 제약 설정:

<limit>
  <lower>-1.57</lower>
  <upper>1.57</upper>
</limit>

Unity에서의 변환:

joint.limits = new JointLimits {
  min = -90,
  max = 90
};

URDF와 SDF 간의 차이점

SDF와 URDF는 유사한 목적을 가진 파일 포맷이지만, Unity에서의 변환 작업 시 고려해야 할 몇 가지 차이점이 있다. 이 차이점을 이해하는 것이 변환 과정에서 오류를 최소화하는 데 중요하다.

변환 과정 자동화

SDF 파일에서 Unity로의 변환을 수동으로 하는 것은 매우 비효율적일 수 있으므로, 이 과정을 자동화하는 스크립트를 작성하는 것이 유리한다. Python이나 C#을 사용하여 SDF 파일을 파싱한 뒤, Unity의 오브젝트로 변환하는 자동화 도구를 만들 수 있다.

Python을 통한 SDF 파싱

SDF 파일을 파싱하기 위해 Python의 xml.etree.ElementTree 모듈을 사용할 수 있다. 이 모듈을 사용하면 SDF 파일을 트리 구조로 읽어들여, 각 노드를 순차적으로 파싱할 수 있다.

SDF 파일을 읽고 Unity 변환용 데이터를 추출하는 Python 코드 예시:

import xml.etree.ElementTree as ET

def parse_sdf(sdf_file):
    tree = ET.parse(sdf_file)
    root = tree.getroot()

    for model in root.findall('model'):
        model_name = model.get('name')
        print(f"Model: {model_name}")

        for link in model.findall('link'):
            link_name = link.get('name')
            mass = link.find('inertial/mass').text
            print(f"  Link: {link_name}, Mass: {mass}")

            # 조인트 처리
            for joint in model.findall('joint'):
                joint_name = joint.get('name')
                parent = joint.find('parent').text
                child = joint.find('child').text
                print(f"  Joint: {joint_name}, Parent: {parent}, Child: {child}")

parse_sdf('robot.sdf')

이 파싱 코드를 통해 추출된 정보를 Unity에서 사용할 수 있는 포맷으로 변환하는 C# 스크립트와 연결할 수 있다.

Unity에서 SDF 데이터 적용

파싱된 SDF 데이터를 Unity에 적용하려면, 파싱 결과를 C#으로 가져와서 Unity 오브젝트를 생성하는 스크립트를 작성해야 한다. 예를 들어, 각 링크에 해당하는 GameObject를 생성하고, 물리 속성을 적용할 수 있다.

C#에서 Python 파싱 결과를 사용하는 예시:

using UnityEngine;

public class RobotLoader : MonoBehaviour
{
    public void CreateLink(string linkName, float mass)
    {
        GameObject link = new GameObject(linkName);
        Rigidbody rb = link.AddComponent<Rigidbody>();
        rb.mass = mass;

        // 다른 물리 속성 추가
    }

    public void CreateJoint(string jointName, string parentName, string childName)
    {
        GameObject parent = GameObject.Find(parentName);
        GameObject child = GameObject.Find(childName);
        HingeJoint joint = child.AddComponent<HingeJoint>();
        joint.connectedBody = parent.GetComponent<Rigidbody>();

        // 다른 조인트 속성 추가
    }
}

이처럼 SDF 파일에서 로봇의 링크와 조인트를 자동으로 생성하고 Unity에서 물리적으로 시뮬레이션할 수 있는 환경을 만들 수 있다.

충돌 메쉬 및 시각적 메쉬 처리

SDF에서 각 링크는 충돌 메쉬와 시각적 메쉬를 별도로 지정할 수 있다. Unity로 변환할 때, 이를 Unity의 MeshColliderMeshRenderer로 적절히 처리해야 한다. 충돌 메쉬는 물리적 상호작용을 위한 것이며, 시각적 메쉬는 렌더링을 위한 것이다.

충돌 메쉬 변환

SDF의 충돌 메쉬는 <collision> 태그 아래에 정의된다. 이를 Unity의 MeshCollider로 변환할 수 있다. 충돌 메쉬가 복잡할 경우, 물리 성능을 고려하여 간소화하는 작업이 필요할 수 있다.

SDF 충돌 메쉬 정의:

<collision name="base_collision">
  <geometry>
    <mesh>
      <uri>model://robot/meshes/base_collision.dae</uri>
    </mesh>
  </geometry>
</collision>

Unity에서의 변환 예시:

MeshCollider collider = link.AddComponent<MeshCollider>();
collider.sharedMesh = Resources.Load<Mesh>("Meshes/base_collision");

시각적 메쉬 변환

SDF의 시각적 메쉬는 <visual> 태그 아래에 정의된다. 이는 Unity에서 MeshRendererMeshFilter를 사용하여 로봇의 외형을 렌더링하는 데 사용된다.

SDF 시각적 메쉬 정의:

<visual name="base_visual">
  <geometry>
    <mesh>
      <uri>model://robot/meshes/base_visual.dae</uri>
    </mesh>
  </geometry>
</visual>

Unity에서의 변환 예시:

MeshFilter meshFilter = link.AddComponent<MeshFilter>();
meshFilter.mesh = Resources.Load<Mesh>("Meshes/base_visual");
MeshRenderer renderer = link.AddComponent<MeshRenderer>();
renderer.material = Resources.Load<Material>("Materials/RobotMaterial");

이와 같이, SDF에서 정의된 시각적 및 충돌 메쉬를 각각 적절한 Unity 구성 요소로 변환할 수 있다.