[ROS] 카메라 플러그인 적용하기

Nodazi·2024년 1월 13일
0

ROS

목록 보기
13/21
post-thumbnail

🐣0.개요

지난 시간에 Gazebo에서 사용할 수 있는 TagPlugin, 적용방법에 대해서 학습하였다.
그리고 world 파일 tag population에 대해서 학습하면서 규칙을 생성하여 월드를 만드는 방법에 대해서 학습하였다.
이번 시간에는 카메라 모듈을 적용한 로봇 모델을 지난 시간에 만든 world에 배치하여 Camera Plugin의 동작 화면을 확인하는게 목표이다.
아래의 링크에서 Camera 플러그인 적용법을 참조 할 수 있었다.

[Gazebo plugins in ROS] - https://classic.gazebosim.org/tutorials?tut=ros_gzplugins#Camera

🗒1.코드 작성

📒1.1 .xacro 파일 작성

카메라의 형태를 정의해준다.
카메라의 위치는 이전에 만든 Ladar 위에 위치시키기 위해 parent link를 해당 링크로 정의하였다.
joint의 위치를 parent link의 z축으로 0.1m 위치한 곳으로 선언하였다.
xacro:property를 통해 정육면체 모양의 카메라의 길이를 선언하였다.
🤖robot.xacro

...
    <xacro:property name="camera_link" value="0.05" />
...
    <!-- camera_joint -->
    <joint name="camera_joint" type="fixed">
        <axis xyz="0 1 0" />
        <origin rpy="0 0 0" xyz="0 0 0.1"/>
        <parent link="link_laser_scan"/>
        <child link="camera_link"/>
    </joint>

    <!-- Camera -->
    <link name="camera_link">
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <box size="${camera_link} ${camera_link} ${camera_link}"/>
            </geometry>
        </collision>

        <visual>
            <origin xyz="0 0 0" rpy="0 0 0"/>
                <geometry>
                    <box size="${camera_link} ${camera_link} ${camera_link}"/>
                </geometry>
        </visual>

        <inertial>
            <mass value="1e-5" />
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
        </inertial>
    </link>
...

카메라의 색상은 robot.gazebo에서 적용하였다.
🏛️robot.gazebo

...
    <gazebo reference="camera_link">
    <material>Gazebo/Red</material>
    </gazebo>
...

🔌1.2 .gazebo 파일 Camera plugin 적용

.gazebo 파일에 Camera plugin을 사용하기 위한 코드를 아래와 같이 추가하였다.

🏛️robot.gazebo

...
<gazebo reference="camera_link">
        <sensor type="camera" name="camera1">
        <update_rate>30.0</update_rate>
        <camera name="head">
            <horizontal_fov>1.3962634</horizontal_fov>
            <image>
                <width>800</width>
                <height>800</height>
                <format>R8G8B8</format>
            </image>
            <clip>
                <near>0.02</near>
                <far>300</far>
            </clip>
            <noise>
                <type>gaussian</type>
                <!-- Noise is sampled independently per pixel on each frame.
                    That pixel's noise value is added to each of its color
                    channels, which at that point lie in the range [0,1]. -->
                <mean>0.0</mean>
                <stddev>0.007</stddev>
            </noise>
        </camera>
        <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
            <alwaysOn>true</alwaysOn>
            <updateRate>0.0</updateRate>
            <cameraName>rrbot/camera1</cameraName>
            <imageTopicName>image_raw</imageTopicName>
            <cameraInfoTopicName>camera_info</cameraInfoTopicName>
            <frameName>camera_link</frameName>
            <hackBaseline>0.07</hackBaseline>
            <distortionK1>0.0</distortionK1>
            <distortionK2>0.0</distortionK2>
            <distortionK3>0.0</distortionK3>
            <distortionT1>0.0</distortionT1>
            <distortionT2>0.0</distortionT2>
        </plugin>
        </sensor>
    </gazebo>
...

.gazebo에서 선언한 camera_linkcamera 플러그인을 적용하는 코드이다.
각각의 Tag의 역할에 대해서 알아보자.
sensor : 센서를 정의한다. 위코드에서는 camera 센서의 속성 값 및 플러그인이 포함되어 있는 Tag이다.
updata_rate : 카메라 센서의 프레임을 선언 (FPS: Frame per Second).
horizontal_fov : 카메라의 시야각을 나타낸다. 위 코드의 선언값은 1.3962634 약 80도의 시야각을 나타낸다.
image : 카메라의 해상도 및 형식을 지정한다. (800 * 800) , R8G8B8 은 RGB의 각각의 값들이 8비트로 표현된다는 뜻이다.
clip : 카메라의 클리핑을 설정한다. 카메라의 최대 거리 및 최소 거리를 지정 할 수 있다.
noise : 사진의 노이즈를 추가한다. 노이즈를 추가하는 이유는 현실의 카메라는 노이즈가 존재하기 때문에 시뮬레이션 환경에서 불확실성을 추가하여 현실과 비슷한 시뮬레이션을 진행 할 수 있게 한다. gaussian 노이즈를 추가하였고 표준편차 및 평균 값을 지정할 수 있다.

gaussian noise 란 - 가우스 분포를 나타내는 잡음으로 이미지 처리를 할 때 주로 나타나는 노이즈. 차후 자세히 다뤄보겠다.

plugin : 플러그인 내용으로 libgazebo_ros_camera.so 플러그인을 사용한다.
내부의 내용은 카메라의 이름, 주기, 발행토픽이름, 왜곡 등을 설정 할 수 있다.

✈️2.실행화면

전에 작업한 world 에 모형 로봇을 소환하여 카메라 시점을 확인 할 수 있었다.
로봇이 움직이면서 카메라의 시점이 바뀌는 데,
카메라 시야각에 보이는 물체들을 잡아내는 것을 확인 할 수 있다.

실행과정은 아래와 같다.
1.world 실행

$roslaunch robot_description empty_world.launch

2.spawn robot

$roslaunch robot_description spawn.launch

3.동작 명령

$rosrun move_with_laser.py

4.rviz 에서 카메라 토픽 기반으로 만들어진 이미지 확인

$roslaunch robot_description rviz.launch

rqt_graph 를 통해 토픽의 흐름을 확인 할 수 있다.

profile
GoGoSing

0개의 댓글

관련 채용 정보