Table of Contents

  1. Mavlink Control
    1. Mavlink Utils
      1. mavproxy
    2. Mavlink Control Examples
  2. Odroid에 mavros offboard mode 실행하기
    1. mavros 설치
    2. mavros에서 px4.launch 실행
    3. px4.launch 수정
  3. SITL Gazebo에서 mavros offboard mode 실행하기
    1. 실행
      1. roscore 실행
      2. modudculab_ros 패키지 실행하기
      3. SITL Gazebo 실행
      4. mavros노드에 명령어 내리기
  4. pymavros 를 이용하기
    1. roscore 실행
    2. mavros node 실행
    3. SITL Gazebo 실행
    4. pymavros Setpoint_Position 예제 실행
    5. 참고

Mavlink Control

Companion(Onboard) PC와 FC연결. TELE2 사용

고마워 mavproxy, 그런데 너는 Ardupilot 만… 되냐.

  • pymavlink
  • mavproxy
  • dronekit
  • mavros

    pip install mavproxy

dronekit 최신버전으로 설치dronekit-install

git clone https://github.com/dronekit/dronekit-python.git      (dronekit-install)
cd ./dronekit-python
sudo python setup.py build
sudo python setup.py install

mavproxy

mavlink proxy server, collection of groundcontrol utility

relay 433mhz telemetry to local udp 14540 and udp:14560

python /usr/local/bin/mavproxy.py --master=/dev/ttyUSB0 --baudrate 57600 --out udp:127.0.0.1:14540  --out udp:127.0.0.1:14560

listen 14550 port, relay to 14540 14560

python  /usr/local/bin/mavproxy.py --master=:14550 --out udp:127.0.0.1:14540 --out udp:127.0.0.1:14560

비행 테스트는 시뮬레이터에서! 결과 확인은 QGroundControl에서!

Odroid에 mavros offboard mode 실행하기

mavros 설치

// expand swap in odroid xu4 to build mavros
$ sudo fallocate -l 4G /swapfile
$ sudo chmod 600 /swapfile
$ sudo mkswap /swapfile
$ sudo swapon /swapfile
// sudo vi /etc/fstab // add “/swapfile none swap sw 0 0” in the last line

$ 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-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116

$ sudo apt-get update -y
$ sudo apt-get install upgrade -y
# $ sudo apt-get install ros-kinetic-desktop-full 
# $ sudo apt-get install ros-kinetic-desktop
# $ sudo apt-get install ros-kinetic-ros-base
# $ sudo apt-get install ros-kinetic-control-toolbox
$ sudo apt-get install ros-kinetic-mavros ros-kinetic-mavros-extras
$ sudo apt-get install python-wstool python-rosinstall-generator python-catkin-tools

$ mkdir -p ~/catkin_ws/src
$ cd ~/catkin_ws
$ catkin init

$ wstool init ~/catkin_ws/src

# 1. get source (upstream - released)
$ rosinstall_generator --upstream mavros | tee /tmp/mavros.rosinstall
# alternative: latest source
$ rosinstall_generator --upstream-development mavros | tee /tmp/mavros.rosinstall

# 2. get latest released mavlink package
# you may run from this line to update ros-*-mavlink package
$ rosinstall_generator mavlink | tee -a /tmp/mavros.rosinstall

# 3. Setup workspace & install deps
$ wstool merge -t src /tmp/mavros.rosinstall
$ wstool update -t src

#$ rosdep install --from-paths src --ignore-src --rosdistro indigo -y
$ rosdep install --from-paths src --ignore-src --rosdistro kinetic -y --os=ubuntu:xenial

$ sudo apt-get install python-future

# finally - build
$ catkin build

GeographicLib 에러가 나면

[FATAL] [1506043767.570923014]: UAS: GeographicLib exception: File not readable /usr/share/GeographicLib/geoids/egm96-5.pgm | Run install_geographiclib_dataset.sh script in order to install Geoid Model dataset!
[mavros-1] process has died [pid 14648, exit code -5, cmd /home/donghee/catkin_ws/devel/lib/mavros/mavros_node __name:=mavros __log:=/home/donghee/.ros/log/a61f72a6-9f34-11e7-80c3-7cb0c21790bc/mavros-1.log].
log file: /home/donghee/.ros/log/a61f72a6-9f34-11e7-80c3-7cb0c21790bc/mavros-1*.log

다음 실행

cd /home/donghee/catkin_ws/src/mavros/mavros/scripts
sudo ./install_geographiclib_dataset.sh

mavros에서 px4.launch 실행

cd ~/catkin_ws/
roslaunch mavros px4.launch

px4.launch 수정

파일 위치: ~/catkin_ws/src/mavros/mavros/launch/px4.launch

odroid 에서 ttyUSB0에 pixhawk를 연결한 경우 px4.launch 파일 수정

  • pixhawk fcu_url: /dev/ttyUSB0:921600
  • qgroundcontrol gcs_url: 192.168.x.x:14550

odroid 에서 fcu를 gazebo로 선택한경우

  • gazebo fcu_url: udp://:14540@192.168.x.x:14557

SITL Gazebo에서 mavros offboard mode 실행하기

실행

roscore 실행

$ cd catkin_ws; source devel/setup.bash
$ roscore

modudculab_ros 패키지 실행하기

modudculab_ros 패키지의 pub_setpoints_pos 노드 실행

1m 높이 정지 비행

$ cd catkin_ws; source devel/setup.bash
$ cd ~/catkin_ws/src
$ git clone https://github.com/Jaeyoung-Lim/modudculab_ros.git
$ cd ~/catkin_ws
$ catkin build modudculab_ros
$ roslaunch modudculab_ros ctrl_pos_gazebo.launch

modudculab_ros 패키지의 pub_setpoints_traj 노드 실행

2m 높이로 원을 그리며 비행

$ roslaunch modudculab_ros ctrl_traj_gazebo.launch

~/catkin_ws/src/modudculab_ros/launch 위치에 있는 ctrl_pos_gazebo.launch 파일

<launch>

<arg name="fcu_url" default="udp://:14540@127.0.0.1:14557" />
<arg name="gcs_url" default="" />
<arg name="tgt_system" default="1" />
<arg name="tgt_component" default="1" />

<node name="mavros" pkg="mavros" type="mavros_node" output="screen">
  <param name="fcu_url" value="$(arg fcu_url)" />
  <param name="gcs_url" value="$(arg gcs_url)" />
  <param name="target_system_id" value="$(arg tgt_system)" />
  <param name="target_component_id" value="$(arg tgt_component)" />

  <!--rosparam command="load" file="$(find mavros)/launch/px4_blacklist.yaml"-->

  <!-- enable heartbeat send and reduce timeout -->
  <param name="conn_heartbeat" value="5.0" />
  <param name="conn_timeout" value="5.0" />
  <!-- automatically start mavlink on USB -->
  <param name="startup_px4_usb_quirk" value="true" />
  <param name="mocap/use_tf" value="true"/>
  <param name="mocap/use_pose" value="false"/>
</node>

<node name="pub_setpoints" pkg="modudculab_ros" type="pub_setpoints_pos" output="screen">

</node>

</launch>

ctrl_traj_gazebo.launch 파일

<launch>
<arg name="fcu_url" default="udp://:14540@127.0.0.1:14557" />
<arg name="gcs_url" default="" />
<arg name="tgt_system" default="1" />
<arg name="tgt_component" default="1" />


<node name="mavros" pkg="mavros" type="mavros_node" output="screen">
  <param name="fcu_url" value="$(arg fcu_url)" />
  <param name="gcs_url" value="$(arg gcs_url)" />
  <param name="target_system_id" value="$(arg tgt_system)" />
  <param name="target_component_id" value="$(arg tgt_component)" />

  <!--rosparam command="load" file="$(find mavros)/launch/px4_blacklist.yaml"-->

  <!-- enable heartbeat send and reduce timeout -->
  <param name="conn_heartbeat" value="5.0" />
  <param name="conn_timeout" value="5.0" />
  <!-- automatically start mavlink on USB -->
  <param name="startup_px4_usb_quirk" value="true" />
  <param name="mocap/use_tf" value="true"/>
  <param name="mocap/use_pose" value="false"/>
</node>

<node name="pub_setpoints_traj" pkg="modudculab_ros" type="pub_setpoints_traj" output="screen">
  <param name="wn" value="0.2" />
  <param name="r" value="3.0" />

</node>

</launch>

SITL Gazebo 실행

$ mkdir ~/src; cd ~/src
$ git clone https://github.com/PX4/Firmware.git
$ cd Firmware
$ git submodule update --init --recursive
$ make posix_sitl_default gazebo

mavros노드에 명령어 내리기

$ cd ~/catkin_ws; source devel/setup.bash
$ rosrun mavros mavsys mode -c OFFBOARD
$ rosrun mavros mavsafety arm 
$ rosrun mavros mavsys mode -c AUTO.RTL

$ rosrun mavros mavsetp local -p 1 0 0 0

rosrun mavros mavros_node _fcu_url:="udp://:14540@192.168.1.3:14557" rosrun mavros mavcmd takeoffcur 0 0 2

https://github.com/mavlink/mavros/blob/master/mavros/scripts/mavcmd

해보기

  • odroid에서 pub_setpoints 노드를 PC(노트북)의 Gazebo와 연결하기
  • odroid에서 pub_setpoints 노드를 FCU(ttyUSB0:921600)와 연결하기

참고

pymavros 를 이용하기

mavros의 python 버전

roscore 실행

$ cd catkin_ws; source devel/setup.bash
$ roscore

mavros node 실행

# gazebo
rosrun mavros mavros_node _fcu_url:="udp://:14540@192.168.1.3:14557"

# qgroundcontrol
rosrun mavros gcs_bridge _gcs_url:='udp://@192.168.1.3'

SITL Gazebo 실행

$ make posix_sitl_default gazebo

pymavros Setpoint_Position 예제 실행

다음 코드를 odroid에서 실행.

https://gist.github.com/donghee/7367afb515a6f761cc18c38313a548ff

참고