其他操作

导出点云

ROS与PCL相关教程

通过命令行

方法1:使用bag_to_pcd详见此链接

rosrun pcl_ros bag_to_pcd <input_file.bag> <topic> <output_directory>

$ rosrun pcl_ros bag_to_pcd data.bag /stereo/points2 ./pcd_folder

方法2:(推荐)使用pointcloud_to_pcd实时捕获,详见此链接

$ rosrun pcl_ros pointcloud_to_pcd input:=/stereo/points2

此命令会实时将指定话题的点云保存到当前目录,所以要注意使用Ctrl+C停止

通过代码

  • 获取点云
#include "pcl/io/pcd_io.h"
#include "pcl/point_cloud.h"
#include "pcl/point_types.h"
#include "pcl_conversions/pcl_conversions.h"
#include "ros/ros.h"
#include "sensor_msgs/PointCloud2.h"

static size_t counter = 0;

void SubscribePointCloud(const sensor_msgs::PointCloud2ConstPtr& message) {
  pcl::PointCloud<pcl::PointXYZI> point_cloud;
  pcl::fromROSMsg(*message, point_cloud);

  counter++;
  std::string file_name = "point_cloud_" + std::to_string(counter) + ".pcd";
  pcl::io::savePCDFile(file_name, point_cloud);
}

int main(int argc, char **argv) {
  ros::init(argc, argv, "point_cloud_subscriber");
  ros::NodeHandle node_handle;
  ros::Subscriber point_cloud_sub = 
    node_handle.subscribe("/stereo/points2", 1, SubscribePointCloud);
  ros::spin();

  return 0;
}
  • 发布点云
#include <ros/ros.h>
#include <pcl/point_cloud.h>
#include <pcl_conversions/pcl_conversions.h>
#include <sensor_msgs/PointCloud2.h>

main (int argc, char **argv)
{
    ros::init (argc, argv, "pcl_create");

    ros::NodeHandle nh;
    ros::Publisher pcl_pub = nh.advertise<sensor_msgs::PointCloud2> ("pcl_output", 1);
    pcl::PointCloud<pcl::PointXYZ> cloud;
    sensor_msgs::PointCloud2 output;

    // Fill in the cloud data
    cloud.width  = 100;
    cloud.height = 1;
    cloud.points.resize(cloud.width * cloud.height);

    for (size_t i = 0; i < cloud.points.size (); ++i)
    {
        cloud.points[i].x = 1024 * rand () / (RAND_MAX + 1.0f);
        cloud.points[i].y = 1024 * rand () / (RAND_MAX + 1.0f);
        cloud.points[i].z = 1024 * rand () / (RAND_MAX + 1.0f);
    }

    //Convert the cloud to ROS message
    pcl::toROSMsg(cloud, output);
    output.header.frame_id = "odom";

    ros::Rate loop_rate(1);
    while (ros::ok())
    {
        pcl_pub.publish(output);
        ros::spinOnce();
        loop_rate.sleep();
    }

    return 0;
}

使用pcl工具查看点云

pcl_viewer xxxx.pcd

其他

  • USB通讯数据抓取工具:BusHound
  • 协议:UVC(USB Video Class)
  • Windows软件:CHUSEI 3D Camera

  • 发布pcd到rviz:

rosrun pcl_ros pcd_to_pointcloud <file.pcd> [ <interval> ]

rosrun pcl_ros pcd_to_pointcloud rops_cloud.pcd 10 _frame_id:=/map