로봇/ROS

Gazebo를 이용해 Camera 시뮬레이션 하기

with-RL 2023. 7. 22. 14:40

이번 포스팅은 이전 포스팅에서 구축한 환경을 기반으로 Gazebo를 이용해서 Camera를 부착하고 동작을 확인해 보는 과정입니다.

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

 

How to use Cameras in ROS (Sim Camera and Pi Camera)

 

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

1. 실행파일 생성

  • 아래 명령을 실행해서 'src/urdf_tutorial/urdf/robot_4.xacro' 파일을 'src/urdf_tutorial/urdf/robot_5.xacro' 파일로 복사합니다.
$ cd ~/Workspace/ros_ws
$ cp src/urdf_tutorial/urdf/robot_4.xacro src/urdf_tutorial/urdf/robot_5.xacro
  • 다음은 ‘src/urdf_tutorial/launch/robot_5.launch.py’ 파일을 만들고 아래와 같이 편집합니다. 파일의 내용은 ‘src/urdf_tutorial/launch/robot_4.launch.py’에서 'robot_4.xacro'을 'robot_5.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_5.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],
            ),
        ]
    )
  • 다음은 ‘src/urdf_tutorial/launch/camera.launch.py’ 파일을 만들고 아래와 같이 편집합니다. 파일의 내용은 ‘src/urdf_tutorial/launch/lidar.launch.py’에서 'robot_4.launch.py'을 'robot_5.launch.py'으로 변경했습니다.
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions import Node


def generate_launch_description():
    package_name = "urdf_tutorial"

    rsp = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            [os.path.join(get_package_share_directory(package_name), "launch", "robot_5.launch.py")]
        ),
        launch_arguments={"use_sim_time": "true"}.items(),
    )

    # Include the Gazebo launch file, provided by the gazebo_ros package
    gazebo = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            [os.path.join(get_package_share_directory("gazebo_ros"), "launch", "gazebo.launch.py")]
        ),
    )

    # Run the spawner node from the gazebo_ros package. The entity name doesn't really matter if you only have a single robot.
    spawn_entity = Node(
        package="gazebo_ros",
        executable="spawn_entity.py",
        arguments=["-topic", "robot_description", "-entity", "with_robot"],
        output="screen",
    )

    # Launch them all!
    return LaunchDescription(
        [
            rsp,
            gazebo,
            spawn_entity,
        ]
    )

2. URDF에 Camera 추가하기

  • URDF를 수정해서 자동차에 Camera 구조물을 부착하는 과정입니다.
  • 'src/urdf_tutorial/urdf/robot_5.xacro’ 파일의 ‘laser_frame’ link 밑에 아래 내용을 추가해서 Camera 형상을 만듭니다.
    camera_joint: fixed joint로 Camera가 자동차의 앞쪽 중앙에 자리 잡을 수 있도록 위치를 조정했습니다.
     camera_link: 직사각형 모양으로 가로 3cm, 세로 3cm, 높이 1cm 인 Box입니다. 색깔은 빨간색으로 설정했습니다.
     camera_optical_joint: fixed joint로 Camera의 렌즈가 정면을 볼 수 있도록 roll과 yaw을 $\pi / 2$씩 조정했습니다.
    <!-- CAMERA -->
    <joint name="camera_joint" type="fixed">
        <parent link="body"/>
        <child link="camera_link"/>
        <origin xyz="0.20 0 0.03" rpy="0 0 0"/>
    </joint>

    <link name="camera_link">
        <visual>
            <geometry>
                <box size="0.01 0.03 0.03"/>
            </geometry>
            <material name="red"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.01 0.03 0.03"/>
            </geometry>
        </collision>
    </link>

    <joint name="camera_optical_joint" type="fixed">
        <parent link="camera_link"/>
        <child link="camera_link_optical"/>
        <origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
    </joint>

    <link name="camera_link_optical">
    </link>
  • 첫 번째 터미널에서 아래 명령을 실행합니다.
$ cd ~/Workspace/ros_ws/
$ colcon build --symlink-install
$ source install/setup.bash
$ ros2 launch urdf_tutorial camera.launch.py
  • 자동차 앞쪽에 카메라가 추가된 것을 확인할 수 있습니다.

3. Camera 기능 추가하기

  • 이전 단계에서 추가된 Camera 구조물에 Camera 기능을 추가하는 과정입니다.
  • 이전에 실행했던 기능은 ‘CTRL+C’를 눌러서 프로그램을 모두 종료합니다.
  • ‘src/urdf_tutorial/urdf/camera.xacro’ 파일을 생성하고 아래와 같이 편집합니다.
    update_rate: 초당 10회 정보를 제공합니다.
    horizontal_fov: 가로 방향의 FOV (Field of View)는 1.089로 설정했습니다. Gazebo에서는 세로 방향의 FOV는 이미지 사이즈에 따라서 자동으로 계산되는 것으로 보입니다.
    image format: R8G 8B8로 빨강, 초록, 파랑 모두 8비트로 인코딩 됩니다.
    image widht/height: 이미지의 크기는 가로 640 픽셀, 세로 480 픽셀로 지정했습니다.
    frame_name: Camera가 부착된 센서 이름입니다.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

    <gazebo reference="camera_link">
        <material>Gazebo/Red</material>
        <sensor name="camera" type="camera">
            <pose>0 0 0 0 0 0</pose>
            <visualize>true</visualize>
            <update_rate>10</update_rate>
            <camera>
                <horizontal_fov>1.089</horizontal_fov>
                <image>
                    <format>B8G8R8</format>
                    <width>640</width>
                    <height>480</height>
                </image>
                <clip>
                    <near>0.05</near>
                    <far>8.0</far>
                </clip>
            </camera>
            <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
                <frame_name>camera_link_optical</frame_name>
                <min_depth>0.1</min_depth>
                <max_depth>100.0</max_depth>
            </plugin>
        </sensor>
    </gazebo>

</robot>
  • 'src/urdf_tutorial/urdf/robot_5.xacro' 파일에 아래 내용을 추가해서 'camera.xacro'를 포함해 줍니다.
<xacro:include filename="camera.xacro"/>
  • 'src/urdf_tutorial/urdf/robot_5.xacro' 파일의 최종 내용은 아래와 같습니다.
<?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>

    <material name="red">
        <color rgba="1 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>

    <gazebo reference="body">
        <material>Gazebo/White</material>
    </gazebo>

    <!-- 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>

    <gazebo reference="left_wheel">
        <material>Gazebo/Black</material>
    </gazebo>

    <!-- 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>

    <gazebo reference="right_wheel">
        <material>Gazebo/Black</material>
    </gazebo>

    <!-- 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>

    <gazebo reference="caster_wheel">
        <material>Gazebo/Blue</material>

        <mu1 value="0.001"/>
        <mu2 value="0.001"/>
    </gazebo>

    <!-- LiDAR -->
    <joint name="laser_joint" type="fixed">
        <parent link="body"/>
        <child link="laser_frame"/>
        <origin xyz="0.1 0 0.075" rpy="0 0 0"/>
    </joint>

    <link name="laser_frame">
        <visual>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
            <material name="red"/>
        </visual>
        <collision>
            <geometry>
                <cylinder radius="0.03" length="0.03"/>
            </geometry>
        </collision>
    </link>

    <!-- CAMERA -->
    <joint name="camera_joint" type="fixed">
        <parent link="body"/>
        <child link="camera_link"/>
        <origin xyz="0.20 0 0.03" rpy="0 0 0"/>
    </joint>

    <link name="camera_link">
        <visual>
            <geometry>
                <box size="0.01 0.03 0.03"/>
            </geometry>
            <material name="red"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.01 0.03 0.03"/>
            </geometry>
        </collision>
    </link>

    <joint name="camera_optical_joint" type="fixed">
        <parent link="camera_link"/>
        <child link="camera_link_optical"/>
        <origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
    </joint>

    <link name="camera_link_optical">
    </link>

    <!-- GAZEBO -->
    <xacro:include filename="gazebo.xacro"/>
    <xacro:include filename="lidar.xacro"/>
    <xacro:include filename="camera.xacro"/>

</robot>
  • 첫 번째 터미널에서 ‘CTRL+C’를 눌러서 프로그램을 종료 후 아래 명령을 실행해서 다시 실행합니다.
$ colcon build --symlink-install
$ ros2 launch urdf_tutorial camera.launch.py world:=src/urdf_tutorial/config/with_robot.world
  • 카메라에 수집된 이미지 정보가 출력되는 것을 확인할 수 있습니다.

  • 두 번째 터미널에서 아래 명령을 아래 명령을 실행해서 Rviz를 실행하고 저장된 'src/urdf_tutorial/config/lidar.rviz'를 읽어 옵니다.
$ rviz2
  • Rivz에서 ‘Add’ 버튼을 누른 후 ‘Image’를 선택하고 ‘Ok’ 버튼을 눌러서 Image를 추가합니다.

  • Rviz의 Image에서 ‘Topic’을 ‘/camera/image_raw’를 선택하면 아래와 같이 자동차에서 보내준 이미지를 수신할 수 있습니다.

  • 메뉴에서 ‘File’ >> ‘Save Config As’를 선택 후 'src/urdf_tutorial/config/camera.rviz'에 현재 설정을 저장합니다.
  • 세 번째 터미널에서 아래 명령을 실행합니다.
$ cd ~/Workspace/ros_ws/
$ ros2 topic echo /camera/image_raw
  • 아래 그림과 같이 Gazebo Camera에서 보내주는 사진 정보가 숫자 형식으로 화면에 출력되는 것을 확인할 수 있습니다.

  • 세 번째 PowerShell에서 ‘CTRL+C’를 눌러서 프로그램을 종료 후 아래 명령을 입력합니다.
$ ros2 run teleop_twist_keyboard teleop_twist_keyboard
  • 아래 화면에서 정당한 키를 눌러서 자동차를 움직여봅니다.
  • Rviz에서 자동차가 움직이는 것을 확인할 수 있습니다. 그리고 카메라에서 수집되는 정보도 변경되는 것을 확인할 수 있습니다.

  • 동시에 Gazebo에서도 자동차가 움직이고 카메라에 수집되는 정보가 변경되는 것을 확인할 수 있습니다.