형변환을 해야 하는 이유
ROS를 처음 입문을 하면 형 변환을 하는 게 낯설어서 굉장히 힘듭니다. 그런데 이 형 변환을 왜 해야할까요? 정답은 ROS에서 master를 통해 통신할 때 주고 받는 sensor_msgs::PointCloud2
메세지를 사용하는데 그 data를 후처리할 때는 PCL의 pointcloud를 사용해야 하기 때문입니다. 비유를 하자면 sensor_msgs::PointCloud2
는 택배를 보내기 위해 상자에 data를 담아서 포장해둔 상태이고 pcl::PointCloud
는 그 상자를 뜯어서 포장지를 뜯은 data라고 이해하면 될 것 같습니다.
사족이지만 이렇게 분리해서 쓰는 이유는 -물론 ROS와 PCL을 개발한 사람들이 다른 이유도 있겠지만- 통신을 빠르게 하기 위함이라고 생각합니다 (저의 100% 추정입니다). 왜냐하면 ROS sensors_msgs::PointCloud2 공식 안내 페이지를 살펴보면 range data가 uint8로 encoding되어 있는데, 이렇게 1차원의 range 정보를 data
를 담아서 publish/subscribe하는 게 3개의 float64로 구성되있는 수 만개의 pcl::PointXYZ
를 직접 publish/subscribe하는 것보다 훨씬 메모리를 절약할 수 있기 때문입니다.
PointCloud 형 변환
메세지 변환은 변환은 어렵지 않습니다 :) 아래와 같이 pcl::fromROSMsg
와 pcl::toROSMsg
를 사용하면 쉽게 변환할 수 있습니다.
sensor_msgs::PointCloud2 → pcl::PointCloud
pcl::PointCloud<pcl::PointXYZ> cloudmsg2cloud(sensor_msgs::PointCloud2 cloudmsg)
{
pcl::PointCloud<pcl::PointXYZ> cloud_dst;
pcl::fromROSMsg(cloudmsg, cloud_dst);
return cloud_dst;
}
pcl::PointCloud → sensor_msgs::PointCloud2
sensor_msgs::PointCloud2 cloud2cloudmsg(pcl::PointCloud<pcl::PointXYZ> cloud_src)
{
sensor_msgs::PointCloud2 cloudmsg;
pcl::toROSMsg(cloudsrc, cloudmsg);
cloudmsg.header.frame_id = "map";
return cloudmsg;
}
2D LiDAR를 사용하시는 분도 계실텐데, 2D LiDAR는 sensor_msgs::PointCloud2
가 아닌 sensor_msgs::LaserScan
이기 때문에, 아래와 같이 laser_geometry header를 통해 변환해줄 수 있습니다.
sensor_msgs::LaserScan → sensor_msgs::PointCloud2
#include "laser_geometry/laser_geometry.h"
sensor_msgs::PointCloud2 laser2cloudmsg(sensor_msgs::LaserScan laser)
{
static laser_geometry::LaserProjection projector;
sensor_msgs::PointCloud2 pc2_dst;
projector.projectLaser(laser, pc2_dst,-1,laser_geometry::channel_option::Intensity | laser_geometry::channel_option::Distance);
pc2_dst.header.frame_id = "map";
return pc2_dst;
}
따라서 편의상 저는 sensor_msgs::LaserScan
→ sensor_msgs::PointCloud2
→ pcl::PointCloud
로 변환해서 사용합니다. LaserScan 같은 경우는 3D LiDAR 보다 데이터 양이 훨씬 적기 떄문에 (약 1000개의 range data가 들어옵니다) sensor_msgs::PointCloud2
를 거쳐서 변환해도 속도 이슈가 크게 발생하지 않습니다.
Point Cloud Library Tutorial 시리즈입니다.
모든 코드는 이 레포지토리에 있고, ros package로 구성되어 있어 build하여 직접 돌려보실 수 있습니다
- ROS Point Cloud Library (PCL) - 0. Tutorial 및 기본 사용법
- ROS Point Cloud Library (PCL) - 1. Ptr, ConstPtr의 완벽 이해 (1) shared_ptr
- ROS Point Cloud Library (PCL) - 1. Ptr, ConstPtr의 완벽 이해 (2) Ptr in PCL
- ROS Point Cloud Library (PCL) - 1. Ptr, ConstPtr의 완벽 이해 (3) Ptr in 클래스 멤버변수
- ROS Point Cloud Library (PCL) - 2. 형변환 - toROSMsg, fromROSMsg
- ROS Point Cloud Library (PCL) - 3. Transformation
- ROS Point Cloud Library (PCL) - 4. Viewer로 visualization하는 법
- ROS Point Cloud Library (PCL) - 5. Voxelization
- ROS Point Cloud Library (PCL) - 6. PassThrough
- ROS Point Cloud Library (PCL) - 7. Statistical Outlier Removal
- ROS Point Cloud Library (PCL) - 8. KdTree를 활용한 Radius Search
- ROS Point Cloud Library (PCL) - 9. KdTree를 활용한 K-nearest Neighbor Search (KNN)
- ROS Point Cloud Library (PCL) - 10. Normal Estimation
- ROS Point Cloud Library (PCL) - 11. Iterative Closest Point (ICP)
- ROS Point Cloud Library (PCL) - 12. Generalized Iterative Closest Point (G-ICP)
- ROS Point Cloud Library (PCL) - 13. getVector3fMap()을 통한 효율적인 복사