659.91 LiDAR 프레임의 정의와 정렬
1. 개요
LiDAR(Light Detection And Ranging)는 레이저 광선을 이용하여 주변 환경의 거리 정보를 측정하는 능동 센서이다. 2D LiDAR(레이저 스캐너)와 3D LiDAR는 로봇의 장애물 감지, 지도 작성(SLAM), 위치 추정 등에 핵심적으로 활용된다. LiDAR 프레임은 센서가 생성하는 거리 데이터의 좌표 기준을 정의하며, 올바른 프레임 정렬이 내비게이션과 매핑의 정확도를 좌우한다.
2. LiDAR 프레임의 정의
2.1 좌표축 방향 (REP 103 준수)
ROS2에서 LiDAR 프레임은 REP 103의 물체 고정 좌표계(FLU) 규약을 따른다.
| 축 | 방향 | 설명 |
|---|---|---|
| X축 | 전방 (Forward) | 로봇의 전진 방향 (0° 각도) |
| Y축 | 좌측 (Left) | 로봇의 좌측 방향 (90° 각도) |
| Z축 | 상방 (Up) | 중력 반대 방향 |
2.2 D LiDAR의 스캔 평면
2D LiDAR는 XY 평면(수평면)에서 레이저 빔을 회전시키며 거리를 측정한다. sensor_msgs/msg/LaserScan 메시지에서 각도는 다음과 같이 정의된다.
- 0° (0 rad): X축 양의 방향 (전방)
- 90° (π/2 rad): Y축 양의 방향 (좌측)
- 180° (π rad): X축 음의 방향 (후방)
- -90° (-π/2 rad): Y축 음의 방향 (우측)
90° (좌측, Y+)
↑
|
-180° (후방) ←─+─→ 0° (전방, X+)
|
↓
-90° (우측, Y-)
스캔은 반시계 방향(양의 각도 방향)으로 이루어지며, 이는 오른손 법칙의 Z축 양의 회전 방향과 일치한다.
2.3 D LiDAR의 좌표계
3D LiDAR(예: Velodyne, Ouster, Livox)는 복수의 레이저 빔을 사용하여 3차원 포인트 클라우드를 생성한다. 포인트 클라우드의 각 점은 LiDAR 프레임에서의 (x, y, z) 직교 좌표로 표현된다.
| 좌표 성분 | 의미 | 단위 |
|---|---|---|
| x | 전방 거리 | m |
| y | 좌측 거리 | m |
| z | 상방 거리 | m |
구면 좌표계 (r, \theta, \phi)에서 직교 좌표계 (x, y, z)로의 변환은 다음과 같다.
x = r \cos\phi \cos\theta, \quad y = r \cos\phi \sin\theta, \quad z = r \sin\phi
여기서 r은 거리, \theta는 수평 각도(azimuth), \phi는 수직 각도(elevation)이다.
3. 센서 제조사 좌표계와의 정렬
3.1 일반적인 LiDAR 좌표계
| 제조사/모델 | 좌표계 | 전방 | 좌측 | 상방 | ROS2 호환 |
|---|---|---|---|---|---|
| SICK LMS1xx | FLU | X+ | Y+ | Z+ | 호환 |
| Hokuyo URG-04LX | FLU | X+ | Y+ | Z+ | 호환 |
| Velodyne VLP-16 | FLU (드라이버 변환) | X+ | Y+ | Z+ | 드라이버에서 변환 |
| Ouster OS1 | FLU (드라이버 변환) | X+ | Y+ | Z+ | 드라이버에서 변환 |
| Livox Mid-360 | FLU (드라이버 변환) | X+ | Y+ | Z+ | 드라이버에서 변환 |
대부분의 ROS2 LiDAR 드라이버는 센서 제조사의 내부 좌표계를 REP 103 규약으로 자동 변환하여 출력한다. 그러나 일부 드라이버는 변환 없이 센서 원본 좌표를 출력하므로, 데이터시트를 확인하여야 한다.
3.2 전방 방향의 정렬
LiDAR를 로봇에 장착할 때, 센서의 0° 방향(X축 양의 방향)이 로봇의 전진 방향과 일치하도록 물리적으로 배치하는 것이 가장 간단한 정렬 방법이다. 물리적 정렬이 불가능한 경우, TF2 정적 변환에 회전 오프셋을 포함하여야 한다.
<!-- LiDAR가 45도 회전하여 장착된 경우 -->
<joint name="laser_joint" type="fixed">
<parent link="base_link"/>
<child link="laser_link"/>
<origin xyz="0.3 0.0 0.2" rpy="0 0 0.7854"/>
<!-- yaw = π/4 = 45° 보정 -->
</joint>
4. URDF에서의 LiDAR 프레임 정의
4.1 D LiDAR
<!-- 2D LiDAR 링크 -->
<link name="laser_link">
<visual>
<geometry>
<cylinder radius="0.035" length="0.05"/>
</geometry>
<material name="dark_grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
</visual>
<collision>
<geometry>
<cylinder radius="0.035" length="0.05"/>
</geometry>
</collision>
</link>
<!-- base_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"/>
<!-- 전방 0.3m, 상방 0.15m, 축 정렬 -->
</joint>
4.2 D LiDAR
<!-- 3D LiDAR 링크 -->
<link name="velodyne_link">
<visual>
<geometry>
<cylinder radius="0.05" length="0.07"/>
</geometry>
<material name="black">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
</visual>
</link>
<!-- 로봇 상부에 장착 -->
<joint name="velodyne_joint" type="fixed">
<parent link="base_link"/>
<child link="velodyne_link"/>
<origin xyz="0.0 0.0 0.5" rpy="0 0 0"/>
<!-- 중심 상부 0.5m -->
</joint>
5. LaserScan 메시지의 프레임 설정
5.1 sensor_msgs/msg/LaserScan 구조
std_msgs/Header header
builtin_interfaces/Time stamp
string frame_id # LiDAR 프레임 이름
float32 angle_min # 스캔 시작 각도 (rad)
float32 angle_max # 스캔 종료 각도 (rad)
float32 angle_increment # 각도 해상도 (rad)
float32 time_increment # 각도별 측정 시간 간격 (s)
float32 scan_time # 전체 스캔 소요 시간 (s)
float32 range_min # 최소 측정 거리 (m)
float32 range_max # 최대 측정 거리 (m)
float32[] ranges # 거리 데이터 배열 (m)
float32[] intensities # 반사 강도 데이터 배열
header.frame_id는 LiDAR 프레임의 이름(예: laser_link)이어야 하며, ranges 배열의 인덱스 i에 해당하는 각도는 다음과 같다.
\theta_i = \text{angle\_min} + i \times \text{angle\_increment}
이 각도에서의 측정점의 좌표는 다음과 같이 계산된다.
x_i = r_i \cos\theta_i, \quad y_i = r_i \sin\theta_i
5.2 드라이버 설정 예시
# SICK LMS1xx 드라이버 설정
sick_lms1xx_node:
ros__parameters:
frame_id: "laser_link" # TF2 프레임과 일치
host: "192.168.0.10"
port: 2112
# Velodyne VLP-16 드라이버 설정
velodyne_driver_node:
ros__parameters:
frame_id: "velodyne_link" # TF2 프레임과 일치
model: "VLP16"
rpm: 600.0
6. LiDAR 데이터의 좌표 변환
6.1 base_link으로의 변환
LiDAR 데이터를 base_link 프레임으로 변환하면 로봇 중심 기준의 환경 인식이 가능하다.
// LaserScan → PointCloud2 변환 후 좌표 변환
#include <laser_geometry/laser_geometry.hpp>
laser_geometry::LaserProjection projector;
sensor_msgs::msg::PointCloud2 cloud;
projector.projectLaser(*scan_msg, cloud);
// base_link으로 변환
auto transform = tf_buffer_->lookupTransform(
"base_link", cloud.header.frame_id,
tf2_ros::fromMsg(cloud.header.stamp));
sensor_msgs::msg::PointCloud2 cloud_base;
tf2::doTransform(cloud, cloud_base, transform);
6.2 map으로의 변환
SLAM이나 지도 작성에서는 LiDAR 데이터를 map 프레임으로 변환하여 글로벌 좌표에서 장애물을 축적한다.
7. 정렬 검증
7.1 시각적 검증
RViz2에서 LaserScan 또는 PointCloud2를 시각화하고, 로봇 모델과의 정합을 확인한다. LiDAR 데이터가 로봇 모델과 관련하여 올바른 방향으로 표시되어야 한다.
7.2 벽면 검증
로봇을 벽면에 수직으로 위치시킨 후, LiDAR 데이터에서 가장 가까운 측정점이 전방(X축 양의 방향)에 나타나는지 확인한다.
7.3 일반적인 정렬 오류와 해결
| 증상 | 원인 | 해결 |
|---|---|---|
| 스캔이 180° 회전되어 표시됨 | LiDAR가 후방을 향하여 장착됨 | 정적 변환에 yaw=π 추가 |
| 스캔이 좌우 반전됨 | LiDAR가 뒤집어져 장착됨 | 정적 변환에 roll=π 추가 |
| 스캔이 지면 아래로 표시됨 | Z 오프셋이 부정확함 | 정적 변환의 Z값 수정 |
| 스캔 데이터가 지도와 불일치 | 전방 방향이 정렬되지 않음 | yaw 오프셋 보정 |
8. 다중 LiDAR 시스템의 프레임 구성
복수의 LiDAR를 사용하는 경우, 각 센서에 고유한 프레임 이름을 부여하고 정적 변환을 정의한다.
base_link
├── front_laser_link (전방 2D LiDAR)
├── rear_laser_link (후방 2D LiDAR)
└── top_lidar_link (상부 3D LiDAR)
복수의 LiDAR 데이터를 통합하려면 모든 데이터를 공통 프레임(예: base_link)으로 변환한 후 병합한다.
9. 요약
LiDAR 프레임은 REP 103의 FLU 규약에 따라 X축이 전방(0°), Y축이 좌측(90°), Z축이 상방을 가리키도록 정렬되어야 한다. 대부분의 ROS2 LiDAR 드라이버는 센서 제조사의 좌표계를 REP 103으로 자동 변환하나, 물리적 장착 방향에 의한 오프셋은 URDF의 정적 변환으로 보정하여야 한다. header.frame_id의 정확한 설정과 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)
sensor_msgs/msg/LaserScanAPI 문서, https://docs.ros2.org/latest/api/sensor_msgs/msg/LaserScan.html (ROS2 Humble Hawksbill)sensor_msgs/msg/PointCloud2API 문서, https://docs.ros2.org/latest/api/sensor_msgs/msg/PointCloud2.html (ROS2 Humble Hawksbill)- laser_geometry 패키지, https://github.com/ros-perception/laser_geometry (ROS2 Humble 브랜치)