translated_page: https://github.com/PX4/Devguide/blob/master/en/dronekit/example.md

translated_sha: 95b39d747851dd01c1fe5d36b24e59ec865e323e

Using DroneKit to communicate with PX4

DroneKit 可以帮助创建强大的无人机应用。这些应用运行在无人机的协同计算机上,通过执行计算密集但又需要低延迟的任务(计算机视觉)来增强飞控计算机。

DroneKit和PX4目前致力于获得完全兼容。截止DroneKit-python 2.2.0,仅提供任务处理和状态监控这样的基本支持。

配置DroneKit

首先,从当前主分支安装DroneKit-python

  1. git clone https://github.com/dronekit/dronekit-python.git
  2. cd ./dronekit-python
  3. sudo python setup.py build
  4. sudo python setup.py install

创建一个新的python文件并导入DroneKit, pymavlink和基本模块

  1. # Import DroneKit-Python
  2. from dronekit import connect, Command, LocationGlobal
  3. from pymavlink import mavutil
  4. import time, sys, argparse, math

连接到无人机或模拟器的MAVLink端口

  1. # Connect to the Vehicle
  2. print "Connecting"
  3. connection_string = '127.0.0.1:14540'
  4. vehicle = connect(connection_string, wait_ready=True)

显示一些基本的状态信息

  1. # Display basic vehicle state
  2. print " Type: %s" % vehicle._vehicle_type
  3. print " Armed: %s" % vehicle.armed
  4. print " System status: %s" % vehicle.system_status.state
  5. print " GPS: %s" % vehicle.gps_0
  6. print " Alt: %s" % vehicle.location.global_relative_frame.alt

完整的任务示例

下面的python脚本文件给出了使用DroneKit和PX4的完整任务范例。目前还不完全支持模式切换,因此我们发送自定义的模式切换指令。

  1. ################################################################################################
  2. # @File DroneKitPX4.py
  3. # Example usage of DroneKit with PX4
  4. #
  5. # @author Sander Smeets <sander@droneslab.com>
  6. #
  7. # Code partly based on DroneKit (c) Copyright 2015-2016, 3D Robotics.
  8. ################################################################################################
  9. # Import DroneKit-Python
  10. from dronekit import connect, Command, LocationGlobal
  11. from pymavlink import mavutil
  12. import time, sys, argparse, math
  13. ################################################################################################
  14. # Settings
  15. ################################################################################################
  16. connection_string = '127.0.0.1:14540'
  17. MAV_MODE_AUTO = 4
  18. # https://github.com/PX4/Firmware/blob/master/Tools/mavlink_px4.py
  19. # Parse connection argument
  20. parser = argparse.ArgumentParser()
  21. parser.add_argument("-c", "--connect", help="connection string")
  22. args = parser.parse_args()
  23. if args.connect:
  24. connection_string = args.connect
  25. ################################################################################################
  26. # Init
  27. ################################################################################################
  28. # Connect to the Vehicle
  29. print "Connecting"
  30. vehicle = connect(connection_string, wait_ready=True)
  31. def PX4setMode(mavMode):
  32. vehicle._master.mav.command_long_send(vehicle._master.target_system, vehicle._master.target_component,
  33. mavutil.mavlink.MAV_CMD_DO_SET_MODE, 0,
  34. mavMode,
  35. 0, 0, 0, 0, 0, 0)
  36. def get_location_offset_meters(original_location, dNorth, dEast, alt):
  37. """
  38. Returns a LocationGlobal object containing the latitude/longitude `dNorth` and `dEast` metres from the
  39. specified `original_location`. The returned Location has the same `alt` value
  40. as `original_location`.
  41. The function is useful when you want to move the vehicle around specifying locations relative to
  42. the current vehicle position.
  43. The algorithm is relatively accurate over small distances (10m within 1km) except close to the poles.
  44. For more information see:
  45. http://gis.stackexchange.com/questions/2951/algorithm-for-offsetting-a-latitude-longitude-by-some-amount-of-meters
  46. """
  47. earth_radius=6378137.0 #Radius of "spherical" earth
  48. #Coordinate offsets in radians
  49. dLat = dNorth/earth_radius
  50. dLon = dEast/(earth_radius*math.cos(math.pi*original_location.lat/180))
  51. #New position in decimal degrees
  52. newlat = original_location.lat + (dLat * 180/math.pi)
  53. newlon = original_location.lon + (dLon * 180/math.pi)
  54. return LocationGlobal(newlat, newlon,original_location.alt+alt)
  55. ################################################################################################
  56. # Listeners
  57. ################################################################################################
  58. home_position_set = False
  59. #Create a message listener for home position fix
  60. @vehicle.on_message('HOME_POSITION')
  61. def listener(self, name, home_position):
  62. global home_position_set
  63. home_position_set = True
  64. ################################################################################################
  65. # Start mission example
  66. ################################################################################################
  67. # wait for a home position lock
  68. while not home_position_set:
  69. print "Waiting for home position..."
  70. time.sleep(1)
  71. # Display basic vehicle state
  72. print " Type: %s" % vehicle._vehicle_type
  73. print " Armed: %s" % vehicle.armed
  74. print " System status: %s" % vehicle.system_status.state
  75. print " GPS: %s" % vehicle.gps_0
  76. print " Alt: %s" % vehicle.location.global_relative_frame.alt
  77. # Change to AUTO mode
  78. PX4setMode(MAV_MODE_AUTO)
  79. time.sleep(1)
  80. # Load commands
  81. cmds = vehicle.commands
  82. cmds.clear()
  83. home = vehicle.location.global_relative_frame
  84. # takeoff to 10 meters
  85. wp = get_location_offset_meters(home, 0, 0, 10);
  86. 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)
  87. cmds.add(cmd)
  88. # move 10 meters north
  89. wp = get_location_offset_meters(wp, 10, 0, 0);
  90. 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)
  91. cmds.add(cmd)
  92. # move 10 meters east
  93. wp = get_location_offset_meters(wp, 0, 10, 0);
  94. 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)
  95. cmds.add(cmd)
  96. # move 10 meters south
  97. wp = get_location_offset_meters(wp, -10, 0, 0);
  98. 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)
  99. cmds.add(cmd)
  100. # move 10 meters west
  101. wp = get_location_offset_meters(wp, 0, -10, 0);
  102. 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)
  103. cmds.add(cmd)
  104. # land
  105. wp = get_location_offset_meters(home, 0, 0, 10);
  106. 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)
  107. cmds.add(cmd)
  108. # Upload mission
  109. cmds.upload()
  110. time.sleep(2)
  111. # Arm vehicle
  112. vehicle.armed = True
  113. # monitor mission execution
  114. nextwaypoint = vehicle.commands.next
  115. while nextwaypoint < len(vehicle.commands):
  116. if vehicle.commands.next > nextwaypoint:
  117. display_seq = vehicle.commands.next+1
  118. print "Moving to waypoint %s" % display_seq
  119. nextwaypoint = vehicle.commands.next
  120. time.sleep(1)
  121. # wait for the vehicle to land
  122. while vehicle.commands.next > 0:
  123. time.sleep(1)
  124. # Disarm vehicle
  125. vehicle.armed = False
  126. time.sleep(1)
  127. # Close vehicle object before exiting script
  128. vehicle.close()
  129. time.sleep(1)