개발 환경 구축 (Ardupilot)

Dingool95·2022년 4월 5일
0

계기

VMware로 개발 중이었는데, 하드 디스크 용량을 30GB로 할당했었다.
충분할거라 생각했는데 모자란 상황이 되어버렸다.
용량 늘리기를 했는데, 대체 왜 디스크 파티션이 나타나지 않는 것인가.
부팅이 되지 않는 상황이 발생...

일단 해결할 수가 없음..
처음부터 다시 모든 것을 다 설치하는 것은 아주 무섭단 말이다.
다행인건 소스코드를 깃허브에 올려놨다.
변경된 코드를 푸쉬 하려니까 용량이 부족해서 임시 파일조차 만들지 못한다는 것 아닌가.
이게 사건의 발단이다. 결국 변경된 코드는 푸쉬하지 못하고, 처음부터 다시 환경세팅 하게되었다.
긍정적으로 생각하자. 가물가물해서 한 번 쫙 정리해볼 필요는 있다.
나중에 또 이런 일이 발생하면 유용하게 활용할 수 있으리라.


VMware 설치

이건 다시 설치할 필요가 없지 않은가.
귀찮다. 버전이 여러가지인데, VMware workstation 이라는 무료 버전을 사용한다.

우분투 설치

일단 최신 LTS 버전이 Ubuntu 20.04임.
하지만 나는 18.04가 필요하다. 구글 검색창에 ubuntu 검색하고 홈페이지 들어가기.

구 버전을 다운 받으려고 하는데, 상당히 안내가 불친절하다. (내 기준)
일단 여기서 받으면 된다.

클릭

클릭 (너무 구석에 있는거 아니냐고...)

쭉 내리면 있다.

데스크탑용 이미지를 받아준다.

이제 다운받은 이미지를 활용해서 가상머신에 우분투를 설치해보자.

다운받은 이미지 경로를 찾아서 선택해준다.

우분투에서 username이랑 비번 설정.

가상머신 이름 설정

문제의 디스크 할당. 다시는 모자랄 일 없도록 화끈하게 100기가 줘버렸다.
밑에 선택하는건 위에꺼로 했음.

이제 기다리면 된다.
우분투 설치 완료.

실행하고 풀스크린하면 화면이 채워지지 않는다.

이거 설정한적 없는거 같은데..
일단 이렇게 쓰자.


터미네이터 설치

$ sudo apt-get install terminator

우클릭해서 preference.

타이틀바 꺼주고

글자, 배경색을 white on black

창 투명하게 0.7정도

마지막 스크롤바 안 보이게


Visual Studio code 설치

그냥 설치하니까 안 되더라. 시간이 좀 걸린다.

$ sudo apt-get update
$ sudo apt-get upgrade
$ sudo apt-get install curl
$ sudo sh -c 'curl https://packages.microsoft.com/keys/microsoft.asc | gpg --dearmor > /etc/apt/trusted.gpg.d/microsoft.gpg'
$ sudo sh -c 'echo "deb [arch=amd64] https://packages.microsoft.com/repos/vscode stable main" > /etc/apt/sources.list.d/vscode.list'
$ sudo apt update	# 혹시 안되면 이거 하고 쉘 껐다켜기
$ sudo apt install code
$ code .

빌드 환경 설정

$ sudo apt-get install build-essential

크롬 설치

$ wget https://dl.google.com/linux/direct/google-chrome-stable_current_amd64.deb
$ sudo apt install ./google-chrome-stable_current_amd64.deb

설치했으면 좌측에 고정시켜주자.


Ardupilot 설치

$ sudo apt-get update
$ sudo apt-get install git
$ sudo apt-get install git-gui

$ cd ~
$ git clone https://github.com/ArduPilot/ardupilot.git
$ cd ardupilot
$ git checkout Copter-3.6
$ git submodule update --init --recursive

fatal: unable to connect to github.com:  <-- 이 에러 뜨면 아래 명령어 한 줄 실행
$ git config --global url.https://github.com/.insteadOf git://github.com/


$ sudo apt install python-matplotlib python-serial python-wxgtk3.0 python-wxtools python-lxml python-scipy python-opencv ccache gawk python-pip python-pexpect

$ sudo -H pip install future pymavlink MAVProxy # -H 안 하니까 안돼서 붙여서 실행
$ code ~/.bashrc

export PATH=$PATH:$HOME/ardupilot/Tools/autotest
export PATH=/usr/lib/ccache:$PATH

# 위 두 줄 추가
# 설치 확인
$ cd ~/ardupilot/ArduCopter
$ sim_vehicle.py -w

Ardupilot Gazebo 플러그인 설치

$ sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
$ wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
$ sudo apt update

$ sudo apt install python-matplotlib python-serial python-wxgtk3.0 python-wxtools python-lxml python-scipy python-opencv ccache gawk python-pip python-pexpect


$ sudo apt install gazebo9 libgazebo9-dev
# 이러고 실행하면 에러뜸. (VMware 문제)

$ echo "export SVGA_VGPU10=0" >> ~/.profile
$ code ~/.bashrc

export SVGA_VGPU10=0
# 추가

$ gazebo --verbose # 설치 확인

$ cd ~
$ git clone https://github.com/khancyr/ardupilot_gazebo
$ cd ardupilot_gazebo
$ git checkout dev

$ mkdir build
$ cd build
$ cmake ..
$ make -j4
$ sudo make install

$ code ~/.bashrc
source /usr/share/gazebo/setup.sh
export GAZEBO_MODEL_PATH=~/ardupilot_gazebo/models

# 두 줄 추가, source를 export 명령들 아랫줄에 배치


$ source ~/.bashrc

$ gazebo --verbose worlds/iris_arducopter_runway.world # 설치 확인
$ sim_vehicle.py -v ArduCopter -f gazebo-iris --console

MAVROS 설치할 때 같이 설치됨, MAVROS 쓸거면 pass

$ sudo apt-get install python3-pip
$ pip3 install --user future
$ sudo apt install python3-lxml libxml2-utils
$ sudo apt install python3-tk
$ cd ~
$ git clone https://github.com/mavlink/mavlink.git --recursive
$ code ~/.bashrc

export PYTHONPATH=/home/j/mavlink # <== 설치된 경로로 알아서 수정
# 추가

$ source ~/.bashrc

$ echo $PYTHONPATH # 환경변수 확인
/home/j/mavlink

Library 설치

$ cd ~/mavlink
$ git clone https://github.com/mavlink/c_library_v2
$ mv ./c_library_v2 ./include

ROS Melodic 설치

이미 포스팅 했으나, 다시 정리

$ sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu (lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
$ sudo apt install curl

$ curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add -
$ sudo apt update

$ sudo apt install ros-melodic-desktop-full

$ sudo apt install python-rosdep python-rosinstall python-rosinstall-generator python-wstool build-essential
$ sudo apt install python-rosdep

$ sudo rosdep init
$ rosdep update
$ source /opt/ros/melodic/setup.bash

$ mkdir -p ~/catkin_ws/src
$ cd ~/catkin_ws/src
$ catkin_init_workspace
$ cd ~/catkin_ws && catkin_make
$ source ~/catkin_ws/devel/setup.bash
$ code ~/.bashrc


# ROS environment
source /opt/ros/melodic/setup.bash
source ~/catkin_ws/devel/setup.bash

export ROS_HOSTNAME=localhost
export ROS_MASTER_URI=http://localhost:11311

alias cs='cd ~/catkin_ws/src'
alias cw='cd ~/catkin_ws'
alias sb='source ~/.bashrc'

# bashrc에 추가

$ source ~/.bashrc

MAVROS 설치

Melodic 용임 주의.

$ sudo apt-get install python-catkin-tools python-rosinstall-generator -y

$ cd ~/catkin_ws
$ catkin init
$ wstool init src

$ rosinstall_generator --rosdistro kinetic mavlink | tee /tmp/mavros.rosinstall
$ rosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall


$ wstool merge -t src /tmp/mavros.rosinstall
$ wstool update -t src -j4
$ rosdep install --from-paths src --ignore-src -y

$ sudo ./src/mavros/mavros/scripts/install_geographiclib_datasets.sh
$ catkin build
$ source devel/setup.bash

$ cd ~/catkin_ws/src/mavros/mavros/launch
$ code  ./apm.launch

SITL 환경이므로 fcu_url을 수정해주자.

<!-- arg name="fcu_url" default="/dev/ttyACM0:57600" / -->  주석처리
<arg name="fcu_url" default="udp://127.0.0.1:14551@14555" />  이렇게 변경

설치 확인

1. MAVProxy 실행

$ sim_vehicle.py -v ArduCopter -f gazebo-iris --map --console

2. Gazebo 실행

$ gazebo --verbose ~/ardupilot_gazebo/worlds/iris_arducopter_runway.world

3. MAVROS 실행

$ roslaunch mavros apm.launch

MAVROS로 코드를 실행하려면, 드론이 takeoff된 상태에서 코드가 먹힌다.


카메라 달기

위 링크의 model.config, model.sdf 파일을 복사해준다.

$ cd /usr/share/gazebo-9/models
$ sudo mkdir ./iris_with_camera
$ cd ./iris_with_camera
$ ls
model.config  model.sdf

model.sdf 파일에서 수정해줄 것이 있음. 가장 윗쪽.

<?xml version='1.0'?>
<sdf version="1.6" >
  <model name="drone_with_camera">
    <include>
      <uri>model://iris_base</uri>   --> 요놈 수정 필요
    </include>

이렇게 수정해준다.

<?xml version='1.0'?>
<sdf version="1.6" >
  <model name="drone_with_camera">
    <include>
      <uri>model://iris_with_standoffs</uri>
    </include>

수정한 모델을 월드에 넣어주자.
새로운 월드를 하나 복사함.

$ cd /usr/share/gazebo-9/worlds
$ sudo cp ./iris_arducopter_runway.world ./custom_iris.world

복사한 world 파일 열어서 제일 밑에 보면 이렇게 나옮.

<model name="iris_demo">
      <include>
        <uri>model://iris_with_ardupilot</uri>
      </include>
    </model>
  </world>
</sdf>

위에서 모델 파일명을 iris_with_camera 라고 했으므로 맞춰서 수정하고 저장.

<model name="iris_demo">
      <include>
        <uri>model://iris_with_camera</uri>
      </include>
    </model>
  </world>
</sdf>

이제 gazebo_ros 런치 파일로 가보자.

런치 파일이 여러 개 있는데 empty_world.launch 를 복사해서 iris_arducopter_runway_world.launch 로 만들어줬음.

$ roscd gazebo_ros/launch
$ cp ./empty_world.launch ./iris_arducopter_runway_world.launch

iris_arducopter_runway_world.launch 열어서 world_name argument를 변경해줌.

<arg name="world_name" default="worlds/empty.world"/> 수정 전

<arg name="world_name" default="worlds/custom_iris.world"/>  수정 후

실행 확인

$ roslaunch gazebo_ros iris_arducopter_runway_world.launch


뎁스 카메라 달기

기존에 만들었던 (정면 응시) 카메라가 달린 모델을 활용하기 위해서 복사.

$ cd /usr/share/gazebo-9/models
$ sudo cp -r ./iris_with_camera ./iris_with_depth

model.sdf 파일 열어보면 <link> </link> 사이에 <sensor> </sensor> 테그를 다음으로 바꾼다.

<sensor name="depth_camera" type="depth">
      <update_rate>20</update_rate>
      <camera>
        <horizontal_fov>1.047198</horizontal_fov>
        <image>
          <width>640</width>
          <height>480</height>
          <format>R8G8B8</format>
        </image>
        <clip>
          <near>0.05</near>
          <far>3</far>
        </clip>
      </camera>
      <plugin name="camera_plugin" filename="libgazebo_ros_openni_kinect.so">
        <baseline>0.2</baseline>
        <alwaysOn>true</alwaysOn>
        <!-- Keep this zero, update_rate in the parent <sensor> tag
            will control the frame rate. -->
        <updateRate>20.0</updateRate>
        <cameraName>camera_ir</cameraName>
        <imageTopicName>/camera/color/image_raw</imageTopicName>
        <cameraInfoTopicName>/camera/color/camera_info</cameraInfoTopicName>
        <depthImageTopicName>/camera/depth/image_raw</depthImageTopicName>
        <depthImageCameraInfoTopicName>/camera/depth/camera_info</depthImageCameraInfoTopicName>
        <pointCloudTopicName>/camera/depth/points</pointCloudTopicName>
        <frameName>depth_camera_link</frameName>
        <pointCloudCutoff>0.05</pointCloudCutoff>
        <distortionK1>0</distortionK1>
        <distortionK2>0</distortionK2>
        <distortionK3>0</distortionK3>
        <distortionT1>0</distortionT1>
        <distortionT2>0</distortionT2>
        <CxPrime>0</CxPrime>
        <Cx>0</Cx>
        <Cy>0</Cy>
        <focalLength>0</focalLength>
        <hackBaseline>0</hackBaseline>
      </plugin>
    </sensor>

정면 응시 카메라처럼 화각이 시각화되지 않는데 정상이다.

depth camera 인데, 일반 RGB 영상과 depth 영상 둘 다 토픽을 내보낸다.
RGB 영상 토픽은 /camera/color/image_raw
Depth 영상 토픽은 /camera/depth/image_raw 이다.
rqt_image_view 를 바로 실행하면 pluin을 추가로 선택할 수 없다.
그냥 rqt 만 실행하고 plugin >> visualization >> image view 를 선택해주면
아래와 같이 멀티뷰로 여러개의 토픽 영상을 볼 수 있다.

리얼센스 달기

$ sudo apt-get install ros-$ROS_DISTRO-realsense2-camera
$ sudo apt-get install ros-$ROS_DISTRO-realsense2-description
$ cd ./catkin_ws/src
$ git clone https://github.com/nilseuropa/realsense_ros_gazebo.git
$ cd ./catkin_ws && catkin build
$ source ./devel/setup.bash
$ roslaunch realsense_ros_gazebo simulation.launch


$ cd /usr/share/gazebo-9/models
$ sudo cp -p ./iris_with_camera ./iris_with_real 

위에서 simulation.launch를 열어보면 test.xacro파일을 활용함.

  <!-- Model setup -->
  <arg name="model" default="$(find realsense_ros_gazebo)/urdf/test.xacro"/>
$ cd ~/catkin_ws/src/realsense_ros_gazebo/urdf
$ ls
test.xacro

$ xacro test.xacro > model.urdf
$ gz sdf -p model.urdf > model.sdf
$ ls
model.sdf  model.urdf  test.xacro

$ code model.sdf

필요없는 부분 주석처리

      <!-- <pose frame=''>0 0 0 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0.007846 0 -0 0</pose>
        <mass>100.564</mass>
        <inertia>
          <ixx>1.17136</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>1.53901</iyy>
          <iyz>0</iyz>
          <izz>2.13206</izz>
        </inertia>
      </inertial>
      <collision name='base_footprint_fixed_joint_lump__base_link_collision'>
        <pose frame=''>0 0 0.005 0 -0 0</pose>
        <geometry>
          <box>
            <size>0.4 0.4 0.01</size>
          </box>
        </geometry>
      </collision> -->

리얼센스 시각화를 위해서 .stl파일이 필요.
model.sdf파일 중간쯤에 보면

        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://iris_with_real/meshes/realsense_d435.stl</uri>
          </mesh>
        </geometry>

meshes 폴더가 필요함

$ sudo cp -r ~/catkin_ws/src/realsense_ros_gazebo/meshes /usr/share/gazebo-9/models/iris_with_real/meshes

다시 model.sdf파일
1. 무게가 너무 무거움. 1kg 으로 설정되어 있음. 근데 0으로 하니까 에러뜸. 0.001로 바꿈. 그에 맞게 inertial도 바꿈.
2. <visual>태그 바로 밑의 <pose> 태그 수정해서 카메라 위치 변경할 수 있는데

아래 사진처럼 카메라 시각화 위치만 변하고 실제 초점 위치가 안변함.

초점 위치 바꾸려면 <sensor> 태그 안의 <pose> 태그를 따로 수정 해줘야 됨.
완성 모습

일단 월드 파일 수정.

    <!-- <model name="iris_demo">
      <include>
        <uri>model://iris_with_depth</uri>
      </include>
    </model> -->

    <model name="realsense">
      <include>
        <uri>model://iris_with_real</uri>
      </include>
    </model>
  </world>
</sdf>

최종 모델 파일

<?xml version='1.0'?>
<sdf version='1.6'>
  <model name='test_model'>
    <include>
      <uri>model://iris_with_standoffs</uri>
    </include>

    <link name='cam_link'>
      <pose frame=''>0 0 0 0 -0 0</pose>
      <inertial>
        <mass>0.001</mass>
        <inertia>
          <ixx>0.001</ixx>
          <iyy>0.001</iyy>
          <izz>0.001</izz>
        </inertia>
      </inertial>
      <!-- <pose frame=''>0 0 0 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0.007846 0 -0 0</pose>
        <mass>100.564</mass>
        <inertia>
          <ixx>1.17136</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>1.53901</iyy>
          <iyz>0</iyz>
          <izz>2.13206</izz>
        </inertia>
      </inertial>
      <collision name='base_footprint_fixed_joint_lump__base_link_collision'>
        <pose frame=''>0 0 0.005 0 -0 0</pose>
        <geometry>
          <box>
            <size>0.4 0.4 0.01</size>
          </box>
        </geometry>
      </collision> -->
      <!-- <collision name='d435_link_collision'>
        <pose frame=''>0 0 0.5125 0 -0 0</pose>
        <geometry>
          <box>
            <size>0.02505 0.09 0.025</size>
          </box>
        </geometry>
        <surface>
          <contact>
            <ode>
              <kp>1e+13</kp>
              <kd>1</kd>
            </ode>
          </contact>
          <friction>
            <ode>
              <mu2>1</mu2>
              <fdir1>0 0 0</fdir1>
            </ode>
          </friction>
        </surface>
      </collision> -->
      <!-- <visual name='base_footprint_fixed_joint_lump__base_link_visual'>
        <pose frame=''>0 0 0.005 0 -0 0</pose>
        <geometry>
          <box>
            <size>0.4 0.4 0.01</size>
          </box>
        </geometry>
      </visual> -->
      <visual name='d435_link_visual'>
        <pose frame=''>0.1249 0 0.2 1.5708 -0 1.5708</pose>
        <!-- <pose frame=''>0.0149 0 0.5125 1.5708 -0 1.5708</pose> -->
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://realsense/meshes/realsense_d435.stl</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <uri>__default__</uri>
            <name>__default__</name>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
      <enable_wind>0</enable_wind>
      <kinematic>0</kinematic>
      <gravity>1</gravity>
      <sensor name='d435_color' type='camera'>
        <camera name='d435'>
          <horizontal_fov>1.21126</horizontal_fov>
          <image>
            <width>640</width>
            <height>480</height>
            <format>RGB_INT8</format>
          </image>
          <clip>
            <near>0.1</near>
            <far>100</far>
          </clip>
          <noise>
            <type>gaussian</type>
            <mean>0</mean>
            <stddev>0.007</stddev>
          </noise>
        </camera>
        <always_on>1</always_on>
        <update_rate>30</update_rate>
        <visualize>1</visualize>
        <pose frame=''>0.11 0.0175 0.2 0 -0 0</pose>
      </sensor>
      <sensor name='d435_ired1' type='camera'>
        <camera name='d435'>
          <horizontal_fov>1.48702</horizontal_fov>
          <image>
            <width>1280</width>
            <height>720</height>
            <format>L_INT8</format>
          </image>
          <clip>
            <near>0.1</near>
            <far>100</far>
          </clip>
          <noise>
            <type>gaussian</type>
            <mean>0</mean>
            <stddev>0.05</stddev>
          </noise>
        </camera>
        <always_on>1</always_on>
        <update_rate>90</update_rate>
        <visualize>0</visualize>
        <pose frame=''>0.11 0.0175 0.2 0 -0 0</pose>
      </sensor>
      <sensor name='d435_ired2' type='camera'>
        <camera name='d435'>
          <horizontal_fov>1.48702</horizontal_fov>
          <image>
            <width>1280</width>
            <height>720</height>
            <format>L_INT8</format>
          </image>
          <clip>
            <near>0.1</near>
            <far>100</far>
          </clip>
          <noise>
            <type>gaussian</type>
            <mean>0</mean>
            <stddev>0.05</stddev>
          </noise>
        </camera>
        <always_on>1</always_on>
        <update_rate>90</update_rate>
        <visualize>0</visualize>
        <pose frame=''>0.11 0.0175 0.2 0 -0 0</pose>
      </sensor>
      <sensor name='d435_depth' type='depth'>
        <camera name='d435'>
          <horizontal_fov>1.48702</horizontal_fov>
          <image>
            <width>1280</width>
            <height>720</height>
          </image>
          <clip>
            <near>0.1</near>
            <far>100</far>
          </clip>
          <noise>
            <type>gaussian</type>
            <mean>0</mean>
            <stddev>0.1</stddev>
          </noise>
        </camera>
        <always_on>1</always_on>
        <update_rate>90</update_rate>
        <visualize>0</visualize>
        <pose frame=''>0.11 0.0175 0.2 0 -0 0</pose>
      </sensor>
    </link>
    <static>0</static>

    <joint name="camera_mount" type="fixed">
      <child>cam_link</child>
      <parent>iris::base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <upper>0</upper>
          <lower>0</lower>
        </limit>
      </axis>
    </joint>

    <plugin name='d435' filename='librealsense_gazebo_plugin.so'>
      <prefix>d435_</prefix>
      <depthUpdateRate>10</depthUpdateRate>
      <colorUpdateRate>10</colorUpdateRate>
      <infraredUpdateRate>10</infraredUpdateRate>
      <depthTopicName>depth/image_raw</depthTopicName>
      <depthCameraInfoTopicName>depth/camera_info</depthCameraInfoTopicName>
      <colorTopicName>color/image_raw</colorTopicName>
      <colorCameraInfoTopicName>color/camera_info</colorCameraInfoTopicName>
      <infrared1TopicName>infra1/image_raw</infrared1TopicName>
      <infrared1CameraInfoTopicName>infra1/camera_info</infrared1CameraInfoTopicName>
      <infrared2TopicName>infra2/image_raw</infrared2TopicName>
      <infrared2CameraInfoTopicName>infra2/camera_info</infrared2CameraInfoTopicName>
      <colorOpticalframeName>d435_color_optical_frame</colorOpticalframeName>
      <depthOpticalframeName>d435_depth_optical_frame</depthOpticalframeName>
      <infrared1OpticalframeName>d435_infrared1_optical_frame</infrared1OpticalframeName>
      <infrared2OpticalframeName>d435_infrared2_optical_frame</infrared2OpticalframeName>
      <rangeMinDepth>0.2</rangeMinDepth>
      <rangeMaxDepth>10.0</rangeMaxDepth>
      <pointCloud>0</pointCloud>
      <pointCloudTopicName>depth/color/points</pointCloudTopicName>
      <pointCloudCutoff>0.25</pointCloudCutoff>
      <pointCloudCutoffMax>9.0</pointCloudCutoffMax>
    </plugin>

    <!-- plugins -->
    <plugin name="rotor_0_blade_1" filename="libLiftDragPlugin.so">
      <a0>0.3</a0>
      <alpha_stall>1.4</alpha_stall>
      <cla>4.2500</cla>
      <cda>0.10</cda>
      <cma>0.00</cma>
      <cla_stall>-0.025</cla_stall>
      <cda_stall>0.0</cda_stall>
      <cma_stall>0.0</cma_stall>
      <area>0.002</area>
      <air_density>1.2041</air_density>
      <cp>0.084 0 0</cp>
      <forward>0 1 0</forward>
      <upward>0 0 1</upward>
      <link_name>iris::rotor_0</link_name>
    </plugin>
    <plugin name="rotor_0_blade_2" filename="libLiftDragPlugin.so">
      <a0>0.3</a0>
      <alpha_stall>1.4</alpha_stall>
      <cla>4.2500</cla>
      <cda>0.10</cda>
      <cma>0.00</cma>
      <cla_stall>-0.025</cla_stall>
      <cda_stall>0.0</cda_stall>
      <cma_stall>0.0</cma_stall>
      <area>0.002</area>
      <air_density>1.2041</air_density>
      <cp>-0.084 0 0</cp>
      <forward>0 -1 0</forward>
      <upward>0 0 1</upward>
      <link_name>iris::rotor_0</link_name>
    </plugin>

    <plugin name="rotor_1_blade_1" filename="libLiftDragPlugin.so">
      <a0>0.3</a0>
      <alpha_stall>1.4</alpha_stall>
      <cla>4.2500</cla>
      <cda>0.10</cda>
      <cma>0.00</cma>
      <cla_stall>-0.025</cla_stall>
      <cda_stall>0.0</cda_stall>
      <cma_stall>0.0</cma_stall>
      <area>0.002</area>
      <air_density>1.2041</air_density>
      <cp>0.084 0 0</cp>
      <forward>0 1 0</forward>
      <upward>0 0 1</upward>
      <link_name>iris::rotor_1</link_name>
    </plugin>
    <plugin name="rotor_1_blade_2" filename="libLiftDragPlugin.so">
      <a0>0.3</a0>
      <alpha_stall>1.4</alpha_stall>
      <cla>4.2500</cla>
      <cda>0.10</cda>
      <cma>0.00</cma>
      <cla_stall>-0.025</cla_stall>
      <cda_stall>0.0</cda_stall>
      <cma_stall>0.0</cma_stall>
      <area>0.002</area>
      <air_density>1.2041</air_density>
      <cp>-0.084 0 0</cp>
      <forward>0 -1 0</forward>
      <upward>0 0 1</upward>
      <link_name>iris::rotor_1</link_name>
    </plugin>

    <plugin name="rotor_2_blade_1" filename="libLiftDragPlugin.so">
      <a0>0.3</a0>
      <alpha_stall>1.4</alpha_stall>
      <cla>4.2500</cla>
      <cda>0.10</cda>
      <cma>0.00</cma>
      <cla_stall>-0.025</cla_stall>
      <cda_stall>0.0</cda_stall>
      <cma_stall>0.0</cma_stall>
      <area>0.002</area>
      <air_density>1.2041</air_density>
      <cp>0.084 0 0</cp>
      <forward>0 -1 0</forward>
      <upward>0 0 1</upward>
      <link_name>iris::rotor_2</link_name>
    </plugin>
    <plugin name="rotor_2_blade_2" filename="libLiftDragPlugin.so">
      <a0>0.3</a0>
      <alpha_stall>1.4</alpha_stall>
      <cla>4.2500</cla>
      <cda>0.10</cda>
      <cma>0.00</cma>
      <cla_stall>-0.025</cla_stall>
      <cda_stall>0.0</cda_stall>
      <cma_stall>0.0</cma_stall>
      <area>0.002</area>
      <air_density>1.2041</air_density>
      <cp>-0.084 0 0</cp>
      <forward>0 1 0</forward>
      <upward>0 0 1</upward>
      <link_name>iris::rotor_2</link_name>
    </plugin>

    <plugin name="rotor_3_blade_1" filename="libLiftDragPlugin.so">
      <a0>0.3</a0>
      <alpha_stall>1.4</alpha_stall>
      <cla>4.2500</cla>
      <cda>0.10</cda>
      <cma>0.00</cma>
      <cla_stall>-0.025</cla_stall>
      <cda_stall>0.0</cda_stall>
      <cma_stall>0.0</cma_stall>
      <area>0.002</area>
      <air_density>1.2041</air_density>
      <cp>0.084 0 0</cp>
      <forward>0 -1 0</forward>
      <upward>0 0 1</upward>
      <link_name>iris::rotor_3</link_name>
    </plugin>
    <plugin name="rotor_3_blade_2" filename="libLiftDragPlugin.so">
      <a0>0.3</a0>
      <alpha_stall>1.4</alpha_stall>
      <cla>4.2500</cla>
      <cda>0.10</cda>
      <cma>0.00</cma>
      <cla_stall>-0.025</cla_stall>
      <cda_stall>0.0</cda_stall>
      <cma_stall>0.0</cma_stall>
      <area>0.002</area>
      <air_density>1.2041</air_density>
      <cp>-0.084 0 0</cp>
      <forward>0 1 0</forward>
      <upward>0 0 1</upward>
      <link_name>iris::rotor_3</link_name>
    </plugin>
    <plugin name="arducopter_plugin" filename="libArduPilotPlugin.so">
      <fdm_addr>127.0.0.1</fdm_addr>
      <fdm_port_in>9002</fdm_port_in>
      <fdm_port_out>9003</fdm_port_out>
      <!--
          Require by APM :
          Only change model and gazebo from XYZ to XY-Z coordinates
      -->
      <modelXYZToAirplaneXForwardZDown>0 0 0 3.141593 0 0</modelXYZToAirplaneXForwardZDown>
      <gazeboXYZToNED>0 0 0 3.141593 0 0</gazeboXYZToNED>
      <imuName>iris::iris/imu_link::imu_sensor</imuName>
      <connectionTimeoutMaxCount>5</connectionTimeoutMaxCount>
      <control channel="0">
      <!--
          incoming control command [0, 1]
          so offset it by 0 to get [0, 1]
          and divide max target by 1.
          offset = 0
          multiplier = 838 max rpm / 1 = 838
        -->
        <type>VELOCITY</type>
        <offset>0</offset>
        <p_gain>0.20</p_gain>
        <i_gain>0</i_gain>
        <d_gain>0</d_gain>
        <i_max>0</i_max>
        <i_min>0</i_min>
        <cmd_max>2.5</cmd_max>
        <cmd_min>-2.5</cmd_min>
        <jointName>iris::rotor_0_joint</jointName>
        <multiplier>838</multiplier>
        <controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>
      </control>
      <control channel="1">
        <type>VELOCITY</type>
        <offset>0</offset>
        <p_gain>0.20</p_gain>
        <i_gain>0</i_gain>
        <d_gain>0</d_gain>
        <i_max>0</i_max>
        <i_min>0</i_min>
        <cmd_max>2.5</cmd_max>
        <cmd_min>-2.5</cmd_min>
        <jointName>iris::rotor_1_joint</jointName>
        <multiplier>838</multiplier>
        <controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>
      </control>
      <control channel="2">
        <type>VELOCITY</type>
        <offset>0</offset>
        <p_gain>0.20</p_gain>
        <i_gain>0</i_gain>
        <d_gain>0</d_gain>
        <i_max>0</i_max>
        <i_min>0</i_min>
        <cmd_max>2.5</cmd_max>
        <cmd_min>-2.5</cmd_min>
        <jointName>iris::rotor_2_joint</jointName>
        <multiplier>-838</multiplier>
        <controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>
      </control>
      <control channel="3">
        <type>VELOCITY</type>
        <offset>0</offset>
        <p_gain>0.20</p_gain>
        <i_gain>0</i_gain>
        <d_gain>0</d_gain>
        <i_max>0</i_max>
        <i_min>0</i_min>
        <cmd_max>2.5</cmd_max>
        <cmd_min>-2.5</cmd_min>
        <jointName>iris::rotor_3_joint</jointName>
        <multiplier>-838</multiplier>
        <controlVelocitySlowdownSim>1</controlVelocitySlowdownSim>
      </control>
    </plugin>
  </model>
</sdf>
profile
내 맘대로 요점정리

0개의 댓글