包括的なPCLのチュートリアルのリストは、PCLの [[http://pointclouds.org/documentation/tutorials/|外部ウェブサイト]]で見ることができます.  あなたが見たいであろうものは以下のようなものがあると思います。


 * [[http://pointclouds.org/documentation/tutorials/reading_pcd.php|PCDファイルから点群データを読み込む]]
 * [[http://pointclouds.org/documentation/tutorials/voxel_grid.php#voxelgrid|点群データをVoxelGrid filterを用いてダウンサンプリングする。]]
 * [[http://pointclouds.org/documentation/tutorials/planar_segmentation.php|平面モデルの分割(segmentation)]]
 * [[http://pointclouds.org/documentation/tutorials/octree_change.php|認識されない点群データによる空間の変位検知]]
 * [[http://pointclouds.org/documentation/tutorials/resampling.php|polynomial reconstructionに基づくスムージングと法線推定]]
 * [[http://pointclouds.org/documentation/tutorials/greedy_projection.php|Fast triangulation of unordered point clouds]]
 * [[http://pointclouds.org/documentation/tutorials/template_alignment.php|Aligning object templates to a point cloud]]

{{{#!wiki red/solid
ROSにおけるpcl全般の更なる情報(例えば、point clouodデータの型, パブリッシュ/サブスクライブ)などは[[../Overview|ROS/PCL overview]]で見ることができます.
}}}

下記のチュートリアルでは既存のいずれかの http://pointclouds.org のチュートリアルをnodeやnodeletを用いるROS ecosystemでどのように使用するかについて説明します.

= How to use a PCL tutorial in ROS =

<<Buildsystem()>>

== ROSパッケージの作成 ==

{{{{{#!wiki buildsystem rosbuild
{{{
roscreate-pkg my_pcl_tutorial pcl pcl_ros roscpp sensor_msgs
}}}
}}}}}

{{{{{#!wiki buildsystem catkin
{{{
catkin_create_pkg my_pcl_tutorial pcl pcl_ros roscpp sensor_msgs
}}}
}}}}}

これで必要な依存性を持ったROSパッケージができます

== コードの骨組みの作成 ==

'''src/example.cpp'''という名前の空のファイルを作成して以下のコードを貼り付けましょう
{{{#!cplusplus
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
// PCL specific includes
#include <pcl/ros/conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>

ros::Publisher pub;

void 
cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input)
{
  // ... do data processing

  sensor_msgs::PointCloud2 output;
  // Publish the data
  pub.publish (output);
}

int
main (int argc, char** argv)
{
  // Initialize ROS
  ros::init (argc, argv, "my_pcl_tutorial");
  ros::NodeHandle nh;

  // Create a ROS subscriber for the input point cloud
  ros::Subscriber sub = nh.subscribe ("input", 1, cloud_cb);

  // Create a ROS publisher for the output point cloud
  pub = nh.advertise<sensor_msgs::PointCloud2> ("output", 1);

  // Spin
  ros::spin ();
}

}}}

上記のコードはROSを初期化しPointCloud2データへのサブスクライバとパブリシャを作るだけです

== CMakeLists.txtにソースファイルを追加する ==

あなたが新しく作成したパッケージのCMakeLists.txtを編集して下記を追加してください
{{{{{#!wiki buildsystem rosbuild
{{{
rosbuild_add_executable (example src/example.cpp)
}}}
}}}}}

{{{{{#!wiki buildsystem catkin
{{{
add_executable(example src/example.cpp)
target_link_libraries(example ${catkin_LIBRARIES})
}}}
}}}}}

== PCLチュートリアルからソースコードをダウンロードする ==

バージョン2.0までのすべてのPCLは点群データの2種類の表現法を持っています
 * '''sensor_msgs/PointCloud2'''ROSメッセージを通したもの
 * '''pcl/PointCloud<T>'''データ構造を通したもの

下記の2つのコード例は両方のフォーマットについて論じています

=== sensor_msgs/PointCloud2 ===

'''sensor_msgs/PointCloud2'''フォーマットはROSメッセージとして設計されており, ROSアプリケーションにはより好ましい選択です. 下記の例では3Dグリッドを用いてPointCloud2構造の解像度を下げ, 相当に入力データの点の数を減らしています.

上記のコードの骨組みにこの能力を持たせるために, 以下のステップを行ってください

 * http://www.pointclouds.org/documentation/ を訪れ, Tutorialsをクリックし, '''Downsampling a !PointCloud using a !VoxelGrid filter''' チュートリアルに行きましょう (http://www.pointclouds.org/documentation/tutorials/voxel_grid.php)
 
 * そこに用意されているコードと説明を読んでください. コードが本質的に3つの部分に分かれていることに気づくでしょう:

   * 点群の読み込み (lines 9-19)
   * 点群の処理 (lines 20-24)
   * 結果の保存 (lines 25-32)

 * 私たちは上記のコード片にてROSのサブスクライバとパブリシャを使うので, PCDフォーマットを用いる点群の読み込みと保存は気にする必要はありません. したがって, チュートリアルの残っている関係する部分は20-24行のPCLオブジェクトを作成し, 入力データを渡し, 実際の計算を行う部分だけです:
{{{#!cplusplus
  // Create the filtering object
  pcl::VoxelGrid<sensor_msgs::PointCloud2> sor;
  sor.setInputCloud (cloud);
  sor.setLeafSize (0.01, 0.01, 0.01);
  sor.filter (*cloud_filtered);
}}} 

これらの行では, 入力データは '''cloud'''と呼ばれ, 出力は'''cloud_filtered'''と呼ばれます. コールバック関数を下記のように書き換えて, これらの行を上のコード片にコピーしましょう:
{{{#!cplusplus
#include <pcl/filters/voxel_grid.h>

...

void 
cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud)
{
  sensor_msgs::PointCloud2 cloud_filtered;

  // Perform the actual filtering
  pcl::VoxelGrid<sensor_msgs::PointCloud2> sor;
  sor.setInputCloud (cloud);
  sor.setLeafSize (0.01, 0.01, 0.01);
  sor.filter (cloud_filtered);

  // Publish the data
  pub.publish (cloud_filtered);
}
}}}

{{{#!wiki caution

'''注'''

別のチュートリアルではしばしば各々異なった変数名を入出力に用いているので, チュートリアルのコードをあなた自身のROSノードに統合する場合はわずかにコードを変更する必要がある可能性があることを覚えておいてください. 今回の場合, コピーしたチュートリアルのコードと一致させるため変数名を'''input'''から'''cloud'''に, そして'''output'''から'''cloud_filtered'''に変更しなければならなかったことに注目してください

}}}

出力ファイルを保存してビルドしましょう:
{{{{{#!wiki buildsystem rosbuild
{{{
$ rosmake my_pcl_tutorial
}}}
}}}}}

{{{{{#!wiki buildsystem catkin
{{{
$ cd %TOP_DIR_YOUR_CATKIN_HOME%
$ catkin_make
}}}
}}}}}

そして動かしましょう:
{{{
rosrun my_pcl_tutorial example input:=/narrow_stereo_textured/points2
}}}

{{{#!wiki red/solid
もしコピーペーストしてを保存したいなら, この例のソースファイルをダウンロードできます[[attachment:example_voxelgrid.cpp|here]].
}}}

=== pcl/PointCloud<T> ===

'''pcl/PointCloud<T>''' フォーマットはPCL点群フォーマットの内部を表現します. モジュール性と効率性を考えて, フォーマットは点の種類によるテンプレートになっており, PCLはSSEで整列したテンプレートの共通型のリストを提供します. 以下の例では, シーン内で見つかったもっとも大きい平面のplanar係数を見積もります.

上のコード骨組みにこの能力を付加するため, 以下のステップにしたがってください:

 * http://www.pointclouds.org/documentation/ を訪れ, チュートリアルをクリックし, '''Planar model segmentation''' チュートリアルに行きましょう (http://www.pointclouds.org/documentation/tutorials/planar_segmentation.php)
 
 * そこで用意されているコードと説明を読みましょう. コードが本質的に3つの部分に分かれていることに気づくでしょう:

   * 点群を作成し値を付与する (lines 12-30)
   * 点群を処理する (lines 38-56)
   * 係数を書き出す (lines 58-68)

 * 私たちは上記コード片でROSサブスクライバを用いるので, 最初のステップは気にする必要はなく, 直接コールバックにて受け取った点群を処理すれば良いのです. そのため, チュートリアルで残っている部分は38-56行のPCLオブジェクトを作成し, 入力を渡し, 実際の計算を行う部分のみです:
{{{#!cplusplus
  pcl::ModelCoefficients coefficients;
  pcl::PointIndices inliers;
  // Create the segmentation object
  pcl::SACSegmentation<pcl::PointXYZ> seg;
  // Optional
  seg.setOptimizeCoefficients (true);
  // Mandatory
  seg.setModelType (pcl::SACMODEL_PLANE);
  seg.setMethodType (pcl::SAC_RANSAC);
  seg.setDistanceThreshold (0.01);

  seg.setInputCloud (cloud.makeShared ());
  seg.segment (inliers, coefficients);
}}} 

これらの行では, 入力データセットは'''cloud'''と呼ばれ, '''pcl::PointCloud<pcl::PointXYZ>'''型を持っており, 出力は平面が含む点のインデックスの集合とplane係数で表現されます. '''cloud.makeShared()''' は'''cloud'''オブジェクトへの [[http://www.boost.org/doc/libs/1_46_1/libs/smart_ptr/shared_ptr.htm|boost shared_ptr]] オブジェクトを生成します ([[http://docs.pointclouds.org/1.5.1/classpcl_1_1_point_cloud.html#a33ec29ee932707f593af9839eb37ea17|the pcl::PointCloud API]] ドキュメントを見てください). 

コールバック関数を下記のように書き換えて, これらの行を上記のコード片にコピーしましょう:
{{{#!cplusplus
#include <pcl/sample_consensus/model_types.h>
#include <pcl/sample_consensus/method_types.h>
#include <pcl/segmentation/sac_segmentation.h>

...

void 
cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input)
{
  // Convert the sensor_msgs/PointCloud2 data to pcl/PointCloud
  pcl::PointCloud<pcl::PointXYZ> cloud;
  pcl::fromROSMsg (*input, cloud);

  pcl::ModelCoefficients coefficients;
  pcl::PointIndices inliers;
  // Create the segmentation object
  pcl::SACSegmentation<pcl::PointXYZ> seg;
  // Optional
  seg.setOptimizeCoefficients (true);
  // Mandatory
  seg.setModelType (pcl::SACMODEL_PLANE);
  seg.setMethodType (pcl::SAC_RANSAC);
  seg.setDistanceThreshold (0.01);

  seg.setInputCloud (cloud.makeShared ());
  seg.segment (inliers, coefficients);

  // Publish the model coefficients
  pub.publish (coefficients);
}
}}}

{{{#!wiki caution
  私たちは最初の2行で '''sensor_msgs/PointCloud2''' から '''pcl/PointCloud<T>''' への変換ステップを追加し, また発行する変数名を '''output''' から '''coefficients'''に変更したことに注目してください.
}}}

加えて, 今私たちは点群データよりもplanar model係数を発行しているので, パブリシャの型を

{{{
  // Create a ROS publisher for the output point cloud
  pub = nh.advertise<sensor_msgs::PointCloud2> ("output", 1);
}}}
から:
{{{
  // Create a ROS publisher for the output model coefficients
  pub = nh.advertise<pcl::ModelCoefficients> ("output", 1);
}}}

へ変えましょう.

出力ファイルを保存して, 上記のコードをコンパイルして動かしましょう:
{{{
rosrun my_pcl_tutorial example input:=/narrow_stereo_textured/points2
}}}

{{{#!wiki red/solid
先の例と同様, もし少しの手間を省きたければ, この例のソースファイルをダウンロードすることができます[[attachment:example_planarsegmentation.cpp|here]].
}}}