로봇/ROS

URDF를 이용한 간단한 로봇 만들기 (2)

with-RL 2023. 7. 16. 23:31

이번 포스팅은 이전 포스팅에서 구축한 환경을 기반으로 간단한 자동차를 만들어보는 과정입니다.

이 포스트는 다음 영상의 내용을 기반으로 개발하고자 하는 로봇에 적합하게 수정했습니다.

 

Creating a rough 3D model of our robot with URDF

 

이 포스트는 다음 과정을 완료한 후에 참고하시길 바랍니다.

1. ROS 로봇 좌표계

  • 로봇 또는 구성품의 위치와 각도를 3차원 공간에 표현하기 위한 좌표계에 대한 간단한 설명입니다.
  • 위치에 대한 표현은 x, y, z 3개의 좌표로 표현하며 아래와 같습니다.

  • 아래 그림과 같이 오른손을 기준으로 검지(x), 중지(y), 엄지(z)의 좌표계로 기억하면 좀 더 쉽습니다.

  • 회전에 대한 표현은 x, y, z 축을 기준으로 반시계 방향으로 회전 각도를 표현합니다.

  • 반시계 방향은 아래 그림과 같은 오른나사 방향으로 기억하면 좀 더 쉽습니다.
  • 그리고 공간의 물체는 $(x, y, z, \theta_x, \theta_y, \theta_z)$ 이렇게 6개의 값으로 표현 가능합니다.

2. 자동차 body 생성

  • 직육면체 형태의 자동차 body를 생성하는 과정입니다. 아래 이미지의 자동차 본체에 해당합니다.

  •  ‘src/urdf_tutorial/urdf/robot_2.xacro’ 파일을 생성하고 아래와 같이 편집합니다.
    body_joint는 base_link에 'fixed' 형식으로 연결 돼 있습니다.
    boday의 크기는 (x, y, z)가 (20cm, 10cm, 6cm)입니다.
     body는 base_link에 부착했습니다.
    body_joint를 body의 뒷부분에 위치하도록 body를 10cm 이동하고 body_joint를 -12cm만큼 이동했습니다. 결과적으로 base_link는 body의 8cm 부분에 위치하게 됩니다.
    body의 색깔은 흰색입니다.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="urdf_tutorial">

    <!-- COLOR -->
    <material name="white">
        <color rgba="1 1 1 1" />
    </material>

    <!-- BASE LINK -->
    <link name="base_link">
    </link>

    <!-- BODY LINK -->
    <joint name="body_joint" type="fixed">
        <parent link="base_link"/>
        <child link="body"/>
        <origin xyz="-0.12 0 0"/>
    </joint>

    <link name="body">
        <visual>
            <origin xyz="0.1 0 0.03"/>
            <geometry>
                <box size="0.2 0.1 0.06"/>
            </geometry>
            <material name="white"/>
        </visual>
    </link>

</robot>
  • 다음은 ‘src/urdf_tutorial/launch/robot_2.launch.py’ 파일을 만들고 아래와 같이 편집합니다. 파일의 내용은 ‘src/urdf_tutorial/launch/robot_1.launch.py’에서 'robot_1.xacro'을 'robot_2.xacro'으로 변경했습니다.
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument
from launch_ros.actions import Node
import xacro

def generate_launch_description():
    use_sim_time = LaunchConfiguration("use_sim_time")

    pkg_path = os.path.join(get_package_share_directory("urdf_tutorial"))
    xacro_file = os.path.join(pkg_path, "urdf", "robot_2.xacro")
    robot_description = xacro.process_file(xacro_file)
    params = {"robot_description": robot_description.toxml(), "use_sim_time": use_sim_time}

    return LaunchDescription(
        [
            DeclareLaunchArgument(
                "use_sim_time", default_value="false", description="use sim time"
            ),
            Node(
                package="robot_state_publisher",
                executable="robot_state_publisher",
                output="screen",
                parameters=[params],
            ),
        ]
    )
  • 첫 번째 터미널에서 아래 명령을 실행해서 컴파일 및 ‘robot_2.launch.py’ 파일을 실행합니다. 아래 그림과 같이 실행결과를 확인할 수 있습니다.
$ cd ~/Workspace/ros_ws
$ colcon build --symlink-install
$ source install/setup.bash
$ ros2 launch urdf_tutorial robot_2.launch.py
  • 두 번째 터미널에서 아래 명령을 실행해서 Rviz를 실행합니다.
$ cd ~/Workspace/ros_ws
$ source install/setup.bash
$ rviz2
  • Rviz 메뉴에서 'File' >> 'Open Config' 선택 후 이전 과정에서 저장한 config 파일을 불러옵니다.

  • 아래 그림과 같이  자동차 body를 확인할 수 있습니다.

3. 자동차 wheel 생성

  • 자동차에 바퀴(left_wheel, right_wheel)를 부착하는 과정입니다.
  • ‘src/urdf_tutorial/urdf/robot_2.xacro’ 파일의 내용을 아래와 같이 편집합니다.
    left_wheel_joint는 base_link에 'continuous' 형식으로 부착 돼 있습니다.
     left_wheel의 크기는 반지름 3cm, 폭 3cm입니다.
     left_wheel은 body의 왼쪽 바깥쪽에 위치해야 하므로 y 방향으로 6.5cm 이동했습니다.
     left_wheel은 누워 있으므로 x축을 기준으로 시계 방향으로 90도 회전했습니다.
    left_wheel의 색깔은 파란색입니다.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="urdf_tutorial">

    <!-- COLOR -->
    <material name="white">
        <color rgba="1 1 1 1" />
    </material>

    <material name="blue">
        <color rgba="0 0 1 1"/>
    </material>

    <!-- BASE LINK -->
    <link name="base_link">
    </link>

    <!-- BODY LINK -->
    <joint name="body_joint" type="fixed">
        <parent link="base_link"/>
        <child link="body"/>
        <origin xyz="-0.12 0 0"/>
    </joint>

    <link name="body">
        <visual>
            <origin xyz="0.1 0 0.03"/>
            <geometry>
                <box size="0.2 0.1 0.06"/>
            </geometry>
            <material name="white"/>
        </visual>
    </link>

    <!-- LEFT WHEEL LINK -->
    <joint name="left_wheel_joint" type="continuous">
        <parent link="base_link"/>
        <child link="left_wheel"/>
        <origin xyz="0 0.065 0" rpy="-${pi/2} 0 0" />
        <axis xyz="0 0 1"/>
    </joint>

    <link name="left_wheel">
        <visual>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
            <material name="blue"/>
        </visual>
    </link>

</robot>
  • 변경된 값을 반영하기 위해 첫 번째 터미널에서 ‘CTRL+C’ 키를 입력해서 종료한 후 명령을 수행해서 'robot_2.launch.py'를 다시 실행합니다.
$ colcon build --symlink-install
$ ros2 launch urdf_test robot_2.launch.py
  • Rviz에서 아래와 같이 left_wheel 관련해서 오류가 발생한 것을 확인할 수 있습니다.

  • 세 번째 터미널에서 아래 명령을 실행해서 ‘joint_state_publisher_gui’를 실행합니다.
$ ros2 run joint_state_publisher_gui joint_state_publisher_gui
  • Rviz에서 left_wheel을 확인할 수 있습니다. ‘joint_state_publisher_gui’에서 ‘left_wheel_joint’ 값을 변경하면 left_wheel이 회전하는 것을 확인할 수 있습니다.

  • 네 번째 터미널에서 아래 명령을 실행해서 rqt_graph를 실행합니다. ‘joint_state_publisher’가 ‘/joint_states’라는 topic을 ‘/robot_state_publisher’에게 보내는 것을 확인할 수 있습니다.

  • ‘src/urdf_tutorial/urdf/robot_2.xacro’  파일의 내용을 아래와 같이 편집합니다.
    right_wheel_joint 역시 base_link에 'continuous' 형식으로 부착 돼 있습니다.
     
    right_wheel의 크기는 left_wheel과 동일한 반지름 3cm, 폭 3cm입니다.
    right_wheel은 body의 오른쪽 바깥쪽에 위치해야 하므로 y의 반대 방향으로 6.5cm 이동했습니다.
    right_wheel은 누워 있으므로 x축을 기준으로 반시계 방향으로 90도 회전했습니다.
    right_wheel의 색깔 역시 파란색입니다.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="urdf_tutorial">

    <!-- COLOR -->
    <material name="white">
        <color rgba="1 1 1 1" />
    </material>

    <material name="blue">
        <color rgba="0 0 1 1"/>
    </material>

    <!-- BASE LINK -->
    <link name="base_link">
    </link>

    <!-- BODY LINK -->
    <joint name="body_joint" type="fixed">
        <parent link="base_link"/>
        <child link="body"/>
        <origin xyz="-0.12 0 0"/>
    </joint>

    <link name="body">
        <visual>
            <origin xyz="0.1 0 0.03"/>
            <geometry>
                <box size="0.2 0.1 0.06"/>
            </geometry>
            <material name="white"/>
        </visual>
    </link>

    <!-- LEFT WHEEL LINK -->
    <joint name="left_wheel_joint" type="continuous">
        <parent link="base_link"/>
        <child link="left_wheel"/>
        <origin xyz="0 0.065 0" rpy="-${pi/2} 0 0" />
        <axis xyz="0 0 1"/>
    </joint>

    <link name="left_wheel">
        <visual>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
            <material name="blue"/>
        </visual>
    </link>

    <!-- RIGHT WHEEL LINK -->
    <joint name="right_wheel_joint" type="continuous">
        <parent link="base_link"/>
        <child link="right_wheel"/>
        <origin xyz="0 -0.065 0" rpy="${pi/2} 0 0" />
        <axis xyz="0 0 -1"/>
    </joint>

    <link name="right_wheel">
        <visual>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
            <material name="blue"/>
        </visual>
    </link>

</robot>
  • 변경된 값을 반영하기 위해 첫 번째 터미널에서 ‘CTRL+C’ 키를 입력해서 종료한 후 명령을 수행해서 'robot_2.launch.py'를 다시 실행합니다.
$ colcon build --symlink-install
$ ros2 launch urdf_test robot_2.launch.py
  • Rviz에서 right_wheel을 확인할 수 있습니다. ‘joint_state_publisher_gui’에서 ‘right_wheel_joint’가 추가되었고 변경하면 right_wheel이 회전하는 것을 확인할 수 있습니다.

4. Caster Wheel 추가하기

  • 이번에 만들 자동차는 동력이 바퀴 두 개에서 발생하는 간단한 자동차입니다. 동력이 없고 자동차가 넘어지지 않도록 하는 보조 바퀴 caster_wheel을 추가하는 과정입니다.
  • ‘src/urdf_tutorial/urdf/robot_2.xacro’  파일의 내용을 아래와 같이 편집합니다.
    caster_wheel_joint는 body에 'fixed' 형식으로 부착 돼 있습니다. caster_wheel이 body 뒤쪽에 위치하도록 x축 방향으로 3cm 이동했습니다.
     caster_wheel의 크기는 반지름 3cm인 구입니다.
    caster_wheel의 색깔은 검은색입니다.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="urdf_tutorial">

    <!-- COLOR -->
    <material name="white">
        <color rgba="1 1 1 1" />
    </material>

    <material name="blue">
        <color rgba="0 0 1 1"/>
    </material>

    <!-- BASE LINK -->
    <link name="base_link">
    </link>

    <!-- BODY LINK -->
    <joint name="body_joint" type="fixed">
        <parent link="base_link"/>
        <child link="body"/>
        <origin xyz="-0.12 0 0"/>
    </joint>

    <link name="body">
        <visual>
            <origin xyz="0.1 0 0.03"/>
            <geometry>
                <box size="0.2 0.1 0.06"/>
            </geometry>
            <material name="white"/>
        </visual>
    </link>

    <!-- LEFT WHEEL LINK -->
    <joint name="left_wheel_joint" type="continuous">
        <parent link="base_link"/>
        <child link="left_wheel"/>
        <origin xyz="0 0.065 0" rpy="-${pi/2} 0 0" />
        <axis xyz="0 0 1"/>
    </joint>

    <link name="left_wheel">
        <visual>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
            <material name="blue"/>
        </visual>
    </link>

    <!-- RIGHT WHEEL LINK -->
    <joint name="right_wheel_joint" type="continuous">
        <parent link="base_link"/>
        <child link="right_wheel"/>
        <origin xyz="0 -0.065 0" rpy="${pi/2} 0 0" />
        <axis xyz="0 0 -1"/>
    </joint>

    <link name="right_wheel">
        <visual>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
            <material name="blue"/>
        </visual>
    </link>

    <!-- CASTER WHEEL LINK -->
    <joint name="caster_wheel_joint" type="fixed">
        <parent link="body"/>
        <child link="caster_wheel"/>
        <origin xyz="0.03 0 0"/>
    </joint>

    <link name="caster_wheel">
        <visual>
            <geometry>
                <sphere radius="0.03"/>
            </geometry>
            <material name="black"/>
        </visual>
    </link>

</robot>
  • 변경된 값을 반영하기 위해 첫 번째 터미널에서 ‘CTRL+C’ 키를 입력해서 종료한 후 명령을 수행해서 'robot_2.launch.py'를 다시 실행합니다.
  • Rviz에서 아래와 같이 caster_wheel이 추가된 것을 확인할 수 있습니다. 

  • 모양을 TF의 축 표현 때문에 자동차의 모양을 확인하기 어렵습니다. Rviz에서 TF를 비활성화하면 아래와 같이 정확한 자동차 모형을 확인할 수 있습니다.

5. Collision 추가하기

  • 이전 과정에서 만든 것은 자동차의 모형입니다. 현재 상태에서 자동차가 주행하다가 장애물을 만난다면 그대로 통과할 것입니다. 충동을 시뮬레이션을 위해서 collision을 추가하는 과정입니다.
  • ‘src/urdf_tutorial/urdf/robot_2.xacro’ 파일의 내용을 아래와 같이 편집합니다. 이번에 만들 자동차는 외형과 충돌 부위가 동일합니다. 그러므로 visual과 동일한 모양으로 collision을 만들어 줍니다.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="urdf_tutorial">

    <!-- COLOR -->
    <material name="white">
        <color rgba="1 1 1 1" />
    </material>

    <material name="blue">
        <color rgba="0 0 1 1"/>
    </material>

    <material name="black">
        <color rgba="0 0 0 1"/>
    </material>

    <!-- BASE LINK -->
    <link name="base_link">
    </link>

    <!-- BODY LINK -->
    <joint name="body_joint" type="fixed">
        <parent link="base_link"/>
        <child link="body"/>
        <origin xyz="-0.12 0 0"/>
    </joint>

    <link name="body">
        <visual>
            <origin xyz="0.1 0 0.03"/>
            <geometry>
                <box size="0.2 0.1 0.06"/>
            </geometry>
            <material name="white"/>
        </visual>
        <collision>
            <origin xyz="0.1 0 0.03"/>
            <geometry>
                <box size="0.2 0.1 0.06"/>
            </geometry>
        </collision>
    </link>

    <!-- LEFT WHEEL LINK -->
    <joint name="left_wheel_joint" type="continuous">
        <parent link="base_link"/>
        <child link="left_wheel"/>
        <origin xyz="0 0.065 0" rpy="-${pi/2} 0 0" />
        <axis xyz="0 0 1"/>
    </joint>

    <link name="left_wheel">
        <visual>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
            <material name="blue"/>
        </visual>
        <collision>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
        </collision>
    </link>

    <!-- RIGHT WHEEL LINK -->
    <joint name="right_wheel_joint" type="continuous">
        <parent link="base_link"/>
        <child link="right_wheel"/>
        <origin xyz="0 -0.065 0" rpy="${pi/2} 0 0" />
        <axis xyz="0 0 -1"/>
    </joint>

    <link name="right_wheel">
        <visual>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
            <material name="blue"/>
        </visual>
        <collision>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
        </collision>
    </link>

    <!-- CASTER WHEEL LINK -->
    <joint name="caster_wheel_joint" type="fixed">
        <parent link="body"/>
        <child link="caster_wheel"/>
        <origin xyz="0.03 0 0"/>
    </joint>

    <link name="caster_wheel">
        <visual>
            <geometry>
                <sphere radius="0.03"/>
            </geometry>
            <material name="black"/>
        </visual>
        <collision>
            <geometry>
                <sphere radius="0.03"/>
            </geometry>
        </collision>
    </link>

</robot>
  • Rviz에서 ‘Visual Enabled’를 비활성화하고 ‘Collision Enabled’를 활성화해도 동일한 모양을 확인할 수 있습니다.

6. 관성 모멘트 추가

  • 자동차의 물리적인 특성을 계산할 수 있는 관성 모멘트를 추가하는 과정입니다.
  • 주요 형상에 대한 관성 모멘트의 계산식은 List of moments of inertia에서 확인할 수 있습니다.
  • ‘src/urdf_tutorial/urdf/macros.xacro’ 파일을 만들고 아래와 같이 편집합니다
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >

    <!-- Specify some standard inertial calculations https://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
    <!-- These make use of xacro's mathematical functionality -->

    <xacro:macro name="inertial_sphere" params="mass radius *origin">
        <inertial>
            <xacro:insert_block name="origin"/>
            <mass value="${mass}" />
            <inertia ixx="${(2/5) * mass * (radius*radius)}" ixy="0.0" ixz="0.0"
                    iyy="${(2/5) * mass * (radius*radius)}" iyz="0.0"
                    izz="${(2/5) * mass * (radius*radius)}" />
        </inertial>
    </xacro:macro>  


    <xacro:macro name="inertial_box" params="mass x y z *origin">
        <inertial>
            <xacro:insert_block name="origin"/>
            <mass value="${mass}" />
            <inertia ixx="${(1/12) * mass * (y*y+z*z)}" ixy="0.0" ixz="0.0"
                    iyy="${(1/12) * mass * (x*x+z*z)}" iyz="0.0"
                    izz="${(1/12) * mass * (x*x+y*y)}" />
        </inertial>
    </xacro:macro>


    <xacro:macro name="inertial_cylinder" params="mass length radius *origin">
        <inertial>
            <xacro:insert_block name="origin"/>
            <mass value="${mass}" />
            <inertia ixx="${(1/12) * mass * (3*radius*radius + length*length)}" ixy="0.0" ixz="0.0"
                    iyy="${(1/12) * mass * (3*radius*radius + length*length)}" iyz="0.0"
                    izz="${(1/2) * mass * (radius*radius)}" />
        </inertial>
    </xacro:macro>

</robot>
  • 'src/urdf_tutorial/urdf/robot_2.xacro' 파일에 ‘src/urdf_tutorial/urdf/macros.xacro’의 내용을 포함하고 관성 물리적 특성을 지정해 주십니다.
    body는 ‘solid rectangular cuboid’ 수식을 사용합니다.
     left_wheel, right_wheel은 ‘solid cylinder’ 수식을 사용합니다.
     caster_wheel은 ‘solid sphere’ 수식을 사용합니다.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="urdf_tutorial">

    <!-- MACROS -->
    <xacro:include filename="macros.xacro"/>

    <!-- COLOR -->
    <material name="white">
        <color rgba="1 1 1 1" />
    </material>

    <material name="blue">
        <color rgba="0 0 1 1"/>
    </material>

    <material name="black">
        <color rgba="0 0 0 1"/>
    </material>

    <!-- BASE LINK -->
    <link name="base_link">
    </link>

    <!-- BODY LINK -->
    <joint name="body_joint" type="fixed">
        <parent link="base_link"/>
        <child link="body"/>
        <origin xyz="-0.12 0 0"/>
    </joint>

    <link name="body">
        <visual>
            <origin xyz="0.1 0 0.03"/>
            <geometry>
                <box size="0.2 0.1 0.06"/>
            </geometry>
            <material name="white"/>
        </visual>
        <collision>
            <origin xyz="0.1 0 0.03"/>
            <geometry>
                <box size="0.2 0.1 0.06"/>
            </geometry>
        </collision>
        <xacro:inertial_box mass="0.5" x="0.2" y="0.1" z="0.06">
            <origin xyz="0.1 0 0.03" rpy="0 0 0"/>
        </xacro:inertial_box>
    </link>

    <!-- LEFT WHEEL LINK -->
    <joint name="left_wheel_joint" type="continuous">
        <parent link="base_link"/>
        <child link="left_wheel"/>
        <origin xyz="0 0.065 0" rpy="-${pi/2} 0 0" />
        <axis xyz="0 0 1"/>
    </joint>

    <link name="left_wheel">
        <visual>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
            <material name="blue"/>
        </visual>
        <collision>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
        </collision>
        <xacro:inertial_cylinder mass="0.1" length="0.03" radius="0.03">
            <origin xyz="0 0 0" rpy="0 0 0"/>
        </xacro:inertial_cylinder>
    </link>

    <!-- RIGHT WHEEL LINK -->
    <joint name="right_wheel_joint" type="continuous">
        <parent link="base_link"/>
        <child link="right_wheel"/>
        <origin xyz="0 -0.065 0" rpy="${pi/2} 0 0" />
        <axis xyz="0 0 -1"/>
    </joint>

    <link name="right_wheel">
        <visual>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
            <material name="blue"/>
        </visual>
        <collision>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
        </collision>
        <xacro:inertial_cylinder mass="0.1" length="0.03" radius="0.03">
            <origin xyz="0 0 0" rpy="0 0 0"/>
        </xacro:inertial_cylinder>
    </link>

    <!-- CASTER WHEEL LINK -->
    <joint name="caster_wheel_joint" type="fixed">
        <parent link="body"/>
        <child link="caster_wheel"/>
        <origin xyz="0.03 0 0"/>
    </joint>

    <link name="caster_wheel">
        <visual>
            <geometry>
                <sphere radius="0.03"/>
            </geometry>
            <material name="black"/>
        </visual>
        <collision>
            <geometry>
                <sphere radius="0.03"/>
            </geometry>
        </collision>
        <xacro:inertial_sphere mass="0.1" radius="0.03">
            <origin xyz="0 0 0" rpy="0 0 0"/>
        </xacro:inertial_sphere>
    </link>

</robot>