안녕하세요. MrLacquer입니다. 이번 포스팅에서는 지난번에 다루었던 Universal Robot 사의 UR3를 활용해서 양팔 로봇의 urdf를 만들고, rviz에서 확인하는 방법에 대해서 다뤄보겠습니다.
일단, UR3라는 녀석은 지난 포스팅을 참고해주세요
▷[ROS] Universal Robot Co.의 ROS package 사용하기
ROS에서 사용하는 URDF는 XML format입니다.
이 XML format에 맞추어 로봇의 외형을 규격화 시키는 것이죠.
단순한 로봇인 경우, 복사 붙여넣기로 금방 만들 수 있습니다.
하지만, UR로봇과 같이 6DoF를 가진 녀석은 단순한 복사 붙여넣기로는 거의 노가다가 되어버립니다.
게다가, 이번 포스팅에서 다루는 것처럼 이런 UR 로봇을 사용해서 양팔 로봇을 만들고자 한다면...? 정말 귀찮습니다.
말로만 하면 감이 안오니까,
미리 제가 만든 양팔 로봇의 URDF의 line 수를 보여드리면요....
총 667줄입니다.... 어마어마하죠?
하지만, 오늘 이용할 xacro라는 녀석을 활용하면 굉장히 편하게 작성할 수 있습니다.
xacro는 XML + macro의 합성어로, XML macro입니다. 자세한 내용은 아래 위키에서 참고하시기 바랍니다.
우선, universal robot ROS package가 설치되어 있거나, catkin_ws/src에 해당 패키지가 셋팅되어 있어야 합니다.
참고로 제 환경은 후자입니다.
1. UR3 xacro 살펴보기!
우선 UR3 xacro를 그대로 가져다 활용할 계획이니, 해당 파일을 들여보겠습니다.
우리가 볼 파일은
입니다.
여기서, 우리가 살펴볼 라인은 6번부터 시작합니다.
6번부터 보시면, include가 있는 것을 보아하니... 어떤 파일을 불러오는 줄이라고 짐작되실겁니다.
천천히 해석해보자면,
<xacro:include filename="$(find ur_description)/urdf/ur.transmission.xacro" />→ 내가 원하는 파일을 불러오고 싶은데, 그것은 ur_descriton/urdf 폴더에 있는 ur.transmission.xacro 라는 파일이다.
라고 해석하시면 됩니다.
이제 line9-43 까지는 UR3의 physical parameter가 쭉 정의되어 있습니다. 마치 변수 선언하듯이요.
나머지는 건너뛰고, line 53부터 보겠습니다.
60번 줄을 보시면 "${prefix}base_link" 라고 되어있습니다.
이것은 53번 줄에 선언한 macro를 중, prefix 매개변수(정확한 용어는 모르겠습니다.)를 활용한다는 의미입니다.
즉, 다른 파일에서 지금 우리가 보고 있는 xacro 파일을 불러올때, prefix setting을 "l_"로 하게 되면,
"${prefix}base_link" → "l_base_link"로 된다는 의미입니다.
이렇게 될 경우, 왼팔, 오른팔을 간단하게 구분할 수 있습니다.
이를 이용해서 양팔 로봇을 작성해 보겠습니다.
2. UR3 양팔 로봇 만들어 보기!
catkin_ws/src에 아래 그림처럼 패키지를 만들겠습니다.
$ catkin_create_pkg my_dual_arm
그런 다음 해당 패키지에 다음 그림과 같은 폴더를 생성합니다.
launch 폴더는 launch 파일을 저장하는 곳이고, urdf 폴더는 urdf 파일을 저장하는 곳입니다.
저는 양팔 로봇의 구성을 몸통(torso), 왼팔(left_arm), 오른팔(right_arm)으로 구성하겠습니다.
우선, 주어진 UR3의 xacro를 이용해서 왼팔, 오른팔의 URDF를 작성해보겠습니다.
일단 아래 그림과 같이 "left_arm.xacro", "right_arm.xacro" 파일을 만들어 줍니다.
<left_arm.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 |
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="l_ur3" >
<!-- common stuff -->
<xacro:include filename="$(find ur_description)/urdf/common.gazebo.xacro" />
<!-- ur3 -->
<xacro:include filename="$(find ur_description)/urdf/ur3.urdf.xacro" />
<!--left arm, the prefix setting: l_ -->
<xacro:ur3_robot prefix="l_" joint_limited="true"
shoulder_pan_lower_limit="${-pi}" shoulder_pan_upper_limit="${pi}"
shoulder_lift_lower_limit="${-pi}" shoulder_lift_upper_limit="${pi}"
elbow_joint_lower_limit="${-pi}" elbow_joint_upper_limit="${pi}"
wrist_1_lower_limit="${-pi}" wrist_1_upper_limit="${pi}"
wrist_2_lower_limit="${-pi}" wrist_2_upper_limit="${pi}"
wrist_3_lower_limit="${-pi}" wrist_3_upper_limit="${pi}"
/>
<link name="l_world" />
<joint name="l_world_joint" type="fixed">
<parent link="l_world" />
<child link = "l_base_link" /> <!--"l_base_link" is follow the prefix setting.-->
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</joint>
</robot> |
cs |
<right_arm.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 |
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="r_ur3" >
<!-- common stuff -->
<xacro:include filename="$(find ur_description)/urdf/common.gazebo.xacro" />
<!-- ur3 -->
<xacro:include filename="$(find ur_description)/urdf/ur3.urdf.xacro" />
<!--right arm, the prefix setting: r_ -->
<xacro:ur3_robot prefix="r_" joint_limited="true"
shoulder_pan_lower_limit="${-pi}" shoulder_pan_upper_limit="${pi}"
shoulder_lift_lower_limit="${-pi}" shoulder_lift_upper_limit="${pi}"
elbow_joint_lower_limit="${-pi}" elbow_joint_upper_limit="${pi}"
wrist_1_lower_limit="${-pi}" wrist_1_upper_limit="${pi}"
wrist_2_lower_limit="${-pi}" wrist_2_upper_limit="${pi}"
wrist_3_lower_limit="${-pi}" wrist_3_upper_limit="${pi}"
/>
<link name="r_world" />
<joint name="r_world_joint" type="fixed">
<parent link="r_world" />
<child link = "r_base_link" /> <!--"r_base_link" is follow the prefix setting.-->
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</joint>
</robot>
|
cs |
각 파일에서 12줄을 보면, prefix에 "l_" 와 "r_"를 삽입하여 왼쪽, 오른쪽이 구분되도록 했습니다.
다음으로 몸통과 양팔을 잇는 xacro를 작성해보겠습니다.
<dual_robot_arm.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
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57 |
<?xml version="1.0"?>
<robot
xmlns:xacro="http://ros.org/wiki/xacro" name="dual_robot">
<xacro:include filename="$(find my_dual_arm)/urdf/left_arm.xacro" />
<xacro:include filename="$(find my_dual_arm)/urdf/right_arm.xacro" />
<link name="dual_world"/>
<joint name="dual_world" type="fixed">
<parent link="dual_world"/>
<child link="dual_base_link"/>
</joint>
<link name="dual_base_link" />
<!--the robot model urdf code-->
<!--torso of robot-->
<link name = "torso">
<visual>
<geometry>
<box size="0.22 0.22 1.5"/>
</geometry>
<origin xyz = "0 0 0.75" rpy = "0 0 0"/>
<material name="LightGrey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
</visual>
<collision>
<geometry>
<box size="0.22 0.22 1.5"/>
<mesh filename = "package://violin_description/meshes/robot_body.stl" />
</geometry>
</collision>
<inertial>
<!--mass: kg, inertia: using meshlab program -->
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value = "20"/>
<inertia ixx="0.5" ixy="0" ixz="0" iyy="0.6" iyz="0" izz="0.3" />
</inertial>
</link>
<joint name="dual_base_joint" type="fixed">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<parent link="dual_base_link"/>
<child link="torso"/>
</joint>
<!--joint part-->
<joint name = "l_robot_body" type = "fixed">
<parent link = "torso"/>
<child link = "l_world"/>
<axis xyz = "0 0 0"/>
<origin xyz = "0 0.11 1.26275" rpy = "-1.5708 -1.5708 0"/>
</joint>
<joint name = "r_robot_body" type = "fixed">
<parent link = "torso"/>
<child link = "r_world"/>
<axis xyz = "0 0 0"/>
<origin xyz = "0 -0.11 1.26275" rpy = "-1.5708 1.5708 3.14159"/>
</joint>
</robot> |
cs |
4, 5줄에서 지금까지 작성한 left_arm.xacro와 right_arm.xacro를 불러옵니다.
14-37줄까지는 torso 부분입니다.
저는 개인적으로 모델링한 mesh 파일을 넣지만, 여기서는 단순하게 막대기를 세워서 진행합니다.
45-56줄까지 불러온 left_arm.xacro와 right_arm.xacro을 고려해서 joint를 구성합니다.
자, 이렇게 하면 힘들게 복사 붙여넣기 할 필요 없이 아주 쉽게(?) 양팔 로봇에 대한 urdf를 작성할 수 있습니다.
지금까지 작성한 로봇이 과연 제대로 되었는지 확인하기 위해서는 아래 코드로 확인 가능합니다.
$ roscd my_dual_arm$ cd urdf/
$ rosrun xacro xacro dual_robot_arm.xacro
너무 길어서 캡쳐가 다 안됐지만... 에러 없이 위 처럼 뜬다면 문제 없습니다.
그래도 못 미더우면... 아래 코드로 urdf 변환 후, check_urdf 하면...
$ rosrun xacro xacro dual_robot_arm.xacro > exp_dual_robot_arm.urdf$ check_urdf exp_dual_robot_arm.urdf
성공적으로 parse 된 결과를 볼 수 있습니다.
3. 시각화 툴(Rviz)로 확인하기
이제 마지막으로 시각화 툴(Rviz)를 활용해서 내가 원하는대로 잘 되었는지 확인해볼까요?
아까 만들었던 launch 폴더에 "my_dual_arm_publisher.launch" 파일을 만들어줍니다.
1
2
3
4
5
6
7
8
9
10 |
<launch>
<param name="robot_description" command="$(find xacro)/xacro.py $(find my_dual_arm)/urdf/dual_robot_arm.xacro" />
<node pkg="robot_state_publisher" type="state_publisher" name="robot_state_publisher" />
<node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher">
<param name="use_gui" value="1" />
</node>
<!-- Launch visualization in rviz -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find my_dual_arm)/urdf.rviz" required="True" />
</launch> |
cs |
joint_state_publisher 및 rviz가 한번에 실행되도록 작성했습니다.
launch를 실행하게 되면 위 그림과 같이 rviz가 실행되고, 동시에 joint_state_publisher도 같이 실행됩니다.
그리고 아래 그림과 같이 옵션에서 robot model을 추가 하고, Fixed Frame 항목을 dual_world로 바꿔 줍니다.
짠~! 이렇게 정상적으로 모델을 불러왔습니다!
이제 남은 것은 joint_state_publisher를 조작하면서 관절들이 제대로 움직이는지 확인하면 됩니다.
지금까지 UR3의 xacro 파일을 이용해서 양팔 로봇을 만들어 봤습니다.
많은 설명이 부족하지만, 도움이 되었으면 좋겠습니다.
참고:
http://enesbot.me/creating-a-dual-arm-manipulator-in-ROS.html
https://www.slideshare.net/ahnbk/oroca-seminar/1
https://github.com/ros-industrial/universal_robot/issues/340
다음 포스팅도 기다려 주세요~!
'Project notes > Robot Operating System' 카테고리의 다른 글
[ROS] Universal Robot manipulator with Moveit! (1) | 2020.04.28 |
---|---|
[ROS] Universal Robot Co.의 ROS package 사용하기 (1) | 2017.12.31 |