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

补充阅读:

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

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

Create a ROS package

  1. $ catkin_create_pkg my_pcl_tutorial pcl_conversions pcl_ros roscpp sensor_msgs

Then, modify the package.xml to add

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

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

  1. $ cd %TOP_DIR_YOUR_CATKIN_HOME%
  2. $ catkin_make

Then run:

  1. $ rosrun my_pcl_tutorial example input:=/narrow_stereo_textured/points2

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

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

You can visualize the result by running RViz:

  1. $ 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. 1 pcl::ModelCoefficients coefficients;
  2. 2 pcl::PointIndices inliers;
  3. 3 // Create the segmentation object
  4. 4 pcl::SACSegmentation<pcl::PointXYZ> seg;
  5. 5 // Optional
  6. 6 seg.setOptimizeCoefficients (true);
  7. 7 // Mandatory
  8. 8 seg.setModelType (pcl::SACMODEL_PLANE);
  9. 9 seg.setMethodType (pcl::SAC_RANSAC);
  10. 10 seg.setDistanceThreshold (0.01);
  11. 11
  12. 12 seg.setInputCloud (cloud.makeShared ());
  13. 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. 1 #include <pcl/sample_consensus/model_types.h>
  2. 2 #include <pcl/sample_consensus/method_types.h>
  3. 3 #include <pcl/segmentation/sac_segmentation.h>
  4. 4
  5. 5 ...
  6. 6
  7. 7 void
  8. 8 cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input)
  9. 9 {
  10. 10 // Convert the sensor_msgs/PointCloud2 data to pcl/PointCloud
  11. 11 pcl::PointCloud<pcl::PointXYZ> cloud;
  12. 12 pcl::fromROSMsg (*input, cloud);
  13. 13
  14. 14 pcl::ModelCoefficients coefficients;
  15. 15 pcl::PointIndices inliers;
  16. 16 // Create the segmentation object
  17. 17 pcl::SACSegmentation<pcl::PointXYZ> seg;
  18. 18 // Optional
  19. 19 seg.setOptimizeCoefficients (true);
  20. 20 // Mandatory
  21. 21 seg.setModelType (pcl::SACMODEL_PLANE);
  22. 22 seg.setMethodType (pcl::SAC_RANSAC);
  23. 23 seg.setDistanceThreshold (0.01);
  24. 24
  25. 25 seg.setInputCloud (cloud.makeShared ());
  26. 26 seg.segment (inliers, coefficients);
  27. 27
  28. 28 // Publish the model coefficients
  29. 29 pcl_msgs::ModelCoefficients ros_coefficients;
  30. 30 pcl_conversions::fromPCL(coefficients, ros_coefficients);
  31. 31 pub.publish (ros_coefficients);
  32. 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:

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

to:

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

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

  1. $ rosrun my_pcl_tutorial example input:=/narrow_stereo_textured/points2

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

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

See the output with

  1. $ rostopic echo output
-End-

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

  1. ROS机器人程序设计(原书第2版)补充资料 教学大纲

    ROS机器人程序设计(原书第2版) 补充资料 教学大纲 针对该书稍后会补充教学大纲.教案.多媒体课件以及练习题等. <ROS机器人程序设计>课程简介 课程编号:XXXXXX 课程名称:RO ...

  2. ROS机器人程序设计(原书第2版)补充资料 (拾) 第十章 使用MoveIt!

    ROS机器人程序设计(原书第2版)补充资料 (拾) 第十章 使用MoveIt! 书中,大部分出现hydro的地方,直接替换为indigo或jade或kinetic,即可在对应版本中使用. MoveIt ...

  3. ROS机器人程序设计(原书第2版)补充资料 (玖) 第九章 导航功能包集进阶 navigation

    ROS机器人程序设计(原书第2版)补充资料 (玖) 第九章 导航功能包集进阶 navigation 书中,大部分出现hydro的地方,直接替换为indigo或jade或kinetic,即可在对应版本中 ...

  4. ROS机器人程序设计(原书第2版)补充资料 (零) 源代码、资料和印刷错误修订等 2017年01月01日更新

    ROS机器人程序设计(原书第2版)补充资料 (零) 源代码等 ROS官网 版)部分内容修订 页:第1行,删去$ 页:第6行,float64 y 前面加一个空格 页:中间创建主题:下面程序不用换行,(& ...

  5. ROS机器人程序设计(原书第2版)学习镜像分享及使用说明

    ROS机器人程序设计(原书第2版)学习镜像分享及使用说明 系统用于ROS爱好者学习交流,也可用于其他用途,并不局限于ROS. 这款镜像文件是基于一年前的Ubuntu ROS Arduino Gazeb ...

  6. ROS机器人程序设计(原书第2版)补充资料 (捌) 第八章 导航功能包集入门 navigation

    ROS机器人程序设计(原书第2版)补充资料 (捌) 第八章 导航功能包集入门 navigation 书中,大部分出现hydro的地方,直接替换为indigo或jade或kinetic,即可在对应版本中 ...

  7. ROS机器人程序设计(原书第2版)补充资料 (柒) 第七章 3D建模与仿真 urdf Gazebo V-Rep Webots Morse

    ROS机器人程序设计(原书第2版)补充资料 (柒) 第七章 3D建模与仿真 urdf Gazebo V-Rep Webots Morse 书中,大部分出现hydro的地方,直接替换为indigo或ja ...

  8. ROS机器人程序设计(原书第2版)补充资料 (伍) 第五章 计算机视觉

    ROS机器人程序设计(原书第2版)补充资料 (伍) 第五章 计算机视觉 书中,大部分出现hydro的地方,直接替换为indigo或jade或kinetic,即可在对应版本中使用. 计算机视觉这章分为两 ...

  9. ROS机器人程序设计(原书第2版)补充资料 (肆) 第四章 在ROS下使用传感器和执行器

    ROS机器人程序设计(原书第2版)补充资料 (肆) 第四章 在ROS使用传感器和执行器 书中,大部分出现hydro的地方,直接替换为indigo或jade或kinetic,即可在对应版本中使用. 第四 ...

随机推荐

  1. win7下ubuntu14.4双系统安装

    参考https://jingyan.baidu.com/article/f71d60379824041ab641d19d.html

  2. testng执行多个suite

    由于testng.xml中只能设置一个<suite>标签,就无法创建多个测试集,通过<suite-files >标签可以实现允许多个测试集. 1.testng.xml中引入多个 ...

  3. CentOS6.9安装

    我安装在VM的虚拟机中.具体安装方式网上很多,由于本机只能安装32位的linux系统,所以悬在了Centsos6.9版本.点此下载. 其中有一种是叫做LIVEDVD的版本,这种的值虚拟机中配置后,打开 ...

  4. 计蒜客NOIP模拟赛(3)D1T3 任性的国王

    X 国的地图可以被看作一个两行 nn 列的网格状图.现在 X 国需要修建铁路,然而该国的国王非常小气,他只想保证位于某两列之间的所有城市互相可以到达就行了,在此基础上,他希望所花费的代价最小. 铁路可 ...

  5. epoll源码分析(转)

    在create后会创建eventpoll对象保存在一个匿名fd的file struct的private指针中,然后进程睡在等待队列上面. 对于等待的fd,通过poll机制在准备好之后会调用相应的cal ...

  6. 【网络流】【BZOJ1061】【NOI2008】志愿者招募

    原题链接:http://www.lydsy.com/JudgeOnline/problem.php?id=1061 题意:问你如何购买志愿者使得满足题意的总费用最小. 解题思路:首先,由于志愿者存在的 ...

  7. 【bzoj4008 hnoi2015】 亚瑟王

    题目描述 小 K 不慎被 LL 邪教洗脑了,洗脑程度深到他甚至想要从亚瑟王邪教中脱坑.他决定,在脱坑之前,最后再来打一盘亚瑟王.既然是最后一战,就一定要打得漂亮.众所周知,亚瑟王是一个看脸的游戏,技能 ...

  8. ●BZOJ 2329 [HNOI2011]括号修复.cpp

    题链: http://www.lydsy.com/JudgeOnline/problem.php?id=2329 题解: Splay 类似 BZOJ 2329 [HNOI2011]括号修复 只是多了一 ...

  9. HDU2303(数论)大整数求余+素数筛选

    Sample Input 143 10 143 20 667 20 667 30 2573 30 2573 40 0 0   Sample Output GOOD BAD 11 GOOD BAD 23 ...

  10. 【吃炸弹的鸽子UVA10765-双联通模板】

    ·从前有一个鸽子Lence,它吃了一个炸弹,然后有人出了这道题. ·英文题,述大意:        给出一张连通无向图,求出:对于每个点,删去这个点(以及它相连的边以后)时,当前图中的连通块数量,这个 ...