02.3 드론 카메라 토픽을 ros 토픽으로 받아오기 - pineland/px4 GitHub Wiki

1. 모델 생성

1.1 모델 디렉토리 및 파일 생성

여기서는 /src/Firmware/Tools/sitl_gazebo/models/iris_opt_flow를 복사하여 iris_camera_topic를 만든다.
해당 디렉토리에 가서 iris_opt_flow 폴더를 복사하여 iris_camera_topic 폴더를 생성한다.
iris_camera_topic 폴더에 들어가서 iris_opt_flow.sdf파일을 iris_camera_topic.sdf 이름으로 바꿔준다.
참고로 Gazebo 모델은 ~/.gazebo/models/에 있는데 우리가 쓸 iris 모델은 /src/Firmware/Tools/sitl_gazebo/models/에 있다.

cd /src/Firmware/Tools/sitl_gazebo/models/
cp -r ./iris_opt_flow ./iris_camera_topic && cd ./iris_camera_topic
mv ./iris_opt_flow.sdf ./iris_camera_topic.sdf

1.2 iris에 카메라 달기

1.2.1 iris_camera_topic.sdf 수정

<?xml version='1.0'?>
<sdf version='1.5'>
  <model name='iris_camera_topic'>
    <include>
      <uri>model://iris</uri>
    </include>
    
    <!---------------- 수정하는 부분(시작) ---------------->
    <link name='camera::link'>
      <pose frame=''>0.1 0 0 0 0 0</pose>
      <inertial>
        <pose frame=''>0.01 0.025 0.025 0 -0 0</pose>
        <mass>0.01</mass>
        <inertia>
          <ixx>4.15e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>2.407e-06</iyy>
          <iyz>0</iyz>
          <izz>2.407e-06</izz>
        </inertia>
      </inertial>
      <self_collide>0</self_collide>
      <kinematic>0</kinematic>
      <sensor name='PX4Flow' type='camera'>
        <update_rate>30</update_rate>
        <camera name='__default__'>
          <horizontal_fov>0.6</horizontal_fov>
          <image>
            <width>256</width>
            <height>256</height>
          </image>
          <clip>
            <near>0.1</near>
            <far>100</far>
          </clip>
          <noise>
            <type>gaussian</type>
            <mean>0</mean>
            <stddev>0.001</stddev>
          </noise>
        </camera>
        <!-- Gazebo에서 발행되는 토픽을 ROS 토픽으로 카메라 데이터를 받아오는 플러그인.                                -->
        <!-- libgazebo_ros_camera.so는 /opt/ros/indigo/include/gazebo_plugins/gazebo_ros_camera.h를 말한다. -->
        <plugin name='camera_controller' filename='libgazebo_ros_camera.so'>
          <robotNamespace/>
          <cameraName>flow_camera</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>
      <visual name='visual'>
        <geometry>
          <box>
            <size>0.026012 0.029339 0.024291</size>
          </box>
        </geometry>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <cast_shadows>1</cast_shadows>
        <transparency>0</transparency>
      </visual>
    </link>
    <!-- 드론의 해당 위치에 나타나도록 조인트 -->
    <joint name="camera_joint" type="revolute">
      <parent>iris::base_link</parent>
      <child>camera::link</child>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <upper>0</upper>
          <lower>0</lower>
        </limit>
      </axis>
    </joint>
    <!---------------- 수정하는 부분(끝) ---------------->
    
  </model>
</sdf>

1.2.2 model.config 수정

<?xml version="1.0"?>
<model>
  <name>Iris with camera_topic</name>
  <version>1.0</version> 
  <sdf version='1.4'>iris_camera_topic.sdf</sdf>

  <author>
   <name>Christoph Tobler</name>
   <email>[email protected]</email>
  </author>

  <description>
    This is a model of the 3DR Iris Quadrotor with lidar and optical flow sensors. The original model has been created by
    Thomas Gubler and is maintained by Lorenz Meier. The sensors have been created by Christoph Tobler
  </description>
</model>

2 실행

//Terminal 1  
roscore

//Terminal 2
cd /src/Firmware
no_sim=1 make px4_sitl_default gazebo

//Terminal 3
export GAZEBO_MODEL_PATH=${GAZEBO_MODEL_PATH}:/src/Firmware/Tools/sitl_gazebo/models
export GAZEBO_PLUGIN_PATH=${GAZEBO_PLUGIN_PATH}:/src/Firmware/Tools/sitl_gazebo/Build
roslaunch gazebo_ros empty_world.launch

(해설1) no_sim=1을 앞에 붙여야 gazebo가 바로 실행되지는 않고 기존에 사용하던 mavros 패키지 안에 있는 topic들 말고 다른 정보들을 gazebo에서 토픽으로 받아볼 수 있다.  
(해설2) 환경변수(plugin/model)에 sitl_gazebo 폴더를 포함하며, ~/.bashrc에 등록이 되어 있으면 생략 가능하다. 
(해설3) default로 empty world를 부르고 gazebo 안에서 모델을 불러올 것이다.  

2.1 gazebo 내에서 드론 불러오기

gazebo 왼쪽 insert 항목에서 iris_camera_topic를 선택하여 scene에 추가해 준다.
다른 터미널을 하나더 열어서 rostopic이 뜨는 지 확인한다.

$ rostopic list | grep camera
  /iris_camera_topic/flow_camera/camera_info
  /iris_camera_topic/flow_camera/image_raw
  /iris_camera_topic/flow_camera/parameter_descriptions
  /iris_camera_topic/flow_camera/parameter_updates
$ rostopic echo /iris_camera_topic/flow_camera/image_raw
  (이미지값 배열들이 출력된다)

gazebo 내 드론 카메라 앞에 공을 하나 추가한다. 그리고 아래 명령을 실행하여 화면을 띄운다.

$ rosrun image_view image_view image:=/iris_camera_topic/flow_camera/image_raw  
⚠️ **GitHub.com Fallback** ⚠️