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

DroneKit로 PX4와 통신하기

DroneKit는 무인 항공기용 프로그램에 강력한 기능을 갖추도록 도와줍니다. 이 프로그램은 UAV의 보조 컴퓨터에서 실행하며, 처리 집약적 저지연 연결이 필요한 작업을 수행하여 오토파일럿의 능력(또는 기능, 예: 컴퓨터 비전)을 확장합니다.

DroneKit과 PX4는 현재 완전한 호환성을 갖추는 중입니다. DroneKit-python 2.2.0에서는 임무 처리와 기체 감시등 기본 기능을 지원합니다.

DroneKit와 PX4 설치

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

새 파이썬 파일을 만들어 DroneKit, pymavlink, 기본 모듈을 끌어(import)오십시오.

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

드론 또는 모의시험 환경(예: jMAVSim)의 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

전체 임무 예제

다음 파이썬 스크립트에서는 DroneKit와 PX4를 활용한 전체 임무 예제를 보여줍니다. DroneKit에서 상태 전환은 완전히 지원하지 않기에, 개별 상태 전환 명령을 따로 보냅니다.

  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)