包括的なPCLのチュートリアルのリストは、PCLの 外部ウェブサイトで見ることができます. あなたが見たいであろうものは以下のようなものがあると思います。
ROSにおけるpcl全般の更なる情報(例えば、point clouodデータの型, パブリッシュ/サブスクライブ)などはROS/PCL overviewで見ることができます.
下記のチュートリアルでは既存のいずれかの http://pointclouds.org のチュートリアルをnodeやnodeletを用いるROS ecosystemでどのように使用するかについて説明します.
How to use a PCL tutorial in ROS
ROSパッケージの作成
roscreate-pkg my_pcl_tutorial pcl pcl_ros roscpp sensor_msgs
catkin_create_pkg my_pcl_tutorial pcl pcl_ros roscpp sensor_msgs
これで必要な依存性を持ったROSパッケージができます
コードの骨組みの作成
src/example.cppという名前の空のファイルを作成して以下のコードを貼り付けましょう
   1 #include <ros/ros.h>
   2 #include <sensor_msgs/PointCloud2.h>
   3 // PCL specific includes
   4 #include <pcl/ros/conversions.h>
   5 #include <pcl/point_cloud.h>
   6 #include <pcl/point_types.h>
   7 
   8 ros::Publisher pub;
   9 
  10 void 
  11 cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input)
  12 {
  13   // ... do data processing
  14 
  15   sensor_msgs::PointCloud2 output;
  16   // Publish the data
  17   pub.publish (output);
  18 }
  19 
  20 int
  21 main (int argc, char** argv)
  22 {
  23   // Initialize ROS
  24   ros::init (argc, argv, "my_pcl_tutorial");
  25   ros::NodeHandle nh;
  26 
  27   // Create a ROS subscriber for the input point cloud
  28   ros::Subscriber sub = nh.subscribe ("input", 1, cloud_cb);
  29 
  30   // Create a ROS publisher for the output point cloud
  31   pub = nh.advertise<sensor_msgs::PointCloud2> ("output", 1);
  32 
  33   // Spin
  34   ros::spin ();
  35 }
上記のコードはROSを初期化しPointCloud2データへのサブスクライバとパブリシャを作るだけです
CMakeLists.txtにソースファイルを追加する
あなたが新しく作成したパッケージのCMakeLists.txtを編集して下記を追加してください
rosbuild_add_executable (example src/example.cpp)
add_executable(example src/example.cpp)
target_link_libraries(example ${catkin_LIBRARIES})
PCLチュートリアルからソースコードをダウンロードする
バージョン2.0までのすべてのPCLは点群データの2種類の表現法を持っています
- sensor_msgs/PointCloud2ROSメッセージを通したもの 
- 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オブジェクトを作成し, 入力データを渡し, 実際の計算を行う部分だけです:
これらの行では, 入力データは cloudと呼ばれ, 出力はcloud_filteredと呼ばれます. コールバック関数を下記のように書き換えて, これらの行を上のコード片にコピーしましょう:
   1 #include <pcl/filters/voxel_grid.h>
   2 
   3 ...
   4 
   5 void 
   6 cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud)
   7 {
   8   sensor_msgs::PointCloud2 cloud_filtered;
   9 
  10   // Perform the actual filtering
  11   pcl::VoxelGrid<sensor_msgs::PointCloud2> sor;
  12   sor.setInputCloud (cloud);
  13   sor.setLeafSize (0.01, 0.01, 0.01);
  14   sor.filter (cloud_filtered);
  15 
  16   // Publish the data
  17   pub.publish (cloud_filtered);
  18 }
注
別のチュートリアルではしばしば各々異なった変数名を入出力に用いているので, チュートリアルのコードをあなた自身のROSノードに統合する場合はわずかにコードを変更する必要がある可能性があることを覚えておいてください. 今回の場合, コピーしたチュートリアルのコードと一致させるため変数名をinputからcloudに, そしてoutputからcloud_filteredに変更しなければならなかったことに注目してください
出力ファイルを保存してビルドしましょう:
$ rosmake my_pcl_tutorial
$ cd %TOP_DIR_YOUR_CATKIN_HOME% $ catkin_make
そして動かしましょう:
rosrun my_pcl_tutorial example input:=/narrow_stereo_textured/points2
もしコピーペーストしてを保存したいなら, この例のソースファイルをダウンロードできます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オブジェクトを作成し, 入力を渡し, 実際の計算を行う部分のみです:
   1   pcl::ModelCoefficients coefficients;
   2   pcl::PointIndices inliers;
   3   // Create the segmentation object
   4   pcl::SACSegmentation<pcl::PointXYZ> seg;
   5   // Optional
   6   seg.setOptimizeCoefficients (true);
   7   // Mandatory
   8   seg.setModelType (pcl::SACMODEL_PLANE);
   9   seg.setMethodType (pcl::SAC_RANSAC);
  10   seg.setDistanceThreshold (0.01);
  11 
  12   seg.setInputCloud (cloud.makeShared ());
  13   seg.segment (inliers, coefficients);
これらの行では, 入力データセットはcloudと呼ばれ, pcl::PointCloud<pcl::PointXYZ>型を持っており, 出力は平面が含む点のインデックスの集合とplane係数で表現されます. cloud.makeShared() はcloudオブジェクトへの boost shared_ptr オブジェクトを生成します (the pcl::PointCloud API ドキュメントを見てください).
コールバック関数を下記のように書き換えて, これらの行を上記のコード片にコピーしましょう:
   1 #include <pcl/sample_consensus/model_types.h>
   2 #include <pcl/sample_consensus/method_types.h>
   3 #include <pcl/segmentation/sac_segmentation.h>
   4 
   5 ...
   6 
   7 void 
   8 cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input)
   9 {
  10   // Convert the sensor_msgs/PointCloud2 data to pcl/PointCloud
  11   pcl::PointCloud<pcl::PointXYZ> cloud;
  12   pcl::fromROSMsg (*input, cloud);
  13 
  14   pcl::ModelCoefficients coefficients;
  15   pcl::PointIndices inliers;
  16   // Create the segmentation object
  17   pcl::SACSegmentation<pcl::PointXYZ> seg;
  18   // Optional
  19   seg.setOptimizeCoefficients (true);
  20   // Mandatory
  21   seg.setModelType (pcl::SACMODEL_PLANE);
  22   seg.setMethodType (pcl::SAC_RANSAC);
  23   seg.setDistanceThreshold (0.01);
  24 
  25   seg.setInputCloud (cloud.makeShared ());
  26   seg.segment (inliers, coefficients);
  27 
  28   // Publish the model coefficients
  29   pub.publish (coefficients);
  30 }
- 私たちは最初の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
先の例と同様, もし少しの手間を省きたければ, この例のソースファイルをダウンロードすることができますhere.
