最小構成(point cloudを読み込んで,表示して,保存する)
色々調べて聞くと,一番初めの型の宣言方法が2種類あることが分かる.
pcl::PointCloud<pcl::PointXYZ> cloud;
pcl::PointCloud<pcl::PointXYZ> Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
どちらもビルドできるし,何が違うの?と思ったら,一つ目では使えない関数が多々あった.
その理由として,
pcl::PointCloud<pcl::PointXYZ> cloud;
これはスマートポインタを使わない方法であり
pcl::PointCloud<pcl::PointXYZ> Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
こちらはスマートポインタを利用した点群オブジェクトの宣言方法である,という違いがあげられる.
スマートポインタが何なのかちょっとよく分からないが,「点群はかなり大きいデータになるので、オブジェクトをディープコピーするとメモリを浪費してしまいます。 この問題を避けるのが、スマートポインタを用いた宣言の仕方です。 なので、PCLで扱う多くの関数の引数はスマートポインタを取るようになっています。」だそう.
つまり,スマートポインタを使わなかったせいで,動くはずの関数が動かない事件が発生していた.
スマートポインタなしだと動かない事例
- ポイントクラウドの表示
- ダウンサンプリング
スマートポインタの有無によるコードの違い
スマートポインタありver.
# include <ros/ros.h> //rosを使わないときはこの行のみ消す
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/io/pcd_io.h>
#include <iostream>
#include <pcl/common/impl/io.hpp>
using namespace std;
// settings
void viewerOneOff(pcl::visualization::PCLVisualizer& viewer)
{
// set back ground color
viewer.setBackgroundColor(1, 1, 1); //white
cout << "viewerOneOff" << std::endl;
}
int main()
{ // set Type
using CloudType = pcl::PointCloud<pcl::PointXYZRGB>;
CloudType::Ptr cloud(new CloudType);
// 作成したPointCloudを読み込む
pcl::io::loadPCDFile("/home/file_path/PointCloud.pcd", *cloud);
// get point cloud data
double width = cloud->width;
double height = cloud->height;
// cloud->points.resize(cloud->width * cloud->height);
//access each point
for(int i = 0 ; i < cloud->points.size() ; i++)
{
double x, y, z, r, g, b;
x = cloud->points[i].x;
y = cloud->points[i].y;
z = cloud->points[i].z;
r = cloud->points[i].r;
g = cloud->points[i].g;
b = cloud->points[i].b;
}
// create veiwer
pcl::visualization::CloudViewer viewer("PointCloudViewer");
viewer.showCloud(cloud);
// ビューワー起動時の一回だけ呼ばれる関数をセット
viewer.runOnVisualizationThreadOnce(viewerOneOff);
// ビューワー視聴用ループ
while (!viewer.wasStopped())
{
}
//PCDファイルの出力
pcl::io::savePCDFile('/home/file_path/cloud',*cloud);
return 0;
}
スマートポインタなしver.
# include <ros/ros.h> //rosを使わないときはこの行のみ消す
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/io/pcd_io.h>
#include <iostream>
#include <pcl/common/impl/io.hpp>
using namespace std;
// settings
void viewerOneOff(pcl::visualization::PCLVisualizer& viewer)
{
// set back ground color
viewer.setBackgroundColor(1, 1, 1); //white
cout << "viewerOneOff" << std::endl;
}
int main()
{ // set Type
using CloudType = pcl::PointCloud<pcl::PointXYZRGB>;
CloudType cloud;
// 作成したPointCloudを読み込む
pcl::io::loadPCDFile("/home/file_path/PointCloud.pcd", cloud);
// get point cloud data
double width = cloud.width;
double height = cloud.height;
// cloud->points.resize(cloud.width * cloud.height);
//access each point
for(int i = 0 ; i < cloud.points.size() ; i++)
{
double x, y, z, r, g, b;
x = cloud.points[i].x;
y = cloud.points[i].y;
z = cloud.points[i].z;
r = cloud.points[i].r;
g = cloud.points[i].g;
b = cloud.points[i].b;
}
// スマートポインタでは,ポイントクラウドの表示はできない
//// create veiwer
//pcl::visualization::CloudViewer viewer("PointCloudViewer");
//viewer.showCloud(cloud);
//// ビューワー起動時の一回だけ呼ばれる関数をセット
//viewer.runOnVisualizationThreadOnce(viewerOneOff);
//// ビューワー視聴用ループ
//while (!viewer.wasStopped())
//{
//}
//PCDファイルの出力
pcl::io::savePCDFile('/home/file_path/cloud', cloud);
return 0;
}
PCL機能いろいろ
複数のポイントクラウドを合成,ポイントクラウドを作る
近傍店探索
https://ppdr.softether.net/ros-pointcloud-zatxy
https://pcl.readthedocs.io/projects/tutorials/en/latest/kdtree_search.html
pointcloudの型変換(pointcloud2<->pointcloud)
一部の機能は型がpointcloud型でないといけない場合がある.その時はこれを使って変換する.https://ros-developer.com/2017/08/03/converting-pclpclpointcloud2-to-pclpointcloud-and-reverse/