🚀
PX4 - MAVSDK Python 프로그래밍
  • MAVSDK 개요
  • 프로그래밍 전제 조건
  • MAVSDK Python 개발 환경 설정
  • MAVSDK 라이브러리 클래스
  • Python "asyncio" 이해
  • MAVSDK-Python 샘플 프로그램 분석
  • OFFBOARD 모드 이해하기
  • OFFBOARD 위치 제어 (NED 기준)
  • OFFBOARD 속도 제어 (BODY 기준)
  • OFFBOARD 속도 제어 (NED 기준)
  • OFFBOARD 위치, 속도 제어 (NED 기준)
  • Keyboard 입력을 이용한 기체 이동
  • 문제 해결
  • MAVSDK Server
  • 교육 안내
Powered by GitBook
On this page
  • offboard_position_ned.py 코드 분석
  • 전체 코드
  • 실행

OFFBOARD 위치 제어 (NED 기준)

저작권: 쿼드(QUAD) 드론연구소 https://smartstore.naver.com/maponarooo

이번 세션에서는 Offboard 모드에서 Local_Position_NED를 이용한 위치제어 방법에 대해 다룹니다.

offboard_position_ned.py 코드 분석

EKF Origin 초기화

    print("-- EKF origin 초기화")
    await drone.offboard.set_position_ned(PositionNedYaw(0.0, 0.0, 0.0, 0.0))

    print("-- Starting offboard")
    try:
        await drone.offboard.start()
    except OffboardError as error:
        print(f"Starting offboard mode failed \
                with error code: {error._result.result}")
        print("-- Disarming")
        await drone.action.disarm()
        return

여기서 주의할 점은 Offboard 모드를 시작하기 전에 EKF Origin을 0,0,0 으로 초기화 해야 한다는 것 입니다.

에러가 발생되면 아밍을 종료 합니다.

Takeoff

    print("-- Go 0m North, 0m East, -5m Down \
            within local coordinate system")
    await drone.offboard.set_position_ned(
            PositionNedYaw(0.0, 0.0, -5.0, 0.0))
    await asyncio.sleep(10)

Local coordinate 프레임을 기준으로 기체를 위로 이동 시킵니다. 고도는 NED 기준에서 항상 - 가 위쪽임을 주의 하십시오.

이륙 고도에 다다를 충분한 sleep(10) 타임을 주어야 합니다.

이동

    print("-- Go 5m North, 10m East, -5m Down \
            within local coordinate system")
    await drone.offboard.set_position_ned(
            PositionNedYaw(5.0, 10.0, -5.0, 90.0))
    await asyncio.sleep(15)

NED 기준으로 북쪽으로 5m, 동쪽으로 10m, 고도 5m, 기수 방향 90도로 기체를 이동 시킵니다.

착륙

    print("-- Go 0m North, 10m East, 0m Down \
            within local coordinate system, turn to face South")
    await drone.offboard.set_position_ned(
            PositionNedYaw(0.0, 10.0, 0.0, 180.0))
    await asyncio.sleep(10)

고도를 0으로 주어 기체를 착륙 시킵니다.

PX4는 기체가 지면에 닿으면 자동으로 아밍을 종료 합니다.

Offboard 모드 종료

    print("-- Stopping offboard")
    try:
        await drone.offboard.stop()
    except OffboardError as error:
        print(f"Stopping offboard mode failed \
                with error code: {error._result.result}")

전체 코드

offboard_position_ned.py

#!/usr/bin/env python3

"""
Caveat when attempting to run the examples in non-gps environments:

`drone.offboard.stop()` will return a `COMMAND_DENIED` result because it
requires a mode switch to HOLD, something that is currently not supported in a
non-gps environment.
"""

import asyncio

from mavsdk import System
from mavsdk.offboard import (OffboardError, PositionNedYaw)


async def run():
    """ Does Offboard control using position NED coordinates. """

    drone = System()
    await drone.connect(system_address="udp://:14540")

    print("Waiting for drone to connect...")
    async for state in drone.core.connection_state():
        if state.is_connected:
            print(f"-- Connected to drone!")
            break

    print("Waiting for drone to have a global position estimate...")
    async for health in drone.telemetry.health():
        if health.is_global_position_ok and health.is_home_position_ok:
            print("-- Global position estimate OK")
            break

    print("-- Arming")
    await drone.action.arm()

    print("-- Setting initial setpoint")
    await drone.offboard.set_position_ned(PositionNedYaw(0.0, 0.0, 0.0, 0.0))

    print("-- Starting offboard")
    try:
        await drone.offboard.start()
    except OffboardError as error:
        print(f"Starting offboard mode failed \
                with error code: {error._result.result}")
        print("-- Disarming")
        await drone.action.disarm()
        return

    print("-- Go 0m North, 0m East, -5m Down \
            within local coordinate system")
    await drone.offboard.set_position_ned(
            PositionNedYaw(0.0, 0.0, -5.0, 0.0))
    await asyncio.sleep(10)

    print("-- Go 5m North, 0m East, -5m Down \
            within local coordinate system, turn to face East")
    await drone.offboard.set_position_ned(
            PositionNedYaw(5.0, 0.0, -5.0, 90.0))
    await asyncio.sleep(10)

    print("-- Go 5m North, 10m East, -5m Down \
            within local coordinate system")
    await drone.offboard.set_position_ned(
            PositionNedYaw(5.0, 10.0, -5.0, 90.0))
    await asyncio.sleep(15)

    print("-- Go 0m North, 10m East, 0m Down \
            within local coordinate system, turn to face South")
    await drone.offboard.set_position_ned(
            PositionNedYaw(0.0, 10.0, 0.0, 180.0))
    await asyncio.sleep(10)

    print("-- Stopping offboard")
    try:
        await drone.offboard.stop()
    except OffboardError as error:
        print(f"Stopping offboard mode failed \
                with error code: {error._result.result}")


if __name__ == "__main__":
    # Run the asyncio loop
    asyncio.run(run())

실행

드론의 움직임을 정밀히 관찰해 보시면 문제점을 파악할 수 있을 것입니다.

PreviousOFFBOARD 모드 이해하기NextOFFBOARD 속도 제어 (BODY 기준)

Last updated 1 year ago