659.92 GPS/GNSS 프레임의 정의
1. 개요
GPS/GNSS(Global Navigation Satellite System) 수신기는 위성 항법 신호를 수신하여 로봇의 절대 지리적 위치(위도, 경도, 고도)를 측정한다. GNSS 프레임은 수신기 안테나의 물리적 위치에 배치되며, 수신된 위치 데이터의 기준점을 정의한다. GNSS 데이터는 REP 105의 earth 프레임과 연동되어 절대 위치 기반의 내비게이션에 활용된다.
2. GNSS 프레임의 정의
2.1 프레임 위치
GNSS 프레임(gps_link 또는 gnss_link)은 GNSS 안테나의 위상 중심(phase center)에 위치한다. 위상 중심은 안테나가 위성 신호를 수신하는 전기적 기준점으로, 물리적 안테나의 기하학적 중심과 근사적으로 일치한다.
2.2 좌표축 방향
GNSS 프레임은 REP 103의 물체 고정 좌표계(FLU) 규약을 따른다.
| 축 | 방향 |
|---|---|
| X축 | 전방 (Forward) |
| Y축 | 좌측 (Left) |
| Z축 | 상방 (Up) |
그러나 GNSS 수신기 자체는 방향 정보를 측정하지 않으므로(단일 안테나 기준), 프레임의 방향은 장착 방향에 의하여 결정된다.
3. GNSS 데이터의 좌표 체계
3.1 GNSS 출력 좌표
GNSS 수신기가 출력하는 원시 좌표는 WGS84 타원체 기반의 지리적 좌표이다.
| 좌표 성분 | 설명 | 단위 |
|---|---|---|
| 위도 (\phi) | 적도면으로부터의 각도 | 도(°) 또는 라디안(rad) |
| 경도 (\lambda) | 본초 자오선으로부터의 각도 | 도(°) 또는 라디안(rad) |
| 고도 (h) | WGS84 타원체면으로부터의 높이 | 미터(m) |
3.2 ROS2 메시지 형식
GNSS 데이터는 sensor_msgs/msg/NavSatFix 메시지로 발행된다.
std_msgs/Header header
builtin_interfaces/Time stamp
string frame_id # GNSS 프레임 이름
sensor_msgs/NavSatStatus status
int8 status # 수신 상태 (-1: 미수신, 0: 단독, 1: SBAS, 2: GBAS)
uint16 service # 사용 위성 시스템
float64 latitude # 위도 (도)
float64 longitude # 경도 (도)
float64 altitude # 고도 (m, WGS84 타원체 기준)
float64[9] position_covariance # 위치 공분산 (ENU, 3x3, row-major)
uint8 position_covariance_type # 공분산 유형 (0: 미지, 1: 근사, 2: 대각, 3: 알려진)
header.frame_id는 GNSS 안테나 프레임의 이름(예: gps_link)이어야 한다.
4. URDF에서의 GNSS 프레임 정의
<!-- GPS 안테나 링크 -->
<link name="gps_link">
<visual>
<geometry>
<cylinder radius="0.03" length="0.02"/>
</geometry>
<material name="white">
<color rgba="0.9 0.9 0.9 1.0"/>
</material>
</visual>
</link>
<!-- base_link에 고정 -->
<joint name="gps_joint" type="fixed">
<parent link="base_link"/>
<child link="gps_link"/>
<origin xyz="0.0 0.0 0.6" rpy="0 0 0"/>
<!-- 로봇 상부 0.6m (안테나 장착 위치) -->
</joint>
5. GNSS 데이터와 TF2의 통합
5.1 좌표 변환 경로
GNSS 데이터가 TF2 변환 트리에 통합되는 과정은 다음과 같다.
- GNSS 드라이버:
NavSatFix메시지를 발행한다. (frame_id: gps_link) - navsat_transform_node: WGS84 좌표를 로컬 ENU 좌표로 변환한다.
- EKF/UKF: GNSS 데이터와 다른 센서 데이터를 융합하여 위치를 추정한다.
- TF2 변환:
earth → map → odom → base_link체인이 유지된다.
5.2 GNSS 안테나 위치의 보정
GNSS 안테나는 일반적으로 base_link와 일치하지 않는 위치에 장착된다. robot_localization의 navsat_transform_node는 TF2를 통하여 gps_link에서 base_link로의 변환을 자동으로 조회하여 안테나 오프셋을 보정한다.
# navsat_transform_node 설정
navsat_transform_node:
ros__parameters:
frequency: 30.0
delay: 3.0
magnetic_declination_radians: 0.0
yaw_offset: 0.0
zero_altitude: true
broadcast_utm_transform: false
publish_filtered_gps: true
use_odometry_yaw: true
wait_for_datum: false
이 노드는 gps_link → base_link 변환을 TF2에서 조회하여, GNSS로 측정된 안테나 위치를 base_link 위치로 변환한다.
5.3 안테나 오프셋의 영향
GNSS 안테나가 base_link로부터 (d_x, d_y, d_z)만큼 떨어져 있는 경우, 로봇이 회전하면 안테나의 궤적은 base_link의 궤적과 다르다. 이 오프셋을 보정하지 않으면 위치 추정에 오차가 발생한다.
회전에 의한 안테나 위치 변화는 다음과 같다.
\mathbf{p}_{\text{antenna}}^{\text{odom}} = \mathbf{p}_{\text{base}}^{\text{odom}} + R(\psi) \cdot \mathbf{d}
여기서 \mathbf{d} = (d_x, d_y, d_z)^T는 base_link에서 gps_link까지의 벡터, R(\psi)는 로봇의 현재 Yaw 회전 행렬이다.
6. GNSS 드라이버 설정
6.1 nmea_navsat_driver
nmea_serial_driver_node:
ros__parameters:
port: "/dev/ttyUSB0"
baud: 115200
frame_id: "gps_link" # GNSS 프레임 이름
time_ref_source: "gps"
useRMC: false
6.2 ublox_gps
ublox_gps_node:
ros__parameters:
device: "/dev/ttyACM0"
frame_id: "gps_link"
uart1:
baudrate: 115200
publish:
all: true
nav:
rate: 5 # 5 Hz 갱신
7. 다중 GNSS 안테나 시스템
7.1 이중 안테나를 이용한 방향 추정
단일 GNSS 안테나는 위치만을 제공하나, 이중 안테나(dual antenna) 시스템은 두 안테나 사이의 기선(baseline) 벡터를 이용하여 절대 방향(heading)을 측정할 수 있다.
base_link
├── gps_main_link (주 안테나)
└── gps_aux_link (보조 안테나)
두 안테나의 위치 차이로부터 방향각을 다음과 같이 계산한다.
\psi = \text{atan2}(y_{\text{aux}} - y_{\text{main}}, x_{\text{aux}} - x_{\text{main}})
7.2 RTK-GPS
RTK(Real-Time Kinematic) GPS는 기지국(base station)의 보정 신호를 수신하여 센티미터 수준의 위치 정밀도를 달성한다. RTK 상태는 NavSatFix 메시지의 status 필드로 전달된다.
| status 값 | 의미 | 정밀도 |
|---|---|---|
| -1 | 위성 미수신 | - |
| 0 | 단독 측위 (GPS fix) | 2~5 m |
| 1 | SBAS 보정 (DGPS) | 0.5~2 m |
| 2 | RTK 고정 (Fix) | 1~2 cm |
8. 주의 사항
8.1 frame_id의 정확한 설정
GNSS 드라이버의 frame_id는 TF2 변환 트리에 등록된 프레임 이름과 정확히 일치하여야 한다. 불일치 시 navsat_transform_node가 안테나 오프셋을 보정할 수 없다.
8.2 고도 데이터의 처리
WGS84 고도와 해수면 고도(MSL, Mean Sea Level)는 지오이드 높이(geoid height)만큼의 차이가 있다.
h_{\text{MSL}} = h_{\text{WGS84}} - N
여기서 N은 지오이드 높이이다. 2D 내비게이션에서는 zero_altitude: true 설정을 통하여 고도를 0으로 고정할 수 있다.
8.3 수신 불량 환경에서의 처리
터널, 실내, 고층 빌딩 밀집 지역 등에서는 GNSS 신호가 차단되거나 멀티패스(multipath) 오류가 발생한다. 이러한 환경에서는 GNSS 데이터의 공분산을 증가시키거나 데이터를 일시적으로 배제하여 센서 융합의 안정성을 유지하여야 한다.
9. 요약
GPS/GNSS 프레임은 수신기 안테나의 위상 중심에 위치하며, REP 103의 FLU 규약을 따르는 좌표 프레임이다. GNSS 데이터는 sensor_msgs/msg/NavSatFix 메시지로 WGS84 좌표를 발행하며, robot_localization의 navsat_transform_node를 통하여 로컬 ENU 좌표로 변환되어 TF2 변환 트리에 통합된다. GNSS 안테나와 base_link 사이의 오프셋은 TF2 변환을 통하여 자동으로 보정되며, 이를 위하여 URDF에서 gps_link의 정확한 위치 정의가 필수적이다.
참고 문헌 및 출처
- T. Foote, “REP 105 – Coordinate Frames for Mobile Platforms,” ROS Enhancement Proposals, https://www.ros.org/reps/rep-0105.html (2010, 최종 갱신 2022)
sensor_msgs/msg/NavSatFixAPI 문서, https://docs.ros2.org/latest/api/sensor_msgs/msg/NavSatFix.html (ROS2 Humble Hawksbill)- T. Moore, D. Stouch, “A Generalized Extended Kalman Filter Implementation for the Robot Operating System,” Advances in Intelligent Systems and Computing, vol. 302, pp. 335–348, 2016.
- National Imagery and Mapping Agency, “Department of Defense World Geodetic System 1984,” NIMA TR8350.2, Third Edition, 2000.