659.84 base_footprint 프레임의 정의와 역할
1. 개요
base_footprint는 로봇의 수직 투영점(vertical projection)에 위치하는 좌표 프레임으로, 로봇 본체를 지면(ground plane)에 수직으로 투영한 지점에 원점을 갖는다. 이 프레임은 REP 105의 표준 프레임 체인에서 선택적(optional)으로 사용되며, 주로 2D 내비게이션 시스템에서 로봇의 지면 위치를 표현하는 용도로 활용된다. base_footprint는 base_link와 함께 로봇 본체를 표현하되, Z축 높이 성분을 제거하여 지면 평면 상의 위치만을 나타낸다.
2. 정의
2.1 기하학적 정의
base_footprint는 다음과 같이 정의된다.
base_footprint는base_link프레임의 원점을 지면에 수직으로 투영한 점에 위치하며, Z 좌표가 항상 0인 좌표 프레임이다.base_footprint의 X축과 Y축은base_link와 동일한 방향을 가리키되, Roll과 Pitch 회전이 제거된다.
이를 수학적으로 표현하면, odom 프레임에서의 base_footprint의 포즈는 다음과 같다.
T_{\text{odom} \leftarrow \text{base\_footprint}} = \begin{bmatrix} \cos\psi & -\sin\psi & 0 & x \\ \sin\psi & \cos\psi & 0 & y \\ 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 1 \end{bmatrix}
여기서 x, y는 base_link의 지면 투영 위치, \psi는 Yaw 각이다. Z 좌표, Roll(\phi), Pitch(\theta) 성분이 모두 제거되어 순수한 2D 평면 위치만을 나타낸다.
2.2 base_link와의 관계
base_footprint에서 base_link로의 변환은 주로 Z축 오프셋과 Roll/Pitch 회전으로 구성된다.
T_{\text{base\_footprint} \leftarrow \text{base\_link}} = \begin{bmatrix} R(\phi, \theta) & \begin{pmatrix} 0 \\ 0 \\ h \end{pmatrix} \\ 0 & 1 \end{bmatrix}
여기서 h는 base_link의 지면으로부터의 높이, R(\phi, \theta)는 Roll과 Pitch에 의한 회전 행렬이다.
| 조건 | base_footprint → base_link 변환 |
|---|---|
| 평탄 지면, 고정 높이 | Z축 병진만 존재 (정적 변환) |
| 경사면 주행 | Z축 병진 + Roll/Pitch 회전 (동적 변환) |
| 서스펜션 장착 로봇 | Z축 병진 변동 (동적 변환) |
3. 프레임 체인에서의 위치
3.1 표준 프레임 체인
base_footprint를 사용하는 경우의 프레임 체인은 다음과 같다.
map → odom → base_footprint → base_link → sensor_frames
base_footprint는 odom과 base_link 사이에 위치하며, 주행 측정 노드는 odom → base_footprint 변환을 발행한다.
3.2 base_footprint를 사용하지 않는 경우
base_footprint가 필요하지 않은 시스템에서는 다음과 같이 축소된 프레임 체인을 사용한다.
map → odom → base_link → sensor_frames
이 경우 주행 측정 노드는 odom → base_link 변환을 직접 발행한다.
4. 역할과 활용 목적
4.1 2D 내비게이션의 기준 프레임
Nav2 등의 2D 내비게이션 스택에서는 로봇의 위치를 2D 평면 좌표 (x, y, \theta)로 표현한다. base_footprint는 Z 좌표가 항상 0이므로, 2D 내비게이션의 기준 프레임으로 직접 사용할 수 있다.
# Nav2 설정에서 base_footprint 사용
amcl:
ros__parameters:
base_frame_id: "base_footprint"
odom_frame_id: "odom"
global_frame_id: "map"
controller_server:
ros__parameters:
odom_topic: "/odom"
robot_base_frame: "base_footprint"
4.2 지면 정합성 보장
base_footprint를 사용하면 로봇의 Roll, Pitch 변동(예: 경사면 주행, 요철 통과)이 내비게이션 계산에 영향을 미치지 않는다. 이는 2D 점유 격자 지도(occupancy grid map)와의 정합성을 보장한다.
4.3 풋프린트 정의의 기준
로봇의 2D 풋프린트(충돌 영역)는 base_footprint 프레임에서 정의된다. 풋프린트의 모든 꼭짓점이 Z=0 평면에 위치하므로, 지도 상의 장애물과의 충돌 검사가 단순화된다.
4.4 비용 지도(Costmap)와의 호환성
Nav2의 비용 지도는 2D 평면에서의 장애물 분포를 표현한다. base_footprint를 기준으로 로봇의 위치를 표현하면, 3D 센서 데이터를 2D 비용 지도에 투영할 때 좌표계의 일관성이 유지된다.
5. TF2에서의 구현
5.1 정적 변환 (평탄 지면)
로봇이 평탄한 지면에서만 운행되는 경우, base_footprint에서 base_link로의 변환은 고정된 Z축 오프셋만을 포함하는 정적 변환이다.
# launch 파일에서 정적 변환 설정
Node(
package='tf2_ros',
executable='static_transform_publisher',
arguments=[
'0', '0', '0.12', # x, y, z (z값이 base_link의 지면 높이)
'0', '0', '0', # roll, pitch, yaw
'base_footprint', # parent frame
'base_link' # child frame
],
)
5.2 동적 변환 (비평탄 지면)
경사면이나 요철이 있는 지면에서 운행되는 로봇의 경우, base_footprint에서 base_link로의 변환은 IMU 데이터 등을 기반으로 동적으로 갱신된다.
void publish_base_footprint_transform(
double roll, double pitch, double height)
{
geometry_msgs::msg::TransformStamped t;
t.header.stamp = this->get_clock()->now();
t.header.frame_id = "base_footprint";
t.child_frame_id = "base_link";
// Z축 높이 설정
t.transform.translation.x = 0.0;
t.transform.translation.y = 0.0;
t.transform.translation.z = height;
// Roll과 Pitch만을 반영하는 쿼터니언
tf2::Quaternion q;
q.setRPY(roll, pitch, 0.0);
t.transform.rotation.x = q.x();
t.transform.rotation.y = q.y();
t.transform.rotation.z = q.z();
t.transform.rotation.w = q.w();
tf_broadcaster_->sendTransform(t);
}
5.3 URDF에서의 정의
<!-- base_footprint 프레임 -->
<link name="base_footprint"/>
<!-- base_footprint → base_link 고정 관절 -->
<joint name="base_footprint_joint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link"/>
<origin xyz="0 0 0.12" rpy="0 0 0"/>
</joint>
<!-- base_link 정의 -->
<link name="base_link">
<visual>
<geometry>
<box size="0.5 0.3 0.15"/>
</geometry>
</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>
6. 주행 측정과 base_footprint
6.1 주행 측정 노드의 출력
주행 측정 노드는 base_footprint를 자식 프레임으로 하는 변환을 발행한다.
# 주행 측정 데이터의 frame_id 설정
odom_msg = Odometry()
odom_msg.header.frame_id = 'odom'
odom_msg.child_frame_id = 'base_footprint'
# 2D 위치만 설정 (Z=0)
odom_msg.pose.pose.position.x = x
odom_msg.pose.pose.position.y = y
odom_msg.pose.pose.position.z = 0.0
# Yaw 각만 반영
q = Quaternion()
q.z = math.sin(yaw / 2.0)
q.w = math.cos(yaw / 2.0)
odom_msg.pose.pose.orientation = q
6.2 robot_localization에서의 설정
robot_localization 패키지의 EKF/UKF 노드에서 base_footprint를 사용하려면 다음과 같이 설정한다.
ekf_node:
ros__parameters:
odom_frame: "odom"
base_link_frame: "base_footprint"
world_frame: "odom"
two_d_mode: true # 2D 모드에서 base_footprint 사용
two_d_mode를 true로 설정하면, 필터가 x, y, \psi(Yaw)의 3자유도만을 추정하며, 이는 base_footprint의 2D 특성과 정확히 일치한다.
7. base_footprint 사용 시 고려 사항
7.1 사용이 권장되는 경우
| 시나리오 | 사유 |
|---|---|
| 2D 내비게이션 시스템 | 지면 평면 상의 위치 표현이 필수적 |
| 평탄 실내 환경 | 높이 변동이 없어 정적 변환으로 충분 |
| 점유 격자 지도 기반 경로 계획 | 2D 비용 지도와의 호환성 보장 |
7.2 사용이 불필요한 경우
| 시나리오 | 사유 |
|---|---|
| 3D 내비게이션 (드론, 수중 로봇) | 3D 위치 표현이 필요하므로 base_link를 직접 사용 |
| 매니퓰레이터 전용 시스템 | 지면 투영 개념이 불필요 |
| 6자유도 위치 추정 시스템 | base_link의 완전한 포즈가 필요 |
7.3 주의 사항
-
이중 발행 방지:
odom → base_footprint와odom → base_link변환을 동시에 발행하면 TF2 트리에 분기(branching)가 발생하여base_footprint → base_link경로의 변환 조회가 불가능해진다. 반드시 한 경로만 사용하여야 한다. -
Nav2 설정 일관성: Nav2의
base_frame_id설정이 실제 TF2 트리의 프레임과 일치하여야 한다.base_footprint를 사용하면서 Nav2에base_link를 설정하거나, 그 반대의 경우 내비게이션이 정상적으로 동작하지 않는다. -
IMU 데이터와의 정합:
base_footprint를 사용하는 경우, IMU에서 측정된 Roll/Pitch 값은base_footprint → base_link변환에 반영되어야 하며, 주행 측정의odom → base_footprint변환에는 Yaw만 반영되어야 한다.
8. 요약
base_footprint는 로봇의 지면 투영점에 위치하는 2D 기준 프레임으로, Z 좌표가 항상 0이고 Roll/Pitch 회전이 제거된 상태를 유지한다. 2D 내비게이션 시스템에서 로봇의 평면 위치를 표현하는 데 최적화되어 있으며, odom → base_footprint → base_link 프레임 체인을 통하여 2D 위치 추정과 3D 로봇 구조를 체계적으로 분리한다. 사용 여부는 시스템의 차원성(2D/3D)과 내비게이션 요구 사항에 따라 결정한다.
참고 문헌 및 출처
- T. Foote, “REP 105 – Coordinate Frames for Mobile Platforms,” ROS Enhancement Proposals, https://www.ros.org/reps/rep-0105.html (2010, 최종 갱신 2022)
- 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.
- Nav2 공식 문서, “Setting Up Transformations”, https://docs.nav2.org/setup_guides/transformation/setup_transforms.html (Nav2 1.1, 2023)
- ROS2 공식 문서, “URDF Tutorials”, https://docs.ros.org/en/humble/Tutorials/Intermediate/URDF/ (ROS2 Humble Hawksbill)