!REDIRECT “https://docs.px4.io/master/ja/robotics/dronekit.html

Using DroneKit to communicate with PX4

DroneKit helps you create powerful apps for UAVs. These apps run on a UAV’s Companion Computer, and augment the autopilot by performing tasks that are both computationally intensive and require a low-latency link (e.g. computer vision).

DroneKit and PX4 are currently working on getting full compatibility. As of DroneKit-python 2.2.0 there is basic support for mission handling and vehicle monitoring.

Setting up DroneKit with PX4

Start by installing DroneKit-python from the current master.

  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

Create a new python file and import DroneKit, pymavlink and basic modules

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

Connect to a MAVLink port of your drone or simulation (e.g. JMavSim).

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

Display some basic status information

  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

Full mission example

The following python script shows a full mission example using DroneKit and PX4. Mode switching is not yet fully supported from DroneKit, we therefor send our own custom mode switching commands.

  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/PX4-Autopilot/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 adds the entered `alt` value to the altitude of the `original_location`.
  40. The function is useful when you want to move the vehicle around specifying locations relative to
  41. the current vehicle position.
  42. The algorithm is relatively accurate over small distances (10m within 1km) except close to the poles.
  43. For more information see:
  44. http://gis.stackexchange.com/questions/2951/algorithm-for-offsetting-a-latitude-longitude-by-some-amount-of-meters
  45. """
  46. earth_radius=6378137.0 #Radius of "spherical" earth
  47. #Coordinate offsets in radians
  48. dLat = dNorth/earth_radius
  49. dLon = dEast/(earth_radius*math.cos(math.pi*original_location.lat/180))
  50. #New position in decimal degrees
  51. newlat = original_location.lat + (dLat * 180/math.pi)
  52. newlon = original_location.lon + (dLon * 180/math.pi)
  53. return LocationGlobal(newlat, newlon,original_location.alt+alt)
  54. ################################################################################################
  55. # Listeners
  56. ################################################################################################
  57. home_position_set = False
  58. #Create a message listener for home position fix
  59. @vehicle.on_message('HOME_POSITION')
  60. def listener(self, name, home_position):
  61. global home_position_set
  62. home_position_set = True
  63. ################################################################################################
  64. # Start mission example
  65. ################################################################################################
  66. # wait for a home position lock
  67. while not home_position_set:
  68. print "Waiting for home position..."
  69. time.sleep(1)
  70. # Display basic vehicle state
  71. print " Type: %s" % vehicle._vehicle_type
  72. print " Armed: %s" % vehicle.armed
  73. print " System status: %s" % vehicle.system_status.state
  74. print " GPS: %s" % vehicle.gps_0
  75. print " Alt: %s" % vehicle.location.global_relative_frame.alt
  76. # Change to AUTO mode
  77. PX4setMode(MAV_MODE_AUTO)
  78. time.sleep(1)
  79. # Load commands
  80. cmds = vehicle.commands
  81. cmds.clear()
  82. home = vehicle.location.global_relative_frame
  83. # takeoff to 10 meters
  84. wp = get_location_offset_meters(home, 0, 0, 10);
  85. 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)
  86. cmds.add(cmd)
  87. # move 10 meters north
  88. wp = get_location_offset_meters(wp, 10, 0, 0);
  89. 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)
  90. cmds.add(cmd)
  91. # move 10 meters east
  92. wp = get_location_offset_meters(wp, 0, 10, 0);
  93. 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)
  94. cmds.add(cmd)
  95. # move 10 meters south
  96. wp = get_location_offset_meters(wp, -10, 0, 0);
  97. 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)
  98. cmds.add(cmd)
  99. # move 10 meters west
  100. wp = get_location_offset_meters(wp, 0, -10, 0);
  101. 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)
  102. cmds.add(cmd)
  103. # land
  104. wp = get_location_offset_meters(home, 0, 0, 10);
  105. 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)
  106. cmds.add(cmd)
  107. # Upload mission
  108. cmds.upload()
  109. time.sleep(2)
  110. # Arm vehicle
  111. vehicle.armed = True
  112. # monitor mission execution
  113. nextwaypoint = vehicle.commands.next
  114. while nextwaypoint < len(vehicle.commands):
  115. if vehicle.commands.next > nextwaypoint:
  116. display_seq = vehicle.commands.next+1
  117. print "Moving to waypoint %s" % display_seq
  118. nextwaypoint = vehicle.commands.next
  119. time.sleep(1)
  120. # wait for the vehicle to land
  121. while vehicle.commands.next > 0:
  122. time.sleep(1)
  123. # Disarm vehicle
  124. vehicle.armed = False
  125. time.sleep(1)
  126. # Close vehicle object before exiting script
  127. vehicle.close()
  128. time.sleep(1)