ROS机器人程序设计(原书第2版)补充资料 (陆) 第六章 点云 PCL

书中,大部分出现hydro的地方,直接替换为indigo或jade或kinetic,即可在对应版本中使用。

RGBD深度摄像头传感器最常用的数据存储,处理和显示方式就是点云。

推荐查阅-PCL官网:http://www.pointclouds.org/

1. http://wiki.ros.org/pcl_ros 2. http://wiki.ros.org/pcl

补充阅读:

1 http://blog.csdn.net/zhangrelay/article/details/50053733

2 http://blog.csdn.net/zhangrelay/article/details/50240935

第163页:

简介点云。

第163-165页:

理解点云,包括类型,算法和接口等。

第166-190页:

学习在ROS使用PCL,包括创建点云,可视化,滤波,缩减采样,配准,匹配,分区,分割等。

第191页:

本章小结。

  

思考与巩固:

1 使用深度摄像头采集环境信息,并用点云显示,用本章提及的方法进行处理。

2 在ROSwiki上查阅点云相关功能包并完成编译使用。

附:

How to use a PCL tutorial in ROS

目录

  1. How to use a PCL tutorial in ROS

    1. Create a ROS package
    2. Create the code skeleton
    3. Add the source file to CMakeLists.txt
    4. Download the source code from the PCL tutorial
      1. sensor_msgs/PointCloud2
      2. pcl/PointCloud<T>

Create a ROS package

$ catkin_create_pkg my_pcl_tutorial pcl_conversions pcl_ros roscpp sensor_msgs 

Then, modify the package.xml to add

  <build_depend>libpcl-all-dev</build_depend>
  <run_depend>libpcl-all</run_depend>

Create the code skeleton

Create an empty file called src/example.cpp and paste the following code in it:

切换行号显示

   1 #include <ros/ros.h>
   2 // PCL specific includes
   3 #include <sensor_msgs/PointCloud2.h>
   4 #include <pcl_conversions/pcl_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   // Create a container for the data.
  14   sensor_msgs::PointCloud2 output;
  15
  16   // Do data processing here...
  17   output = *input;
  18
  19   // Publish the data.
  20   pub.publish (output);
  21 }
  22
  23 int
  24 main (int argc, char** argv)
  25 {  26   // Initialize ROS
  27   ros::init (argc, argv, "my_pcl_tutorial");
  28   ros::NodeHandle nh;
  29
  30   // Create a ROS subscriber for the input point cloud
  31   ros::Subscriber sub = nh.subscribe ("input", 1, cloud_cb);
  32
  33   // Create a ROS publisher for the output point cloud
  34   pub = nh.advertise<sensor_msgs::PointCloud2> ("output", 1);
  35
  36   // Spin
  37   ros::spin ();
  38 }

The code above does nothing but initialize ROS, create a subscriber and a publisher for PointCloud2 data.

Add the source file to CMakeLists.txt

Edit the CMakeLists.txt file in your newly created package and add:

add_executable(example src/example.cpp)
target_link_libraries(example ${catkin_LIBRARIES})

Download the source code from the PCL tutorial

PCL has about four different ways of representing point cloud data, so it can get a bit confusing, but we'll try to keep it simple for you. The types are:

  • sensor_msgs::PointCloud — ROS message (deprecated)

  • sensor_msgs::PointCloud2 — ROS message

  • pcl::PCLPointCloud2 — PCL data structure mostly for compatibility with ROS (I think)

  • pcl::PointCloud<T> — standard PCL data structure

In the following code examples we will focus on the ROS message (sensor_msgs::PointCloud2) and the standard PCL data structure (pcl::PointCloud<T>). However, you should also note that pcl::PCLPointCloud2 is an important and useful type as well: you can directly subscribe to nodes using that type and it will be automatically serialized to/from the sensor_msgs type. See this example to try PCLPointCloud2 yourself.

sensor_msgs/PointCloud2

If you'd like to save yourself some copying and pasting, you can download the source file for this example here. Just remember to rename the file to example.cpp or edit your CMakeLists.txt to match.

The sensor_msgs/PointCloud2 format was designed as a ROS message, and is the preferred choice for ROS applications. In the following example, we downsample a PointCloud2 structure using a 3D grid, thus reducing the number of points in the input dataset considerably.

To add this capability to the code skeleton above, perform the following steps:

  • visit http://www.pointclouds.org/documentation/, click on Tutorials, then navigate to the Downsampling a PointCloud using a VoxelGrid filter tutorial (http://www.pointclouds.org/documentation/tutorials/voxel_grid.php)

  • read the code and the explanations provided there. You will notice that the code breaks down essentially in 3 parts: 
    • load the cloud (lines 9-19)
    • process the cloud (lines 20-24)
    • save the output (lines 25-32)
  • since we use ROS subscribers and publishers in our code snippet above, we can ignore the loading and saving of point cloud data using the PCD format. Thus, the only relevant part in the tutorial remains lines 20-24 that create the PCL object, pass the input data, and perform the actual computation:
切换行号显示

   1   // Create the filtering object
   2   pcl::VoxelGrid<pcl::PCLPointCloud2> sor;
   3   sor.setInputCloud (cloud);
   4   sor.setLeafSize (0.01, 0.01, 0.01);
   5   sor.filter (*cloud_filtered);

  • In these lines, the input dataset is named cloud, and the output dataset is called cloud_filtered. We can copy this work, but remember from earlier that we said we wanted to work with the sensor_msgs class, not the pcl class. In order to do this, we're going to have to do a little bit of extra work to convert the ROS message to the PCL type. Modify the callback function as follows:

切换行号显示

   1 #include <pcl/filters/voxel_grid.h>
   2
   3 ...
   4
   5 void
   6 cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud_msg)
   7 {   8   // Container for original & filtered data
   9   pcl::PCLPointCloud2* cloud = new pcl::PCLPointCloud2;
  10   pcl::PCLPointCloud2ConstPtr cloudPtr(cloud);
  11   pcl::PCLPointCloud2 cloud_filtered;
  12
  13   // Convert to PCL data type
  14   pcl_conversions::toPCL(*cloud_msg, *cloud);
  15
  16   // Perform the actual filtering
  17   pcl::VoxelGrid<pcl::PCLPointCloud2> sor;
  18   sor.setInputCloud (cloudPtr);
  19   sor.setLeafSize (0.1, 0.1, 0.1);
  20   sor.filter (cloud_filtered);
  21
  22   // Convert to ROS data type
  23   sensor_msgs::PointCloud2 output;
  24   pcl_conversions::fromPCL(cloud_filtered, output);
  25
  26   // Publish the data
  27   pub.publish (output);
  28 }

Note

Since different tutorials will often use different variable names for their inputs and outputs, remember that you may need to modify the code slightly when integrating the tutorial code into your own ROS node. In this case, notice that we had to change the variable name input to cloud, and output to cloud_filtered in order to match up with the code from the tutorial we copied.

Note that there is a slight inefficiency here. The fromPCL can be replaced with moveFromPCL to prevent copying the entire (filtered) point cloud. However, the toPCL call cannot be optimized in this way since the original input is const.

Save the output file then build:

$ cd %TOP_DIR_YOUR_CATKIN_HOME%
$ catkin_make

Then run:

$ rosrun my_pcl_tutorial example input:=/narrow_stereo_textured/points2

or, if you're running an OpenNI-compatible depth sensor, try:

$ roslaunch openni_launch openni.launch
$ rosrun my_pcl_tutorial example input:=/camera/depth/points

You can visualize the result by running RViz:

$ rosrun rviz rviz

and adding a "PointCloud2" display. Select camera_depth_frame for the Fixed Frame (or whatever frame is appropriate for your sensor) and select output for the PointCloud2 topic. You should see a highly downsampled point cloud. For comparison, you can view the /camera/depth/points topic and see how much it has been downsampled.

pcl/PointCloud<T>

As with the previous example, if you want to skip a few steps, you can download the source file for this example here.

The pcl/PointCloud<T> format represents the internal PCL point cloud format. For modularity and efficiency reasons, the format is templated on the point type, and PCL provides a list of templated common types which are SSE aligned. In the following example, we estimate the planar coefficients of the largest plane found in a scene.

To add this capability to the code skeleton above, perform the following steps:

  • visit http://www.pointclouds.org/documentation/, click on Tutorials, then navigate to the Planar model segmentation tutorial (http://www.pointclouds.org/documentation/tutorials/planar_segmentation.php)

  • read the code and the explanations provided there. You will notice that the code breaks down essentially in 3 parts: 
    • create a cloud and populate it with values (lines 12-30)
    • process the cloud (38-56)
    • write the coefficients (58-68)
  • since we use ROS subscribers in our code snippet above, we can ignore the first step, and just process the cloud received on the callback directly. Thus, the only relevant part in the tutorial remains lines 38-56 that create the PCL object, pass the input data, and perform the actual computation:
切换行号显示

   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);

  • In these lines, the input dataset is named cloud and is of type pcl::PointCloud<pcl::PointXYZ>, and the output is represented by a set of point indices that contain the plane together with the plane coefficients. cloud.makeShared()creates a boost shared_ptr object for the object cloud (see the pcl::PointCloud API documentation).

Copy these lines, in the code snippet above, by modifying the callback function as follows:

切换行号显示

   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   pcl_msgs::ModelCoefficients ros_coefficients;
  30   pcl_conversions::fromPCL(coefficients, ros_coefficients);
  31   pub.publish (ros_coefficients);
  32 }

Notice that we added two conversion steps: from sensor_msgs/PointCloud2 to pcl/PointCloud<T>and from pcl::ModelCoefficients to pcl_msgs::ModelCoefficients. We also changed the variable that we publish from output to coefficients.

In addition, since we're now publishing the planar model coefficients found rather than point cloud data, we have to change our publisher type from:

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

to:

  // Create a ROS publisher for the output model coefficients
  pub = nh.advertise<pcl_msgs::ModelCoefficients> ("output", 1);

Save the output file, then compile and run the code above:

$ rosrun my_pcl_tutorial example input:=/narrow_stereo_textured/points2

or, if you're running an OpenNI-compatible depth sensor, try:

$ rosrun my_pcl_tutorial example input:=/camera/depth/points

See the output with

$ rostopic echo output
-End-

ROS机器人程序设计(原书第2版)补充资料 (陆) 第六章 点云 PCL相关推荐

  1. objective-c 2.0编程语言,Objective-C 2.0程序设计(原书第2版) 中文PDF扫描版[15MB]

    Objective-C 2.0程序设计(原书第2版)  内容简介: 本书是Objective-C领域的经典著作,对 Objective-C进行了系统而全面的阐述,权威性毋庸置疑.全书共分为四大部分:第 ...

  2. 《深入理解Hadoop(原书第2版)》——2.6本章小结

    本节书摘来自华章计算机<深入理解Hadoop(原书第2版)>一书中的第2章,第2.6节,作者 [美]萨米尔·瓦德卡(Sameer Wadkar),马杜·西德林埃(Madhu Siddali ...

  3. 《面向对象的思考过程(原书第4版)》一 第2章 如何以面向对象的方式进行思考...

    本节书摘来自华章出版社<面向对象的思考过程(原书第4版)>一书中的第2章,[美] 马特·魏斯费尔德(Matt Weisfeld) 著黄博文 译更多章节内容可以访问云栖社区"华章计 ...

  4. 《计算机网络:自顶向下方法(原书第6版)》一第1章

    本节书摘来华章计算机<计算机网络:自顶向下方法(原书第6版)>一书中的第1章 ,第1.1节,(美)James F.Kurose Keith W.Ross 著 陈 鸣 译 更多章节内容可以访 ...

  5. 《深入理解Elasticsearch(原书第2版)》一第1章

    本节书摘来华章计算机<深入理解Elasticsearch(原书第2版)>一书中的第1章 ,[美]拉斐尔·酷奇(Rafal Ku) 马雷克·罗戈任斯基(Marek Rogoziski)著 张 ...

  6. 《数论概论(原书第4版)》一第2章 勾 股 数 组

    本节书摘来自华章出版社<数论概论(原书第4版)>一书中的第2章,作者 布朗大学,更多章节内容可以访问云栖社区"华章计算机"公众号查看 第2章 勾 股 数 组 毕达哥拉斯 ...

  7. 编写python程序、计算账户余额_《计算机科学丛书PYTHON程序设计(原书第2版)/(美])凯.S.霍斯特曼》【价格 目录 书评 正版】_中国图书网...

    出版者的话 译者序 前言 第1章 概述 1 1.1 计算机程序 1 1.2 深入剖析计算机 2 1.3 Python编程语言 4 1.4 熟悉编程环境 5 1.5 分析**个程序 9 1.6 错误 1 ...

  8. ROS机器人程序设计(原书第2版).

    机器人设计与制作系列 ROS机器人程序设计 (原书第2版) Learning ROS for Robotics Programming,Second Edition 恩里克·费尔南德斯(Enrique ...

  9. ROS机器人程序设计部分大纲-适用于蓝桥云课及ROS1 KINETIC/MELODIC/NOETIC

    ROS机器人程序设计 ROS robot programming 课程编号 16300021 学分 3 开课学期 6 学时 讲课:32学时      实验:16 学时       实践:0学时 课程类 ...

最新文章

  1. Java动态代理机制
  2. freeMarker语法
  3. android加固多渠道,Android 多渠道打包(使用友盟统计,结合360加固宝进行多渠道打包)...
  4. 【转】makefile写法2
  5. mybatis针对mysql自增主键怎样配置mapper
  6. OpenCV视频中的人脸标志检测
  7. android优化最强软件,最强大的安卓优化工具诞生,让手机流畅度提升75%
  8. 数据结构--栈 codevs 1107 等价表达式
  9. 基于CSE的微服务工程实践-多微服务框架演进
  10. (25)FPGA工程师与其他工程师交集(FPGA不积跬步101)
  11. Linux内核将用Nftables替代iptables
  12. 了解Spring AOP吗
  13. k邻近算法应用实例(一) 改进约会网站的配对效果
  14. NBU备份数据库时的ORA-27211错误分析解决
  15. rubygems 安装mysql时出错_Ruby gem install mysql 错误解决
  16. java虚拟机内存_java虚拟机内存区域的划分以及作用详解
  17. mapgis 6.7视频教程
  18. 单词语音音标正则式查询分析JavaScript应用
  19. 扫一下这个神奇的二维码,Wifi不用输密码
  20. ajax英文翻译,Ajax[埃阿斯]英文名的中文翻译意思、发音、来源及流行趋势-千代英文名...

热门文章

  1. Niushop3.0 店铺模块
  2. 闪兼云谈谈网赚所需的一些必备技术
  3. 炮兵阵地(状态压缩DP)
  4. 基于HAL库手写一个轻量化操作系统——参考ucos
  5. 网络AFNetworking 3.1
  6. 零基础入门UI设计,如何提升审美能力呢?
  7. 第4章 R语言编程基础——数据整理与预处理
  8. 语法俱乐部5:复合句和简化句
  9. 江苏金丰机电参观学习有感
  10. 中国特产 强悍的假冒品牌【转】