- 使用DroneKit与PX4通讯
- 配置DroneKit
- 完整的任务示例
使用DroneKit与PX4通讯
官网英文原文地址:http://dev.px4.io/dronekit-example.html
DroneKit可以帮助创建强大的无人机应用。这些应用运行在无人机的协同计算机上,通过执行计算密集但又需要低延迟的任务(计算机视觉)来增强飞控计算机。
DroneKit和PX4目前致力于获得完全兼容。截止DroneKit-python 2.2.0,仅提供任务处理和状态监控这样的基本支持。
配置DroneKit
首先,从当前主分支安装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 DroneKit-Python
from dronekit import connect, Command, LocationGlobal
from pymavlink import mavutil
import time, sys, argparse, math
连接到无人机或模拟器的MAVLink端口
# 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脚本文件给出了使用DroneKit和PX4的完整任务范例。目前还不完全支持模式切换,因此我们发送自定义的模式切换指令。
################################################################################################
# @File DroneKitPX4.py
# Example usage of DroneKit with PX4
#
# @author Sander Smeets <sander@droneslab.com>
#
# 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 has the same `alt` value
as `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_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)