# 오프보드 제어

WARNING

오프보드 제어는 위험합니다. 오프보드 비행전에 적절한 준비, 테스트 및 안전 예방 조치를 취하여야 합니다.

오프보드 제어의 아이디어는 자동조종장치 외부에서 실행되는 소프트웨어를 사용하여 PX4를 제어하는 것입니다. 이것은 MAVLink 프로토콜, 특히 SET_POSITION_TARGET_LOCAL_NED (opens new window)SET_ATTITUDE_TARGET (opens new window) 메시지를 통하여 수행됩니다.

# 오프보드 제어 펌웨어 설정

오프보드 개발전에 펌웨어에서 두 가지를 설정하여야 합니다.

# RC 스위치를 오프보드 모드 활성화에 매핑

QGroundControl에서 매개변수를 로드하고, 오프보드 모드를 활성화 RC 채널을 할당할 수 있는 RC_MAP_OFFB_SW 매개변수를 검색합니다. 오프보드 모드에서 벗어날 때 위치 제어로 이동하는 방식으로 매핑하는 것이 유용할 수 있습니다.

MAVLink 메시지로 오프보드 모드를 활성화할 수 있으므로, 이 단계는 필수는 아닙니다. 이 방법이 훨씬 더 안전합니다.

# 보조 컴퓨터 인터페이스 활성화

Enable MAVLink on the serial port that you connect to the companion computer (see Companion Computers).

# 하드웨어 설정

일반적으로 오프보드 통신을 설정하는 방법에는 세 가지가 있습니다.

# 직렬 라디오

  1. 하나는 자동조종장치의 UART 포트에 연결합니다.

  2. One connected to a ground station computer

    Example radios include:

Mermaid graph: mavlink channel (opens new window)

# 온보드 프로세서

A small computer mounted onto the vehicle, connected to the autopilot through a serial port or Ehthernet port. There are many possibilities here and it will depend on what kind of additional on-board processing you want to do in addition to sending commands to the autopilot. Some examples are provided in Companion Computers.

Mermaid diagram: Companion mavlink (opens new window)

# 온보드 프로세서 및 ROS에 대한 Wi-Fi 링크(권장)

A small computer mounted onto the vehicle connected to the autopilot through a UART to USB adapter while also having a WiFi link to a ground station running ROS. This can be any of the computers from the above section coupled with a WiFi adapter.

Mermaid graph: ROS (opens new window)