659.90 IMU 프레임의 정의와 정렬

1. 개요

관성 측정 장치(Inertial Measurement Unit, IMU)는 로봇의 각속도, 선가속도, 자세(orientation)를 측정하는 핵심 센서이다. IMU 데이터는 주행 측정, 자세 추정, 센서 융합 등 로봇 시스템의 다양한 기능에 활용된다. IMU 프레임의 올바른 정의와 정렬은 이러한 데이터의 정확한 해석을 위한 전제 조건이며, REP 103의 좌표계 규약과 센서 제조사의 좌표계 규약 사이의 정합이 필수적이다.

2. IMU 프레임의 정의

2.1 좌표축 방향 (REP 103 준수)

ROS2에서 IMU 프레임은 REP 103의 물체 고정 좌표계(FLU) 규약을 따라야 한다.

방향측정 물리량
X축전방 (Forward)전방 가속도, X축 각속도(Roll rate)
Y축좌측 (Left)좌측 가속도, Y축 각속도(Pitch rate)
Z축상방 (Up)상방 가속도, Z축 각속도(Yaw rate)

2.2 REP 145: IMU 센서 드라이버 규약

REP 145는 IMU 센서 드라이버가 출력하는 데이터의 규약을 정의한다. 주요 규정은 다음과 같다.

  1. 선가속도(Linear Acceleration): 중력을 포함한 가속도를 측정한다. 로봇이 정지 상태일 때 Z축 가속도는 약 +9.81 \, \text{m/s}^2이어야 한다.

\mathbf{a}_{\text{measured}} = \mathbf{a}_{\text{kinematic}} - \mathbf{g}

여기서 \mathbf{g} = (0, 0, -9.81)^T \, \text{m/s}^2이다. 정지 상태에서 운동학적 가속도 \mathbf{a}_{\text{kinematic}} = 0이므로:

\mathbf{a}_{\text{measured}} = -\mathbf{g} = (0, 0, +9.81)^T \, \text{m/s}^2

  1. 각속도(Angular Velocity): 오른손 법칙에 따른 양의 방향으로 표현한다.

  2. 자세(Orientation): sensor_msgs/msg/Imu 메시지의 orientation 필드는 IMU 프레임에서 글로벌 기준 프레임으로의 회전을 나타내는 쿼터니언이다.

3. 센서 제조사 좌표계와의 정렬

3.1 좌표계 불일치 문제

IMU 센서 제조사는 각자의 좌표계 규약을 사용하며, 이는 REP 103의 FLU 규약과 일치하지 않을 수 있다.

제조사/센서좌표계 규약X축Y축Z축
Bosch BNO055ENU동쪽북쪽상방
InvenSense MPU6050데이터시트 참조전방좌측상방
Analog Devices ADIS16448NED 유사전방우측하방
VectorNav VN-100NED북쪽동쪽하방
Xsens MTiENU/NED 선택 가능설정 의존설정 의존설정 의존

3.2 정렬 방법

IMU 좌표계를 REP 103에 정렬하는 방법은 두 가지가 있다.

3.2.1 방법 1: 드라이버 수준의 정렬

IMU 드라이버 소프트웨어에서 센서 데이터를 REP 103 규약으로 변환한 후 발행한다. 이 방법이 가장 권장되는 접근 방식이다.

# NED → FLU 변환 예시 (드라이버 내부)
# NED: X=North(전방), Y=East(우측), Z=Down(하방)
# FLU: X=Forward(전방), Y=Left(좌측), Z=Up(상방)

imu_msg.linear_acceleration.x = raw_accel_x      # 전방 유지
imu_msg.linear_acceleration.y = -raw_accel_y      # 우측 → 좌측 (부호 반전)
imu_msg.linear_acceleration.z = -raw_accel_z      # 하방 → 상방 (부호 반전)

imu_msg.angular_velocity.x = raw_gyro_x           # 전방 유지
imu_msg.angular_velocity.y = -raw_gyro_y           # 부호 반전
imu_msg.angular_velocity.z = -raw_gyro_z           # 부호 반전

3.2.2 방법 2: TF2 정적 변환을 이용한 정렬

IMU 드라이버가 센서 제조사의 좌표계를 그대로 사용하는 경우, TF2 정적 변환을 통하여 센서 좌표계와 로봇 좌표계 사이의 회전 관계를 정의할 수 있다.

# NED 좌표계의 IMU → FLU 좌표계의 base_link
Node(
    package='tf2_ros',
    executable='static_transform_publisher',
    arguments=[
        '0.0', '0.0', '0.1',           # x, y, z (IMU 장착 위치)
        '3.14159', '0', '1.5708',       # roll, pitch, yaw (180°, 0°, 90°)
        'base_link', 'imu_link'         # parent, child
    ],
)

4. URDF에서의 IMU 프레임 정의

<!-- IMU 링크 -->
<link name="imu_link">
  <visual>
    <geometry>
      <box size="0.02 0.02 0.01"/>
    </geometry>
    <material name="blue">
      <color rgba="0.0 0.0 0.8 1.0"/>
    </material>
  </visual>
</link>

<!-- base_link에 IMU 고정 -->
<joint name="imu_joint" type="fixed">
  <parent link="base_link"/>
  <child link="imu_link"/>
  <origin xyz="0.0 0.0 0.1" rpy="0 0 0"/>
  <!-- 로봇 중심, 상방 0.1m -->
  <!-- IMU의 축 방향이 base_link와 일치하는 경우 rpy="0 0 0" -->
</joint>

IMU가 로봇 본체에 대하여 회전된 상태로 장착된 경우, <origin> 요소의 rpy 값에 해당 회전을 반영하여야 한다.

<!-- IMU가 90도 회전하여 장착된 경우 -->
<joint name="imu_joint" type="fixed">
  <parent link="base_link"/>
  <child link="imu_link"/>
  <origin xyz="0.0 0.0 0.1" rpy="0 0 1.5708"/>
  <!-- IMU가 Z축을 기준으로 90도 회전 장착 -->
</joint>

5. sensor_msgs/msg/Imu 메시지 구조

std_msgs/Header header
  builtin_interfaces/Time stamp
  string frame_id                    # IMU 프레임 이름

geometry_msgs/Quaternion orientation  # 자세 (쿼터니언)
float64[9] orientation_covariance    # 자세 공분산 (3x3, row-major)

geometry_msgs/Vector3 angular_velocity    # 각속도 (rad/s)
float64[9] angular_velocity_covariance    # 각속도 공분산

geometry_msgs/Vector3 linear_acceleration  # 선가속도 (m/s²)
float64[9] linear_acceleration_covariance  # 선가속도 공분산

각 공분산 행렬은 3 \times 3 대칭 행렬이며, 행 우선(row-major) 순서로 저장된다. 해당 데이터가 없는 경우 공분산의 첫 번째 원소를 -1로 설정한다.

6. IMU 데이터의 좌표 변환

6.1 IMU 데이터를 base_link으로 변환

IMU 데이터를 base_link 프레임으로 변환하려면 imu_link에서 base_link로의 회전 변환을 적용하여야 한다.

// IMU 데이터의 좌표 변환
auto transform = tf_buffer_->lookupTransform(
    "base_link", imu_msg->header.frame_id,
    tf2_ros::fromMsg(imu_msg->header.stamp));

// 각속도 변환 (벡터 회전)
geometry_msgs::msg::Vector3Stamped gyro_imu, gyro_base;
gyro_imu.header = imu_msg->header;
gyro_imu.vector = imu_msg->angular_velocity;
tf2::doTransform(gyro_imu, gyro_base, transform);

// 선가속도 변환 (벡터 회전)
geometry_msgs::msg::Vector3Stamped accel_imu, accel_base;
accel_imu.header = imu_msg->header;
accel_imu.vector = imu_msg->linear_acceleration;
tf2::doTransform(accel_imu, accel_base, transform);

6.2 robot_localization에서의 IMU 프레임 설정

robot_localization 패키지에서 IMU 데이터를 사용할 때, frame_id가 올바르게 설정되어 있으면 자동으로 좌표 변환이 수행된다.

ekf_node:
  ros__parameters:
    imu0: "/imu/data"
    imu0_config: [false, false, false,    # x, y, z 위치
                  true,  true,  true,     # roll, pitch, yaw
                  false, false, false,    # vx, vy, vz
                  true,  true,  true,     # vroll, vpitch, vyaw
                  true,  false, false]    # ax, ay, az

    # IMU 프레임에서 base_link로의 변환이 TF2에 존재하면
    # robot_localization이 자동으로 데이터를 변환함

7. 정렬 검증 방법

7.1 정지 상태 검증

로봇이 평탄한 지면에 정지한 상태에서 IMU 데이터를 확인한다.

ros2 topic echo /imu/data --field linear_acceleration

올바르게 정렬된 경우:

  • x ≈ 0.0 (전후 가속도 없음)
  • y ≈ 0.0 (좌우 가속도 없음)
  • z ≈ +9.81 (중력의 반대 방향)

7.2 회전 검증

로봇을 특정 축을 중심으로 수동 회전하며 각속도 데이터를 확인한다.

동작예상 결과
전방(X축)을 중심으로 시계 방향 회전angular_velocity.x > 0
좌측(Y축)을 중심으로 전방 하방 회전angular_velocity.y > 0
상방(Z축)을 중심으로 반시계 방향 회전angular_velocity.z > 0

7.3 일반적인 정렬 오류

증상원인해결
정지 시 Z 가속도가 -9.81Z축 방향이 반전됨Z축 부호 반전 또는 정적 변환 수정
전진 시 Y축 가속도 증가X축과 Y축이 교환됨축 매핑 수정
좌회전 시 음의 Yaw rateYaw 축 방향이 반전됨Z축 각속도 부호 반전
자세 추정이 점차 발산공분산 설정 부정확공분산 값 재보정

8. 요약

IMU 프레임은 REP 103의 FLU 규약에 따라 X축이 전방, Y축이 좌측, Z축이 상방을 가리키도록 정렬되어야 한다. 정지 상태에서 Z축 선가속도가 약 +9.81 \, \text{m/s}^2이고, 오른손 법칙에 따른 양의 각속도 방향이 유지되어야 한다. 센서 제조사의 좌표계가 REP 103과 일치하지 않는 경우, 드라이버 수준의 데이터 변환이나 TF2 정적 변환을 통하여 정렬을 수행하여야 한다.


참고 문헌 및 출처

  • T. Foote, “REP 103 – Standard Units of Measure and Coordinate Conventions,” ROS Enhancement Proposals, https://www.ros.org/reps/rep-0103.html (2010, 최종 갱신 2023)
  • P. Bouchier, “REP 145 – Conventions for IMU Sensor Drivers,” ROS Enhancement Proposals, https://www.ros.org/reps/rep-0145.html (2015)
  • sensor_msgs/msg/Imu API 문서, https://docs.ros2.org/latest/api/sensor_msgs/msg/Imu.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.