convert_pointcloud_to_image.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: surface_convex_hull.cpp 34612 2010-12-08 01:06:27Z rusu $
00035  *
00036  */
00037 
00041 // ROS core
00042 #include <ros/ros.h>
00043 //Image message
00044 #include <sensor_msgs/Image.h>
00045 #include <sensor_msgs/PointCloud2.h>
00046 //pcl::toROSMsg
00047 #include <pcl/io/pcd_io.h>
00048 //conversions from PCL custom types
00049 #include <pcl_conversions/pcl_conversions.h>
00050 //stl stuff
00051 #include <string>
00052 
00053 class PointCloudToImage
00054 {
00055 public:
00056   void
00057   cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud)
00058   {
00059     if (cloud->height <= 1)
00060     {
00061       ROS_ERROR("Input point cloud is not organized, ignoring!");
00062       return;
00063     }
00064     try
00065     {
00066       pcl::toROSMsg (*cloud, image_); //convert the cloud
00067       image_.header = cloud->header;
00068       image_pub_.publish (image_); //publish our cloud image
00069     }
00070     catch (std::runtime_error &e)
00071     {
00072       ROS_ERROR_STREAM("Error in converting cloud to image message: "
00073                         << e.what());
00074     }
00075   }
00076   PointCloudToImage () : cloud_topic_("input"),image_topic_("output")
00077   {
00078     sub_ = nh_.subscribe (cloud_topic_, 30,
00079                           &PointCloudToImage::cloud_cb, this);
00080     image_pub_ = nh_.advertise<sensor_msgs::Image> (image_topic_, 30);
00081 
00082     //print some info about the node
00083     std::string r_ct = nh_.resolveName (cloud_topic_);
00084     std::string r_it = nh_.resolveName (image_topic_);
00085     ROS_INFO_STREAM("Listening for incoming data on topic " << r_ct );
00086     ROS_INFO_STREAM("Publishing image on topic " << r_it );
00087   }
00088 private:
00089   ros::NodeHandle nh_;
00090   sensor_msgs::Image image_; //cache the image message
00091   std::string cloud_topic_; //default input
00092   std::string image_topic_; //default output
00093   ros::Subscriber sub_; //cloud subscriber
00094   ros::Publisher image_pub_; //image message publisher
00095 };
00096 
00097 int
00098 main (int argc, char **argv)
00099 {
00100   ros::init (argc, argv, "convert_pointcloud_to_image");
00101   PointCloudToImage pci; //this loads up the node
00102   ros::spin (); //where she stops nobody knows
00103   return 0;
00104 }


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu May 5 2016 04:16:43