659.93 드론 시스템의 프레임 체계 (ENU, NED)

1. 개요

드론(무인 항공기, UAV) 시스템에서는 지상 로봇과 달리 항공 분야의 좌표계 규약과 ROS2의 좌표계 규약이 공존한다. 항공 분야에서는 전통적으로 NED(North-East-Down) 좌표계를 사용하는 반면, ROS2에서는 REP 103에 따라 ENU(East-North-Up) 좌표계를 사용한다. 이 두 좌표계 규약 사이의 변환을 정확히 이해하고 구현하는 것은 드론 소프트웨어의 정확성과 안전성에 필수적이다.

2. NED 좌표계

2.1 정의

NED(North-East-Down)는 항공 및 항법 분야의 표준 좌표계이다.

방향설명
X축북쪽 (North)지리적 북쪽 방향
Y축동쪽 (East)지리적 동쪽 방향
Z축하방 (Down)중력 방향

NED 좌표계에서 양의 고도는 하방을 가리키므로, 드론이 상승하면 Z 좌표가 감소한다.

2.2 NED 사용 시스템

시스템프로토콜/규약NED 사용 여부
PX4 비행 제어기MAVLinkNED
ArduPilot 비행 제어기MAVLinkNED
MAVROS (ROS1/ROS2 MAVLink 인터페이스)NED/ENU 변환 포함내부 NED, 외부 ENU
NATO STANAG 4586NEDNED

2.3 물체 고정 좌표계 (NED-FRD)

NED 좌표계에서의 물체 고정(body-fixed) 좌표계는 FRD(Forward-Right-Down) 규약을 사용한다.

방향설명
X축전방 (Forward)드론의 기수(nose) 방향
Y축우측 (Right)드론의 우측 날개 방향
Z축하방 (Down)드론의 하부 방향

3. ENU 좌표계

3.1 정의

ENU(East-North-Up)는 ROS2(REP 103)의 표준 글로벌 좌표계이다.

방향설명
X축동쪽 (East)지리적 동쪽 방향
Y축북쪽 (North)지리적 북쪽 방향
Z축상방 (Up)중력 반대 방향

ENU 좌표계에서 양의 고도는 상방을 가리키므로, 드론이 상승하면 Z 좌표가 증가한다.

3.2 물체 고정 좌표계 (ENU-FLU)

ENU 좌표계에서의 물체 고정 좌표계는 FLU(Forward-Left-Up) 규약을 사용한다.

방향설명
X축전방 (Forward)드론의 기수 방향
Y축좌측 (Left)드론의 좌측 날개 방향
Z축상방 (Up)드론의 상부 방향

4. NED와 ENU 사이의 변환

4.1 글로벌 프레임 변환 (NED ↔ ENU)

NED와 ENU 사이의 좌표 변환은 다음과 같다.

$$
\begin{bmatrix} x_{\text{ENU}} \ y_{\text{ENU}} \ z_{\text{ENU}} \end

\begin{bmatrix} 0 & 1 & 0 \ 1 & 0 & 0 \ 0 & 0 & -1 \end{bmatrix}
\begin{bmatrix} x_{\text{NED}} \ y_{\text{NED}} \ z_{\text{NED}} \end{bmatrix}
$$

즉:

  • x_{\text{ENU}} = y_{\text{NED}} (동쪽 = 동쪽)
  • y_{\text{ENU}} = x_{\text{NED}} (북쪽 = 북쪽)
  • z_{\text{ENU}} = -z_{\text{NED}} (상방 = -하방)

4.2 물체 고정 프레임 변환 (FRD ↔ FLU)

$$
\begin{bmatrix} x_{\text{FLU}} \ y_{\text{FLU}} \ z_{\text{FLU}} \end

\begin{bmatrix} 1 & 0 & 0 \ 0 & -1 & 0 \ 0 & 0 & -1 \end{bmatrix}
\begin{bmatrix} x_{\text{FRD}} \ y_{\text{FRD}} \ z_{\text{FRD}} \end{bmatrix}
$$

즉:

  • x_{\text{FLU}} = x_{\text{FRD}} (전방 = 전방)
  • y_{\text{FLU}} = -y_{\text{FRD}} (좌측 = -우측)
  • z_{\text{FLU}} = -z_{\text{FRD}} (상방 = -하방)

4.3 오일러 각 변환

오일러 각(Roll, Pitch, Yaw)의 변환은 다음과 같다.

각도NED → ENU 변환
Roll (\phi)\phi_{\text{ENU}} = \phi_{\text{NED}}
Pitch (\theta)\theta_{\text{ENU}} = -\theta_{\text{NED}}
Yaw (\psi)\psi_{\text{ENU}} = \frac{\pi}{2} - \psi_{\text{NED}}

NED에서 Yaw는 북쪽(0°)에서 시작하여 시계 방향으로 증가하는 반면, ENU에서 Yaw는 동쪽(0°)에서 시작하여 반시계 방향으로 증가한다.

5. ROS2 드론 시스템의 프레임 구조

5.1 전형적인 프레임 트리

earth (ENU)
  └── map (ENU)
        └── odom (ENU)
              └── base_link (FLU)
                    ├── camera_link
                    │     └── camera_optical_frame
                    ├── imu_link
                    ├── gps_link
                    ├── lidar_link
                    ├── rotor_0_link
                    ├── rotor_1_link
                    ├── rotor_2_link
                    └── rotor_3_link

모든 프레임은 ENU/FLU 규약을 따르며, NED/FRD 좌표계를 사용하는 비행 제어기와의 통신 시에만 좌표 변환이 수행된다.

5.2 PX4/ArduPilot과의 인터페이스

MAVROS 또는 px4_ros_com 패키지가 NED/FRD ↔ ENU/FLU 변환을 자동으로 수행한다.

PX4 (NED/FRD) ←→ MAVROS/px4_ros_com ←→ ROS2 (ENU/FLU)

MAVROS에서의 설정:

mavros_node:
  ros__parameters:
    # MAVROS는 내부적으로 NED ↔ ENU 변환을 수행
    local_position:
      frame_id: "odom"
      tf:
        send: true
        frame_id: "odom"
        child_frame_id: "base_link"

6. 고도 규약의 차이

6.1 NED에서의 고도

NED 좌표계에서 고도는 음수로 증가한다. 지면 위 100m의 고도는 z = -100으로 표현된다.

6.2 ENU에서의 고도

ENU 좌표계에서 고도는 양수로 증가한다. 지면 위 100m의 고도는 z = +100으로 표현된다.

6.3 고도 관련 오류 방지

# NED 고도를 ENU 고도로 변환
def ned_altitude_to_enu(z_ned):
    return -z_ned

# 예: NED에서 -50.0 (지상 50m) → ENU에서 50.0
enu_altitude = ned_altitude_to_enu(-50.0)  # 50.0

7. 스러스트 방향

7.1 NED-FRD 규약

NED-FRD 규약에서 양의 스러스트 방향은 Z축 음의 방향(상방)이다. 이는 드론이 상승하기 위하여 음의 Z 방향으로 힘을 가하기 때문이다.

7.2 ENU-FLU 규약

ENU-FLU 규약에서 양의 스러스트 방향은 Z축 양의 방향(상방)이다. 이는 ROS2의 직관적 규약과 일치한다.

8. 주의 사항

8.1 좌표계 혼동 방지

NED와 ENU 좌표계의 혼동은 치명적인 사고를 초래할 수 있다. 특히 고도 부호의 혼동은 드론이 상승하여야 할 때 하강하는 결과를 야기할 수 있다. 소프트웨어 설계 시 좌표계 경계(coordinate system boundary)를 명확히 정의하고, 변환 함수를 검증하여야 한다.

8.2 단위의 일관성

항공 분야에서는 피트(ft), 노트(knot) 등의 비SI 단위가 사용되기도 하나, ROS2에서는 REP 103에 따라 SI 단위(m, m/s, rad, rad/s)를 사용하여야 한다.

8.3 자기 편차 보정

ENU와 NED 좌표계 모두에서 자기 북(magnetic north)과 진북(true north)의 차이인 자기 편차(magnetic declination)를 보정하여야 한다. 이 보정은 navsat_transform_nodemagnetic_declination_radians 매개변수를 통하여 설정할 수 있다.

9. 요약

드론 시스템에서는 항공 분야의 NED(North-East-Down)/FRD(Forward-Right-Down) 좌표계와 ROS2의 ENU(East-North-Up)/FLU(Forward-Left-Up) 좌표계가 공존한다. ROS2의 TF2 변환 트리는 ENU/FLU 규약을 따르며, 비행 제어기(PX4, ArduPilot)와의 인터페이스에서 MAVROS 등의 미들웨어가 자동으로 좌표 변환을 수행한다. 고도 부호의 차이와 Yaw 각 기준의 차이에 특히 주의하여야 하며, 모든 변환은 검증된 변환 함수를 통하여 수행하여야 한다.


참고 문헌 및 출처

  • T. Foote, “REP 103 – Standard Units of Measure and Coordinate Conventions,” ROS Enhancement Proposals, https://www.ros.org/reps/rep-0103.html (2010, 최종 갱신 2023)
  • L. Meier et al., “PX4: A Node-Based Multithreaded Open Source Robotics Framework for Deeply Embedded Platforms,” IEEE International Conference on Robotics and Automation (ICRA), 2015.
  • MAVROS 공식 문서, https://github.com/mavlink/mavros (ROS2 브랜치)
  • MAVLink 프로토콜 문서, https://mavlink.io/en/ (MAVLink v2.0)