659.71 레이저 스캔 (sensor_msgs::LaserScan) 좌표 변환
1. 개요
레이저 스캔(laser scan)은 2차원 평면에서 레이저 빔을 회전 또는 주사(scanning)하며 취득한 거리 측정 데이터의 집합이다. sensor_msgs::msg::LaserScan 메시지는 2D LiDAR(Light Detection and Ranging), 레이저 거리 센서, 또는 3D LiDAR의 단일 스캔 라인에서 생성된 데이터를 표현한다. 로봇의 장애물 탐지, 2D SLAM, 지역 비용 지도(local costmap) 생성 등에서 핵심적으로 사용되며, 센서 프레임에서 다른 좌표 프레임으로의 변환이 빈번하게 요구된다.
2. sensor_msgs::msg::LaserScan 메시지 구조
2.1 메시지 정의
sensor_msgs/LaserScan
std_msgs/Header header
builtin_interfaces/Time stamp
string frame_id
float32 angle_min
float32 angle_max
float32 angle_increment
float32 time_increment
float32 scan_time
float32 range_min
float32 range_max
float32[] ranges
float32[] intensities
2.2 주요 필드 설명
| 필드 | 단위 | 설명 |
|---|---|---|
angle_min | rad | 스캔 시작 각도 |
angle_max | rad | 스캔 종료 각도 |
angle_increment | rad | 연속 측정 간의 각도 간격 |
time_increment | s | 연속 측정 간의 시간 간격 |
scan_time | s | 전체 스캔 소요 시간 |
range_min | m | 유효 최소 거리 |
range_max | m | 유효 최대 거리 |
ranges | m | 각 방향의 거리 측정값 배열 |
intensities | - | 각 측정의 반사 강도 (선택적) |
각 인덱스 i의 빔 방향 각도 \theta_i는 다음과 같이 계산된다.
\theta_i = \text{angle\_min} + i \cdot \text{angle\_increment}
해당 빔의 극좌표(r_i, \theta_i)에서 직교 좌표로의 변환은 다음과 같다.
x_i = r_i \cos \theta_i, \quad y_i = r_i \sin \theta_i, \quad z_i = 0
3. LaserScan과 PointCloud2의 관계
3.1 LaserScan → PointCloud2 변환
LaserScan의 좌표 변환은 직접적으로는 지원되지 않으며, 일반적으로 LaserScan을 PointCloud2로 변환한 후 포인트 클라우드의 좌표 변환을 적용하는 방식을 사용한다. ROS2에서는 laser_geometry 패키지의 LaserProjection 클래스가 이 변환을 담당한다.
3.2 laser_geometry::LaserProjection
LaserProjection 클래스는 두 가지 변환 메서드를 제공한다.
projectLaser(): TF2 없이 LaserScan을 센서 프레임의 PointCloud2로 변환transformLaserScanToPointCloud(): TF2를 활용하여 LaserScan을 지정된 대상 프레임의 PointCloud2로 변환
4. C++에서의 LaserScan 좌표 변환
4.1 의존성 설정
find_package(laser_geometry REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(sensor_msgs REQUIRED)
ament_target_dependencies(${PROJECT_NAME}
laser_geometry
tf2
tf2_ros
sensor_msgs
)
<depend>laser_geometry</depend>
<depend>tf2_ros</depend>
4.2 projectLaser()를 이용한 PointCloud2 변환
센서 프레임에서의 PointCloud2로 변환한다. TF2가 필요하지 않다.
#include <laser_geometry/laser_geometry.hpp>
laser_geometry::LaserProjection projector;
void scan_callback(
const sensor_msgs::msg::LaserScan::SharedPtr scan)
{
sensor_msgs::msg::PointCloud2 cloud;
projector.projectLaser(*scan, cloud);
// cloud는 scan->header.frame_id 프레임의 PointCloud2
// 이후 tf2를 이용하여 원하는 프레임으로 변환 가능
}
4.3 transformLaserScanToPointCloud()를 이용한 직접 변환
TF2 버퍼를 활용하여 지정된 대상 프레임의 PointCloud2로 직접 변환한다.
#include <laser_geometry/laser_geometry.hpp>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
class ScanToCloudNode : public rclcpp::Node
{
public:
ScanToCloudNode() : Node("scan_to_cloud")
{
tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(
*tf_buffer_);
scan_sub_ = this->create_subscription<
sensor_msgs::msg::LaserScan>(
"scan", 10,
std::bind(&ScanToCloudNode::scan_callback, this,
std::placeholders::_1));
cloud_pub_ = this->create_publisher<
sensor_msgs::msg::PointCloud2>("cloud", 10);
}
private:
void scan_callback(
const sensor_msgs::msg::LaserScan::SharedPtr scan)
{
sensor_msgs::msg::PointCloud2 cloud;
try {
projector_.transformLaserScanToPointCloud(
"base_link", // 대상 프레임
*scan,
cloud,
*tf_buffer_);
cloud_pub_->publish(cloud);
} catch (const tf2::TransformException & ex) {
RCLCPP_WARN(this->get_logger(), "%s", ex.what());
}
}
laser_geometry::LaserProjection projector_;
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr scan_sub_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr cloud_pub_;
};
4.4 운동 보정(Motion Compensation)이 포함된 변환
transformLaserScanToPointCloud()의 핵심 장점은 각 빔(ray)의 취득 시점별 변환을 적용하여 운동 보정을 수행하는 것이다. LaserScan 메시지의 time_increment 필드를 활용하여 각 빔의 정확한 취득 시점을 계산하고, 해당 시점의 TF2 변환을 조회하여 적용한다.
t_i = t_{\text{scan\_start}} + i \cdot \text{time\_increment}
이를 통해 로봇이 이동 중에 취득한 스캔 데이터의 왜곡(motion distortion)을 보정할 수 있다.
5. Python에서의 LaserScan 좌표 변환
from laser_geometry import LaserProjection
from sensor_msgs.msg import LaserScan, PointCloud2
projector = LaserProjection()
def scan_callback(scan_msg):
# 센서 프레임에서의 PointCloud2로 변환
cloud = projector.projectLaser(scan_msg)
# 또는 TF2를 이용한 대상 프레임으로의 변환
try:
cloud = projector.transformLaserScanToPointCloud(
'base_link', scan_msg, tf_buffer)
except TransformException as ex:
node.get_logger().error(f'{ex}')
6. 극좌표 데이터의 직접 변환
6.1 극좌표에서 직교 좌표로의 수동 변환
laser_geometry 패키지를 사용하지 않고 직접 변환하는 방법이다.
std::vector<geometry_msgs::msg::PointStamped> points;
for (size_t i = 0; i < scan->ranges.size(); ++i) {
float range = scan->ranges[i];
// 유효 범위 확인
if (range < scan->range_min || range > scan->range_max) {
continue;
}
float angle = scan->angle_min + i * scan->angle_increment;
geometry_msgs::msg::PointStamped point;
point.header = scan->header;
point.point.x = range * std::cos(angle);
point.point.y = range * std::sin(angle);
point.point.z = 0.0;
// TF2를 이용한 좌표 변환
try {
auto transformed_point = tf_buffer->transform(
point, "base_link");
points.push_back(transformed_point);
} catch (const tf2::TransformException & ex) {
// 변환 실패 처리
}
}
이 방식은 각 포인트별로 Buffer::transform()을 호출하므로 성능이 비효율적이다. laser_geometry의 일괄 변환 방식이 권장된다.
7. D SLAM 및 내비게이션에서의 활용
7.1 costmap_2d와의 연동
ROS2 Nav2의 costmap_2d 플러그인은 LaserScan 데이터를 비용 지도에 반영할 때, 내부적으로 TF2를 사용하여 센서 데이터를 비용 지도 프레임(일반적으로 map 또는 odom)으로 변환한다. 이 과정에서 센서 프레임과 로봇 기체 프레임 간의 정적 변환(URDF에서 정의) 및 로봇 기체 프레임과 비용 지도 프레임 간의 동적 변환이 모두 활용된다.
7.2 slam_toolbox와의 연동
slam_toolbox는 LaserScan 데이터를 수신하여 2D 점유 격자 지도(occupancy grid map)를 생성한다. 스캔 데이터는 odom 프레임으로 변환되어 스캔 매칭(scan matching)에 사용되며, 루프 폐합(loop closure) 검출을 통해 누적 오차를 보정한다.
8. 주의사항
8.1 D LiDAR의 설치 자세
2D LiDAR는 수평 평면에 정확히 정렬되어 설치되어야 한다. LiDAR의 설치 자세가 기울어진 경우, 스캔 평면이 수평 평면과 일치하지 않으므로 z = 0 가정이 위반된다. 이런 경우에는 PointCloud2로 변환한 후 3차원 좌표 변환을 적용해야 한다.
8.2 NaN 및 Inf 값 처리
LaserScan의 ranges 배열에는 유효하지 않은 측정값이 NaN(Not a Number) 또는 Inf(Infinity)로 저장될 수 있다. 좌표 변환 전에 이러한 값을 적절히 필터링하거나, range_min과 range_max 범위를 확인하여 유효 측정값만 처리해야 한다.
8.3 각도 범위와 방향
LaserScan의 angle_min과 angle_max는 센서 프레임의 z축을 중심으로 한 회전 각도이다. REP 103에 따르면 양의 각도는 반시계 방향(counterclockwise)이다. 센서 프레임의 x축 방향이 전방인지 확인하여 각도 해석의 정확성을 보장해야 한다.
9. 참고 문헌
- Open Robotics, “sensor_msgs/LaserScan,” ROS 2 Documentation, https://docs.ros.org/en/rolling/p/sensor_msgs/
- Open Robotics, “laser_geometry,” ROS 2 Documentation, https://docs.ros.org/en/rolling/p/laser_geometry/
- S. Macenski and I. Jambrecic, “SLAM Toolbox: SLAM for the dynamic world,” Journal of Open Source Software, vol. 6, no. 61, 2783, 2021.
버전: 2026-03-26