DroneKit 이용해서 PX4와 통신하기
DroneKit을 이용해서 UAV용 app을 만들 수 있습니다. 이 app은 UAV의 Companion Computer에서 실행되며 계산이 많고 빠르게 데이터 전송(예로 컴퓨터 비전)이 필요한 타스크를 실행해서 자동비행 기능을 향상시킵니다.
DroneKit과 PX4는 현재 완전히 호환되도록 개발 중입니다. DroneKit-python 2.2.0에서 미션 처리와 비행체 모니터링에 대해서 기본으로 지원하고 있다.
DroneKit을 PX4와 셋업하기
현재 master에서 DroneKit-python 설치하는 것부터 시작합니다.
git clone https://github.com/dronekit/dronekit-python.git
cd ./dronekit-python
sudo python setup.py build
sudo python setup.py install
새로 python 파일을 생성하고 DroneKit, pymavlink와 기본 모듈을 import 합니다.
# Import DroneKit-Python
from dronekit import connect, Command, LocationGlobal
from pymavlink import mavutil
import time, sys, argparse, math
드론이나 시뮬레이션의 MavLink port에 연결합니다.(예제 JMavSim)
# Connect to the Vehicle
print "Connecting"
connection_string = '127.0.0.1:14540'
vehicle = connect(connection_string, wait_ready=True)
기본 상태 정보를 표시합니다.
# Display basic vehicle state
print " Type: %s" % vehicle._vehicle_type
print " Armed: %s" % vehicle.armed
print " System status: %s" % vehicle.system_status.state
print " GPS: %s" % vehicle.gps_0
print " Alt: %s" % vehicle.location.global_relative_frame.alt
전체 미션 예제
다음 python script는 DroneKit과 PX4를 사용해서 전체 미션 예제를 보여줍니다. Mode 스위칭은 DroneKit에서 지원하지 않으므로 커스텀 mode 스위칭 명령을 사용합니다.
################################################################################################
# @File DroneKitPX4.py
# Example usage of DroneKit with PX4
#
# @author Sander Smeets <[email protected]>
#
# Code partly based on DroneKit (c) Copyright 2015-2016, 3D Robotics.
################################################################################################
# Import DroneKit-Python
from dronekit import connect, Command, LocationGlobal
from pymavlink import mavutil
import time, sys, argparse, math
################################################################################################
# Settings
################################################################################################
connection_string = '127.0.0.1:14540'
MAV_MODE_AUTO = 4
# https://github.com/PX4/Firmware/blob/master/Tools/mavlink_px4.py
# Parse connection argument
parser = argparse.ArgumentParser()
parser.add_argument("-c", "--connect", help="connection string")
args = parser.parse_args()
if args.connect:
connection_string = args.connect
################################################################################################
# Init
################################################################################################
# Connect to the Vehicle
print "Connecting"
vehicle = connect(connection_string, wait_ready=True)
def PX4setMode(mavMode):
vehicle._master.mav.command_long_send(vehicle._master.target_system, vehicle._master.target_component,
mavutil.mavlink.MAV_CMD_DO_SET_MODE, 0,
mavMode,
0, 0, 0, 0, 0, 0)
def get_location_offset_meters(original_location, dNorth, dEast, alt):
"""
Returns a LocationGlobal object containing the latitude/longitude `dNorth` and `dEast` metres from the
specified `original_location`. The returned Location adds the entered `alt` value to the altitude of the `original_location`.
The function is useful when you want to move the vehicle around specifying locations relative to
the current vehicle position.
The algorithm is relatively accurate over small distances (10m within 1km) except close to the poles.
For more information see:
http://gis.stackexchange.com/questions/2951/algorithm-for-offsetting-a-latitude-longitude-by-some-amount-of-meters
"""
earth_radius=6378137.0 #Radius of "spherical" earth
#Coordinate offsets in radians
dLat = dNorth/earth_radius
dLon = dEast/(earth_radius*math.cos(math.pi*original_location.lat/180))
#New position in decimal degrees
newlat = original_location.lat + (dLat * 180/math.pi)
newlon = original_location.lon + (dLon * 180/math.pi)
return LocationGlobal(newlat, newlon,original_location.alt+alt)
################################################################################################
# Listeners
################################################################################################
home_position_set = False
#Create a message listener for home position fix
@vehicle.on_message('HOME_POSITION')
def listener(self, name, home_position):
global home_position_set
home_position_set = True
################################################################################################
# Start mission example
################################################################################################
# wait for a home position lock
while not home_position_set:
print "Waiting for home position..."
time.sleep(1)
# Display basic vehicle state
print " Type: %s" % vehicle._vehicle_type
print " Armed: %s" % vehicle.armed
print " System status: %s" % vehicle.system_status.state
print " GPS: %s" % vehicle.gps_0
print " Alt: %s" % vehicle.location.global_relative_frame.alt
# Change to AUTO mode
PX4setMode(MAV_MODE_AUTO)
time.sleep(1)
# Load commands
cmds = vehicle.commands
cmds.clear()
home = vehicle.location.global_relative_frame
# takeoff to 10 meters
wp = get_location_offset_meters(home, 0, 0, 10);
cmd = Command(0,0,0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 1, 0, 0, 0, 0, wp.lat, wp.lon, wp.alt)
cmds.add(cmd)
# move 10 meters north
wp = get_location_offset_meters(wp, 10, 0, 0);
cmd = Command(0,0,0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 1, 0, 0, 0, 0, wp.lat, wp.lon, wp.alt)
cmds.add(cmd)
# move 10 meters east
wp = get_location_offset_meters(wp, 0, 10, 0);
cmd = Command(0,0,0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 1, 0, 0, 0, 0, wp.lat, wp.lon, wp.alt)
cmds.add(cmd)
# move 10 meters south
wp = get_location_offset_meters(wp, -10, 0, 0);
cmd = Command(0,0,0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 1, 0, 0, 0, 0, wp.lat, wp.lon, wp.alt)
cmds.add(cmd)
# move 10 meters west
wp = get_location_offset_meters(wp, 0, -10, 0);
cmd = Command(0,0,0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 1, 0, 0, 0, 0, wp.lat, wp.lon, wp.alt)
cmds.add(cmd)
# land
wp = get_location_offset_meters(home, 0, 0, 10);
cmd = Command(0,0,0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_LAND, 0, 1, 0, 0, 0, 0, wp.lat, wp.lon, wp.alt)
cmds.add(cmd)
# Upload mission
cmds.upload()
time.sleep(2)
# Arm vehicle
vehicle.armed = True
# monitor mission execution
nextwaypoint = vehicle.commands.next
while nextwaypoint < len(vehicle.commands):
if vehicle.commands.next > nextwaypoint:
display_seq = vehicle.commands.next+1
print "Moving to waypoint %s" % display_seq
nextwaypoint = vehicle.commands.next
time.sleep(1)
# wait for the vehicle to land
while vehicle.commands.next > 0:
time.sleep(1)
# Disarm vehicle
vehicle.armed = False
time.sleep(1)
# Close vehicle object before exiting script
vehicle.close()
time.sleep(1)