스크린캐스트 11-08-2025 03:28:33 PM.webm
GNSS 시스템을 ROS에 적용하기 위해서는 robot_localization이 제공하는 navsat_transform_node를 이용하는 것이 편리하다. GNSS Receiver는 위·경도 좌표를 송신하므로, 이를 m 단위의 지역 좌표계(ENU)로 변환해 사용한다.

위 그림은 GPS, IMU, Odometry를 기반으로 한 일반적인 robot_localization 구성이다.
공식 문서에 따르면, continuous한 Odometry, IMU 데이터는 Local EKF 에서 융합하며, GPS처럼 비연속적인 데이터(위성 신호)는 Global EKF에서 함께 융합한다.
선박 연구를 수행하며 wheel odometry를 사용할 수 없는 환경이었기 때문에,
이 프로젝트에서는 IMU + GPS 기반의 EKF Fusion으로 구성하였다.
ekf_global과 navsat_transform은 서로 데이터를 주고받는 구조로 되어 있으며,
언뜻 보면 순환참조처럼 보이지만 이는 정상적인 구조이다.
navsat_transform은 ekf_global의 odometry/filtered를 구독하고,
변환된 GPS 기반의 위치(odometry/gps)를 다시 EKF로 전달하는 순환 흐름이 형성된다.
따라서 yaml 파일 구성 시 토픽 방향이 서로 뒤바뀌지 않도록 주의해야 한다.
⚙️ 설정 파일 구성 (ekf_navsat.yaml)
ekf_filter_node: # subscribe : imu, odometry/gps, publish : odometry/filtered & TF
ros__parameters:
frequency: 30.0
sensor_timeout: 0.1
two_d_mode: true
odom0: /odometry/gps
odom0_config: [true, true, false,
false, false, false,
false, false, false,
false, false, false,
false, false, false]
imu0: /imu
imu0_config: [false, false, false,
false, false, true,
false, false, false,
false, false, false,
false, false, false]
publish_tf: true
world_frame: map
base_link_frame: base_link
odom_frame: map
use_sim_time: true
navsat_transform_node: # subscribe : /imu, /gps/fix, /odometry/filtered, publish : odometry/gps
ros__parameters:
frequency: 30.0
two_d_mode: true
magnetic_declination_radians: 0.0
yaw_offset: 0.0
zero_altitude: true
broadcast_utm_transform: false
broadcast_utm_transform_as_parent_frame: false
publish_filtered_gps: true
use_odometry_yaw: false
wait_for_datum: false
use_manual_datum: false
base_link_frame: base_link
odom_frame: odom
world_frame: map
use_sim_time: true