나는 gazebo를 이용한 시뮬레이션(굳이 gazebo가 아니라도)은 로봇 제작에 있어서 상당히 중요하다고 생각한다.
그 이유는 아래와 같이 꼽아볼 수 있다.
① 설계, 모델링 과정에서 미처 파악하지 못한 링크 간의 간섭을 확인할 수 있다.
② 간단하게라도(비록 엄밀하지 않더라도)모터 스펙이 원하는 동작을 하는데에 충분한지 확인할 수 있다.
③ 실물 제작전에 전체적인 모델을 보고 설계 수정을 할 수 있다.
그런 의미에서 WIM에서 제작하는 델타 로봇도 실물 제작 전에 urdf를 만들었고 그 과정에서 '감속기 사용'이라는 큰 설계 변경을 실물 제작 전에 적용하였다.
이 글은 내가 제작한 델타 로봇의 urdf를 만드는 과정을 정리한 것이다.
+)굳이 델타로봇이 아니더라도 URDF를 만드는 것에 관해 도움이 되는 내용을 최대한 많이 정리했다.
실제 나는 실물 제작 전, 후로 총 2번의 urdf를 만들었고 이 글은 2번째 제작 시의 모델링을 기준으로 작성했으며 1번째 제작 시의 참고사항도 같이 정리해 두었다.
●나는 Inventor를 사용하기 때문에 아래의 복잡한 과정을 거쳐서 urdf를 만들었다. 이 와 관련한 내용은 이전에도 간략하게 정리했었다.
https://istein.tistory.com/103
2023-1 4족보행 로봇(Quadruped robot) 만들기 #7 (urdf 제작 및 rviz, gazebo 1)
※ 글#7과 #8은 fusion2urdf를 이용해 로봇을 gazebo에서 시뮬레이션하기 위한 세팅을 하는 과정에서 얻은 지식과 겪은 시행착오를 전부 기록하고 있다. ※ 글 #8 마지막에 핵심만 정리한 내용을 올렸
istein.tistory.com
●Solidworks의 경우 자체적으로 URDF export 기능이 있기에 바로 사용하면 된다.
●Parallel robot의 urdf를 만드는 과정은 Andy-Chien의 simple_delta_robot을 참고하였다.
https://github.com/andy-Chien/simple_delta_robot
GitHub - andy-Chien/simple_delta_robot: Simple delta robot simulation in gazebo
Simple delta robot simulation in gazebo. Contribute to andy-Chien/simple_delta_robot development by creating an account on GitHub.
github.com
1. 인벤터로 각 부품을 모델링한 후 assembly를 이용해 로봇을 조립하고 1차적인 간섭 및 동작을 확인한다.

●부품 간의 간섭이 있는지 아닌지 확인이 쉽지 않다면 Inventor의 'Contact Solver'기능을 이용하는 것도 좋은 방법이다. 간섭이 의심되는 부품들을 Contact Set으로 지정하고 [Inspect] > [Activate Contact Solver]를 활성화시킨 후 다시 위처럼 움직이면 간섭이 일어날 때 움직이지 않게 된다. 아래의 영상이 사용법을 잘 보여주니 참고하면 된다.
https://www.youtube.com/watch?v=hxdEURGT2no

●위 방법 이외에도 Inventor의 'Collision detection' 기능을 사용하는 방법도 있다. 로봇 형태나 동작에 따라 어떤 방법이 더 좋을지 생각하고 적용하면 된다. Collision detection 기능 사용은 이전에 간략하게 다뤘던 글이 있다.
2021-2 간단한 ROS연습용 로봇팔 제작 #3
[설계 및 모델링 2] 일주일 동안 시간 날 때마다 틈틈이 모델링을 했다. link들은 직접 설계했고 모터의 경우 다른 사람이 업로드해 둔 것을 사용했다. https://grabcad.com/library/sg90-servo-2 SG90 Servo | 3D CA
istein.tistory.com
2. 작은 부품들을 assembly를 이용해 합쳐서 큰 부품으로 만든다.
●이번 델타 로봇의 경우 여러 부품들을 Base + Bicep + Forearm + Platform 총 4개로 간소화했다.




Base : Base + Motor_holder + Reducer(감속기) + Motor
Platform : Platform + Ball_stud
Bicep : Shaft_holder + Bicep_connector + Forearm_connector + Ball_stud + Bicep_tube
Forearm : Forearm_holder + Forearm_tube
●이 과정은 좀 더 간단하게 urdf를 만들기 위한 과정이다. 이 과정을 거치면 추후 fusion360에서 조립할 때, URDF를 수정할 때 편하게 할 수 있다.
물론 단점도 있다. 결국 다른 부품이 하나의 부품이 되므로 질량, 무게 중심(URDF의 inertial tag)가 의도와 달라지게 된다. 정밀한 시뮬레이션을 원한다면 이 단계를 최소화하는 것이 좋다.
3. 로봇의 initial pose에 맞도록 모델을 회전시킨 후 ipt파일로 변환한다.
●'로봇의 initial pose에 맞게 모델을 회전시킨다' 과정 또한 추후 urdf 수정을 편하게 하기 위한 과정이다. 아래의 사진을 보면 쉽게 이해할 수 있다.

이 과정의 의의는 한 링크 안에서 joint의 상대 좌표가 한 평면 안에 들어오게 하는 것에 있다. 위 사진 기준으로 'Base-Bicep의 joint'와 'Bicep-Forearm의 joint'가 회전을 통해 같은 xy평면에 들어오게 되었다. 즉 좌표 변화가 x, y에서만 있을 뿐, z축 변화는 0이 된 것이다.
urdf는 결국 joint간의 상대 위치를 기반으로 작성되기 때문에 이렇게 한 평면에 몰아주면 추후 수정할 때 x, y, z 중 2개만 고려할 수 있게 된다.
●Initial pose에 맞게 한다는 것의 의의는 urdf의 joint tag를 간소화하기 위함이다. 우리가 URDF를 만들 때 결국에는 로봇의 초기 상태, 즉 모터들의 초기 각도를 결정해줘야 한다. 이를 joint에서 각도로 줄 수도 있지만 그러면 joint tag도 길어지고 회전이 반영되게 되어 추후 좌표계산을 어렵게 한다. 그래서 아예 초기 상태로 모델을 고정시켜 두면 urdf 상에서 회전도 없어지고, 좌표 계산도 쉬워지게 되는 것이다.
●assembly로 만든 파일은 iam이라는 확장자로 저장되는데 fusion에 업로들 할 때 iam으로 업로드하면 assemble에 사용된 모든 ipt파일을 같이 올려줘야 하는 번거로움이 있다. 그래서 굳이 iam을 ipt로 simplify 시키는 것이다.

위처럼 [Assemble] > [Simplification] > [Create Simplified Part]로 저장하면 똑같은 모델링이 ipt파일로 저장된다.

최종적으로는 간소화한 부품의 iam과 ipt가 남게 될 것이다.
4. Fusion360에서 모델을 assemble 한다.

●기본적으로 이 방법은 fusion2urdf 스크립트를 사용하는 방법이다. 이는 아래의 github에서 다운로드가 가능하면 사용법도 (영어로) 잘 설명되어 있다.
https://github.com/syuntoku14/fusion2urdf
GitHub - syuntoku14/fusion2urdf: A Fusion 360 Script to export URDF
A Fusion 360 Script to export URDF. Contribute to syuntoku14/fusion2urdf development by creating an account on GitHub.
github.com
●기본적인 것 외에 추가로 주의할 점과 팁을 아래에 적었다.
(기본적인 부분은 https://istein.tistory.com/103 글에서 일부 다뤘다.)
ⓐ. Parallel robot은 kinematic chain(loop)를 포함하고 있기에 URDF 단독으로는 표현이 불가능하다. 그래서 우선 fusion2urdf로 제작할 때는 일부가 끊어진 상태로 제작해야 한다. 이번 델타 로봇의 경우 Base-Bicep1-Forearm1L-Platform만 끝까지 연결했고 나머지는 Base-Bicep-Forearm까지만 연결했다. 나머지는 Forearm-Platform joint를 만들어주지 않은 것이다.
ⓑ. 기본적으로 urdf는 ball joint를 지원하지 않는다. Fusion의 ball joint를 쓰면 안 된다. 하지만 ball joint는 본질적으로 '같은 곳에 위치한 서로 수직인 3개의 revolute joint'와 같으며 이를 이용하여 ball joint를 '흉내'낼 수는 있다. 일단 fusion에서는 assemble 할 때는 1축의 revolute joint만 만들어주면 된다.

ⓒ. link나 joint 이름의 첫 글자를 대문자로 하면 정상적으로 잘 작동하긴 하지만 ros에서 경고 메시지가 계속 뜬다. 첫 글자는 가능하면 영어 소문자로 하는 것이 좋다.
5. fusion2urdf 실행해서 로봇이름_description 패키지를 만든다.
●fusion2urdf가 성공적으로 작동했다면 xacro(urdf파일)을 포함한 패키지가 만들어질 것이다. 여기까지 오면 절반은 성공한 것이다.
●fusion2urdf로 만든 urdf(xacro)의 경우 일부 0.0인 값을 0.0이 아닌 이에 가까운 더러운 값으로 나타낸다. 추후 수정할 때 이를 기억하고 있으면 당황하지 않는다.
ex) 실제로는 0.0인 값을 urdf에서 4.648946164651e-8로 표시, 10^-8이므로 0에 한없이 가까운 값이다.
6. URDF가 정상적으로 만들어졌는지 확인한다. (이 단계부터는 완성된 패키지를 옮겨서 리눅스 ros 환경에서 작업한다.)
●본격적인 수정전에 rviz상에서 urdf가 제대로 만들어졌는지 확인해야 한다. 우선 만들어진 패키지의 display.launch를 조금 수정해줘야 한다. joint_state_publisher 노드를 아래와 같이 _gui가 붙은 것으로 바꿔준다.

이후 display.launch를 실행시키면 rviz가 실행될 것이다. 이때 urdf에 문제가 없다면 모델이 정상적으로 나오고 joint slider를 움직였을 때 정상적으로 joint가 회전할 것이다. 물론 parallel robot의 경우 연결하지 않은 joint가 있어 일부 link가 분리되어 움직일 것이다.
이 단계에서 확인할 사항은 '모델이 정상적으로 나오는지', 'joint의 위치가 맞는 위치에 있는지'이다.

만약 제대로 만들어지지 않았거나 실행이 안된다면 fusion에서 assemble 할 때 문제가 있던 것이므로 4과정으로 돌아간다.
7. URDF를 직접 수정해서 완성한다.
지금 만들어진 urdf는 뼈대만 있을 뿐 본격적으로 gazebo에서 시뮬레이션하기 위해서는 수정하고 추가해야 하는 것들이 많다. 수정할 사항을 파일별로 정리했다. 로봇마다 수정할 부분이 다르기에 이 글에서는 델타로봇을 기준으로 정리했다.
로봇이름.xacro
ⓐworld fix 추가 :
●현재 만들어진 urdf는 고정되어 있지 않다. 이동형 로봇이 아닌 메니퓰레이터 같은 로봇은 고정되어 있어야 하므로 이를 world라는 link에 fix joint를 추가하는 것으로 구현한다.

●origin을 바꾸면 고정되는 위치를 바꿀 수 있다.
ⓑball joint를 위한 dummy link와 joint 추가 :
●앞선 4번 과정에서 ball joint의 1축만 만들었고 여기서 추가적으로 나머지 2개 축을 추가한다. 이 과정을 간략하게 아래에 그림으로 나타냈다.

fusion에서 구현한 것은 위쪽 diagram이고 우리가 수정을 통해 구현할 ball joint는 아래의 diagram이다. 여기서 굳이 x, y, z 축으로 잡을 필요는 없고 요점은 3개의 revolute joint가 서로 수직을 이루면 된다.
●dummy link란 말 그대로 가짜 링크이다. 기능적으로는 존재하지만 시각적, 물리적으로는 존재하지 않는 link를 만든 것이다. 이는 URDF에서 link가 1개의 parent만 가질 수 있기 때문에 사용하는 것이다.
dummy_link에 굳이 mass와 inertia를 주는 것은 gazebo가 모든 link가 mass, inertia를 갖고 있는 것을 요구하기 때문이다. 실제 동작에 영향을 주지 않을 정도로 작은 값을 주면 된다.


●ball 1~3 joint는 bicep-forearm의 ball joint를, 4~6는 forearm-platform의 ball joint를 나타내고 있다. axis를 보면 3개가 각각 수직을 이루고 있다.
ⓒ연결되지 않은 joint들을 dummy_link와 gazebo_joint를 이용해서 연결 :
●앞에서도 말했지만 원칙적으로 1개 link는 joint를 통해 1개의 parent만을 가질 수 있다.(child는 여러 개를 가질 수 있다.)
현재 Platform은 forearm_1_L을 parent로 가지고 있기에 더 이상 parent로 다른 foream을 가질 수 없다.
URDF 단독으로는 방법이 없고 여기서 gazebo의 joint tag를 이용해서 연결한다.
(★이 말은 곧 이 방법으로 이용해 구현한 URDF는 gazebo를 통해서만 정상적으로 구현되고 rviz나 다른 display 프로그램, 시뮬레이터 단독으로는 정상적으로 구현되지 않는다는 뜻이다.)


●위 코드들을 보면 forearm 끝에 dummy_platform을 추가한 후 gazebo joint를 이용해 그 dummy_platform과 진짜 platform을 고정시켜 줬다.
ⓒ+ :
●ⓒ를 하다 보면 joint와 link의 origin을 어떻게 해야 할지 막막할 것이다. 기억해야 하는 점은 기본적으로 'URDF 작성은 joint를 중심으로 작성한다'는 것이다. 이 부분은 일일이 설명하기에는 너무 길어지고 URDF를 만져보며 직접 이해해야 한다.
●델타 로봇 같이 동일한 부품이 한 축을 기준으로 배치된 형태의 경우 회전행렬을 이용하면 joint의 origin의 값을 좀 더 쉽게 계산할 수 있다. 예로 Bicep_1 - Forearm_1_L 사이의 joint를 -120º 회전시키면 Bicep_2 - Forearm_2_L joint와 같아지고 반대로 120º 회전시키면 Bicep_3 - Forearm_3_L joint와 같아진다. (회전행렬은 반시계가 +이다.)
회전 행렬에 관한 내용은 이전에 다룬 적이 있다.
[수학] 회전의 수학적 표현 이해하기(Rotation matrix, Euler rotation, RPY rotation, Quaternion
+)내가 이 공부를 한 이유는 ①ROS에서 orientation을 quaternion으로 표현하는데 quaternion, euler rotation 둘 다 몰랐기 때문이고, ②link-joint system 관련 글을 볼 때 회전 행렬이나 dh파라미터가 많이 나오는
istein.tistory.com
ⓓ각 link별로 inertial tag를 알맞게 수정 :
●글 머리에서도 말했지만 시뮬레이션의 목적은 실물 로봇을 만들지 않고 그 특성을 파악할 수 있다는 것에 있다. inertial tag는 로봇의, 특히 link의 물리적 특성을 담는다는 점에서 개인적으로 가장 중요한 tag라고 생각한다.
●inertial tag는 크게 origin, mass, inertia로 나눠져 있고 각각의 의미는 다음과 같다.
origin : 링크의 질량중심(Center of Mass)를 나타낸다. visual, collision origin과는 다를 수 있다.
mass : 링크의 질량(Mass)을 나타낸다. SI unit인 kg을 사용한다.
inertia : 링크의 질량관성모멘트(Mass moment of Inertia)를 나타낸다. SI unit을 사용하여 kg*m2를 사용한다.
일단 위의 설명은 roswiki에서도 볼 수 있다.
http://wiki.ros.org/urdf/XML/link
urdf/XML/link - ROS Wiki
element The link element describes a rigid body with an inertia, visual features, and collision properties. Here is an example of a link element: 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 Attributes name (required) The name of the link
wiki.ros.org
origin과 mass는 대부분 잘 알것이고 질량관성모멘트의 경우 기계공학과나 관련 학과가 아니면 다소 생소한 표현일 것이다. 이 부분은 짧은 글로 따로 정리할 예정이다.
●fusion2urdf로 만든 urdf에서 우리가 수정해야할 부분은 mass 뿐이다. origin은 모델링을 기반으로 결정되기에 건들지 않아도 되며 inertia는 간단한 형상이면 직접 계산할 수는 있지만 대부분의 로봇 link 형상은 직접 계산하는게 불가능하기에 다른 코드를 사용할 것이다.
origin과 inertial은 원래 그대로 둔 상태로 mass만 내가 원하는 값으로 바꿔준다. 이 때 kg임에 주의한다. 이후 gstavrinos의 calc-inertia를 이용해 해당 mass에 맞는 inertia를 계산한 후 계산 결과를 내 urdf에 넣어준다. 이 방법은 이전에도 다룬 적이 있기에 링크를 남긴다.
https://github.com/gstavrinos/calc-inertia
GitHub - gstavrinos/calc-inertia: Based on a provided URDF (or xacro), it reads all geometries that have a mass inertial tag, an
Based on a provided URDF (or xacro), it reads all geometries that have a mass inertial tag, and prints a URDF-ready inertia matrix. - GitHub - gstavrinos/calc-inertia: Based on a provided URDF (or ...
github.com
https://istein.tistory.com/104
2023-1 4족보행 로봇(Quadruped robot) 만들기 #8 (urdf 제작 및 rviz, gazebo 2)
ⓑcalc_inertia_for_urdf.py를 이용해 inertia를 계산: 구글링 하던 도중 'urdf를 input으로 주면 각 링크의 mass와 stl파일을 기반으로 urdf의 inertia tag를 output으로 주는' 파이썬 코드를 찾았다. 정확하게 내가
istein.tistory.com
로봇이름.trans
ⓐ불필요한 transmission tag 제거 :
●fusion2urdf로 만든 패키지의 경우 trans에 모든 joint에 대해 transmission tag가 생기게 된다. 이 tag는 실제 모터가 장착되는 joint만 가지면 되는 것이다. 델타 로봇의 경우 Base-Bicep 총 3개 joint만 transmission tag를 가지면 된다. 그 외의 것들은 과감하게 삭제한다.
●hardware_interface tag는 모터를 어떤 방식으로 제어할지 선택하는 tag다. fusion2urdf로 만들면 EffortJointInterface로 되어 있을 것이다. 이 부분에 대해서는 아직 이해가 부족해서 추가로 바꾸지는 않는다.
https://wiki.ros.org/ros_control#Hardware_Interfaces
ros_control - ROS Wiki
The ros_control packages are a rewrite of the pr2_mechanism packages to make controllers generic to all robots beyond just the PR2. The ros_control packages takes as input the joint state data from your robot's actuator's encoders and an input set point. I
wiki.ros.org
로봇이름.gazebo
ⓐ각 link의 물리적 특성 설정 :
●여기서 각 link별로 색깔, 마찰계수, 중력 적용 여부, 충돌 여부 등을 설정할 수 있다. 설정 가능한 tag는 아래의 글을 보면 잘 정리되어 있다.
https://classic.gazebosim.org/tutorials?tut=ros_urdf&cat=connect_ros#%3Cgazebo%3EElementsForLinks
Gazebo : Tutorial : URDF in Gazebo
Tutorial: Using a URDF in Gazebo The Unified Robotic Description Format (URDF) is an XML file format used in ROS to describe all elements of a robot. To use a URDF file in Gazebo, some additional simulation-specific tags must be added to work properly with
classic.gazebosim.org
https://campus-rover.gitbook.io/lab-notebook/campusrover-lab-notebook/faq/bouncy-objects
bouncy-objects.md - Autonomous Robotics Lab Notebook
The "kp" value can be thought of as the coefficient of deformation. A value of 500,000 is good for truly solid objects like metals; keep in mind that an object with a "kd" value of 0 and a "kp" value of 500,000 will still bounce all around but will be hard
campus-rover.gitbook.io
https://wiki.ros.org/simulator_gazebo/Tutorials/ListOfMaterials
simulator_gazebo/Tutorials/ListOfMaterials - ROS Wiki
Please ask about problems and questions regarding this tutorial on answers.gazebosim.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. List of Materials Description: This page
wiki.ros.org
+)material은 소재가 아닌 단순 색깔 관련 tag이다.
●dummy_link들은 설정하면 안 된다.
controller.yaml
ⓐ불필요한 controller 제거 :
●이전과 같이 모든 joint에 대해서 생성된 controller 중에서 실제 모터가 장착되는 부분을 제외하고는 전부 지워준다.
ⓑController 종류 선택과 pid gain 조정 :
●type의 controller 종류를 바꿔서 position control을 할지, velocity control을 할지, effort control을 할지 고를 수 있다.
●fusion2urdf로 만든 경우 각 joint별로 controller가 1개씩 생성되었을 것이다. 이렇게 사용해도 문제는 없지만 추후 control topic을 publish할 때 controller별로 topic을 publish해야한다.

위와 같이 Group controller를 사용하면 단일 array type의 topic으로 3개의 모터를 전부 제어할 수 있게 된다.
●PID 값을 바꿀 수 있다. gazebo 실행 중에는 rqt를 이용해서 실시간으로 바꿀 수도 있다. (파일에 값이 반영되지는 않음) 이와 관련된 내용은 다음 글에서 자세히 다룰 예정이다.
●'controller 이름이 없다' 같은 에러가 발생할 경우 yaml문서에서 indentation을 제대로 했는지도 한번 확인해 볼 필요가 있다. 내가 이 실수를 많이 했었다....
load_robot.launch (신규 작성)
●fusion2urdf로 만든 경우 gazebo와 controller가 분리되어 있다. 일일이 2개를 실행시키는 게 불편해서 하나의 launch 파일로 묶었다.

●가장 중요한 부분은 controller 부분의 args에 controller.yaml에서 만든 controller의 이름이 정확히 모두 있어야 한다는 점이다. 나는 arm_position_controller라는 group controller를 만들었으므로 그 1개만 적어주었다.
우선 여기까지 한 후 load_robot.launch를 실행시키면 gazebo가 실행되면서 로봇이 정상적으로 나올 것이다.
만약 로봇이 안 나오면 xacro(urdf)에서 잘못된 것이고, 로봇은 나오는데 모터에 힘이 빠진 채로 축 처져 나오면 controller에서 잘못된 것일 가능성이 높다.

[#5 URDF 제작 및 Gazebo 2]에서 이어집니다...
========================================================================
정확한 정보 전달보단 공부 겸 기록에 초점을 둔 글입니다.
틀린 내용이 있을 수 있습니다.
틀린 내용이나 다른 문제가 있으면 댓글에 남겨주시면 감사하겠습니다. : )
========================================================================
'인턴, 협업 > WIM' 카테고리의 다른 글
| 2023-2 델타 로봇(Delta robot) - #6 (실물 로봇 제작) (0) | 2023.08.31 |
|---|---|
| 2023-2 델타 로봇(Delta robot) - #5 (URDF 제작 및 Gazebo 2) (0) | 2023.08.20 |
| 2023-2 델타 로봇(Delta robot) - #3 (설계와 모델링) (0) | 2023.08.12 |
| 2023-2 델타 로봇(Delta robot) - #2 (ws와 치수 결정을 위한 IK, FK analysis) (0) | 2023.07.20 |
| 2023-2 델타 로봇(Delta robot) - #1 (델타 로봇의 개념과 IK, FK) (0) | 2023.07.11 |