659.83 base_link 프레임의 정의와 역할

1. 개요

base_link는 REP 105에 의하여 정의된 로봇 본체의 기준 좌표 프레임(reference coordinate frame)이다. 이 프레임은 로봇의 물리적 구조에 고정되어 로봇과 함께 이동하며, 로봇에 장착된 모든 센서, 구동기, 관절 등의 하위 프레임이 직접 또는 간접적으로 연결되는 중심 프레임으로서 기능한다. TF2 변환 트리에서 base_link는 로봇 본체 프레임 계층의 루트 역할을 수행하며, 로봇 시스템의 모든 좌표 변환의 기준점이 된다.

2. base_link 프레임의 정의

2.1 REP 105에 의한 정의

REP 105는 base_link 프레임을 다음과 같이 정의한다.

base_link는 로봇의 본체에 강체적으로(rigidly) 부착된 좌표 프레임이다. base_link는 로봇의 임의의 위치에 부착될 수 있으나, REP 103의 좌표계 방향 규약을 준수하여야 한다.

이 정의에 따른 base_link의 핵심 특성은 다음과 같다.

  • 강체 부착(Rigid Attachment): base_link는 로봇 본체에 고정되어 있으며, 로봇의 이동 및 회전과 함께 동일하게 변위한다.
  • REP 103 준수: X축이 로봇의 전방(forward), Y축이 좌측(left), Z축이 상방(up)을 가리키는 FLU(Forward-Left-Up) 규약을 따른다.
  • 위치 자유도: 로봇 본체 내의 특정 위치(예: 질량 중심, 회전 중심, 기하학적 중심 등)에 배치할 수 있으나, 일반적으로 로봇의 회전 중심에 배치한다.

2.2 좌표축 방향

        Z (Up)
        ↑
        |
        |    base_link
        +------→ X (Forward, 로봇 전진 방향)
       /
      /
     ↙
    Y (Left)
  • X축: 로봇의 전진 방향을 가리킨다. 차분 구동(differential drive) 로봇의 경우 두 구동 바퀴의 중간점에서 전방을 향한다.
  • Y축: 로봇의 좌측 방향을 가리킨다. X축과 Z축으로부터 오른손 법칙에 의하여 결정된다.
  • Z축: 중력의 반대 방향(상방)을 가리킨다.

2.3 원점 위치 선정 지침

로봇 유형권장 원점 위치사유
차분 구동 로봇두 구동 바퀴의 중심축 교점회전 중심과 일치
아커만 조향 로봇후륜 축의 중심비홀로노믹 운동학 기준점
전방향 이동 로봇기하학적 중심대칭 구조의 기준점
매니퓰레이터베이스 관절 중심운동학적 기준점
멀티로터 드론기하학적 중심추력 벡터의 중심
휴머노이드 로봇골반(pelvis) 중심보행 동역학 기준점

3. base_link의 역할

3.1 센서 프레임의 기준점

로봇에 장착된 모든 센서의 위치와 자세는 base_link에 대한 상대 변환으로 정의된다. 이러한 변환은 로봇의 기계적 구조에 의하여 고정되어 있으므로 정적 변환(static transform)으로 발행된다.

base_link
  ├── laser_link         (정적: 전방 0.3m, 상방 0.15m)
  ├── camera_link        (정적: 전방 0.2m, 상방 0.4m)
  ├── imu_link           (정적: 중심, 상방 0.1m)
  ├── gps_link           (정적: 상부 중심)
  └── ultrasonic_link    (정적: 전방 0.35m, 상방 0.1m)

3.2 로봇 위치의 대표점

로봇의 현재 위치를 표현할 때, base_link의 위치와 자세가 로봇의 위치와 자세를 대표한다. 내비게이션 스택, 위치 추정 알고리즘, 경로 계획기 등은 모두 base_link의 위치를 기준으로 로봇의 상태를 판단한다.

  • map → base_link: 로봇의 글로벌 위치를 나타낸다.
  • odom → base_link: 로봇의 주행 측정 기반 위치를 나타낸다.

3.3 운동학 모델의 기준 프레임

로봇의 운동학 모델(kinematic model)에서 base_link는 로봇 본체의 기준 좌표계로 사용된다. 속도 명령(geometry_msgs/msg/Twist)은 base_link 프레임에서 표현되며, 선속도의 X 성분이 전진 속도, 각속도의 Z 성분이 회전 속도를 나타낸다.

// cmd_vel을 base_link 프레임에서 발행하는 예시
geometry_msgs::msg::Twist cmd_vel;
cmd_vel.linear.x = 0.5;   // 전진 속도 0.5 m/s
cmd_vel.linear.y = 0.0;   // 횡방향 속도 (비홀로노믹 로봇은 0)
cmd_vel.angular.z = 0.2;  // 회전 속도 0.2 rad/s
cmd_vel_pub_->publish(cmd_vel);

3.4 충돌 모델의 기준 프레임

로봇의 충돌 검사(collision detection)와 안전 영역(footprint) 정의에서 base_link가 기준 프레임으로 사용된다. 내비게이션 스택에서 로봇의 풋프린트(footprint)는 base_link 프레임에서의 2D 다각형으로 정의된다.

# Nav2 로봇 풋프린트 설정 (base_link 기준 좌표)
robot_radius: 0.25  # 원형 풋프린트
# 또는 다각형 풋프린트:
footprint: "[[0.3, 0.2], [0.3, -0.2], [-0.3, -0.2], [-0.3, 0.2]]"

4. URDF에서의 base_link 정의

4.1 기본 URDF 구조

<?xml version="1.0" encoding="UTF-8"?>
<robot name="mobile_robot" xmlns:xacro="http://www.ros.org/wiki/xacro">

  <!-- base_link: 로봇 본체의 기준 프레임 -->
  <link name="base_link">
    <visual>
      <geometry>
        <box size="0.5 0.3 0.15"/>
      </geometry>
      <material name="grey">
        <color rgba="0.5 0.5 0.5 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <box size="0.5 0.3 0.15"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="10.0"/>
      <inertia ixx="0.1" ixy="0" ixz="0"
               iyy="0.15" iyz="0" izz="0.2"/>
    </inertial>
  </link>

  <!-- 센서 프레임의 정적 연결 -->
  <joint name="laser_joint" type="fixed">
    <parent link="base_link"/>
    <child link="laser_link"/>
    <origin xyz="0.3 0.0 0.15" rpy="0 0 0"/>
  </joint>

  <link name="laser_link">
    <visual>
      <geometry>
        <cylinder radius="0.03" length="0.05"/>
      </geometry>
    </visual>
  </link>

  <joint name="camera_joint" type="fixed">
    <parent link="base_link"/>
    <child link="camera_link"/>
    <origin xyz="0.2 0.0 0.4" rpy="0 0.2 0"/>
  </joint>

  <link name="camera_link">
    <visual>
      <geometry>
        <box size="0.04 0.08 0.04"/>
      </geometry>
    </visual>
  </link>

</robot>

4.2 관절 프레임의 연결

base_link에 관절(joint)을 통하여 바퀴, 팔, 기타 가동 부품이 연결된다. 가동 관절(revolute, prismatic, continuous)은 동적 변환으로, 고정 관절(fixed)은 정적 변환으로 TF2에 발행된다.

<!-- 좌측 바퀴 관절 -->
<joint name="wheel_left_joint" type="continuous">
  <parent link="base_link"/>
  <child link="wheel_left_link"/>
  <origin xyz="0.0 0.17 -0.05" rpy="-1.5708 0 0"/>
  <axis xyz="0 0 1"/>
</joint>

<!-- 우측 바퀴 관절 -->
<joint name="wheel_right_joint" type="continuous">
  <parent link="base_link"/>
  <child link="wheel_right_link"/>
  <origin xyz="0.0 -0.17 -0.05" rpy="-1.5708 0 0"/>
  <axis xyz="0 0 1"/>
</joint>

5. 프로그래밍에서의 base_link 활용

5.1 센서 데이터의 base_link 변환

센서 데이터를 base_link 프레임으로 변환하면 로봇 중심 기준의 통합된 센서 뷰를 얻을 수 있다.

// 레이저 스캔을 base_link 프레임으로 변환
auto transform = tf_buffer_->lookupTransform(
    "base_link", scan_msg->header.frame_id,
    tf2_ros::fromMsg(scan_msg->header.stamp));

sensor_msgs::msg::PointCloud2 cloud_base;
tf2::doTransform(cloud_laser, cloud_base, transform);

5.2 로봇 위치 조회

로봇의 글로벌 위치를 조회하려면 map에서 base_link로의 변환을 조회한다.

try:
    transform = tf_buffer.lookup_transform(
        'map', 'base_link', rclpy.time.Time())
    
    robot_x = transform.transform.translation.x
    robot_y = transform.transform.translation.y
    robot_z = transform.transform.translation.z
    
    # 쿼터니언에서 yaw 각도 추출
    q = transform.transform.rotation
    siny_cosp = 2.0 * (q.w * q.z + q.x * q.y)
    cosy_cosp = 1.0 - 2.0 * (q.y * q.y + q.z * q.z)
    robot_yaw = math.atan2(siny_cosp, cosy_cosp)
    
except TransformException as ex:
    self.get_logger().warning(f'위치 조회 실패: {ex}')

6. base_link 설정 시 주의 사항

6.1 회전 중심과의 정렬

base_link의 원점을 로봇의 회전 중심(instantaneous center of rotation)에 배치하면 운동학 계산이 단순화된다. 회전 중심에 배치하지 않는 경우, 추가적인 오프셋 보정이 필요하다.

6.2 지면으로부터의 높이

base_link의 Z축 원점은 로봇의 물리적 구조에 따라 결정된다. 고정된 높이에 위치하는 것이 일반적이나, 서스펜션이나 경사면에 의하여 높이가 변동할 수 있는 경우에는 별도의 보정이 필요하다. 2D 내비게이션에서는 지면 높이를 0으로 간주하는 base_footprint 프레임을 활용할 수 있다.

6.3 다중 로봇에서의 네임스페이싱

다중 로봇 시스템에서는 각 로봇의 base_link를 네임스페이스로 구분하여야 한다. 예를 들어, robot1/base_link, robot2/base_link와 같이 접두사를 추가하여 프레임 이름의 충돌을 방지한다.

7. 요약

base_link는 ROS2 로봇 시스템에서 로봇 본체의 기준 좌표 프레임으로, 센서 프레임의 기준점, 로봇 위치의 대표점, 운동학 모델 및 충돌 모델의 기준 프레임으로 사용된다. REP 103의 FLU 규약에 따라 X축이 전방, Y축이 좌측, Z축이 상방을 가리키며, REP 105의 프레임 계층에서 odom의 직접 하위 프레임으로 위치한다. base_link의 원점은 로봇의 회전 중심에 배치하는 것이 권장되며, URDF를 통하여 로봇의 물리적 구조와 센서 배치를 정의한다.


참고 문헌 및 출처

  • T. Foote, “REP 105 – Coordinate Frames for Mobile Platforms,” ROS Enhancement Proposals, https://www.ros.org/reps/rep-0105.html (2010, 최종 갱신 2022)
  • T. Foote, “REP 103 – Standard Units of Measure and Coordinate Conventions,” ROS Enhancement Proposals, https://www.ros.org/reps/rep-0103.html (2010, 최종 갱신 2023)
  • ROS2 공식 문서, “URDF Tutorials”, https://docs.ros.org/en/humble/Tutorials/Intermediate/URDF/ (ROS2 Humble Hawksbill)
  • Nav2 공식 문서, “Setting Up Robot Configuration”, https://docs.nav2.org/setup_guides/ (Nav2 1.1, 2023)