convert_pointcloud_to_image.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id: surface_convex_hull.cpp 34612 2010-12-08 01:06:27Z rusu $
35  *
36  */
37 
41 // ROS core
42 #include <ros/ros.h>
43 //Image message
44 #include <sensor_msgs/Image.h>
45 #include <sensor_msgs/PointCloud2.h>
46 //pcl::toROSMsg
47 #include <pcl/io/pcd_io.h>
48 //conversions from PCL custom types
50 //stl stuff
51 #include <string>
52 
54 {
55 public:
56  void
57  cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud)
58  {
59  if (cloud->height <= 1)
60  {
61  ROS_ERROR("Input point cloud is not organized, ignoring!");
62  return;
63  }
64  try
65  {
66  pcl::toROSMsg (*cloud, image_); //convert the cloud
67  image_.header = cloud->header;
68  image_pub_.publish (image_); //publish our cloud image
69  }
70  catch (std::runtime_error &e)
71  {
72  ROS_ERROR_STREAM("Error in converting cloud to image message: "
73  << e.what());
74  }
75  }
77  {
80  image_pub_ = nh_.advertise<sensor_msgs::Image> (image_topic_, 30);
81 
82  //print some info about the node
83  std::string r_ct = nh_.resolveName (cloud_topic_);
84  std::string r_it = nh_.resolveName (image_topic_);
85  ROS_INFO_STREAM("Listening for incoming data on topic " << r_ct );
86  ROS_INFO_STREAM("Publishing image on topic " << r_it );
87  }
88 private:
90  sensor_msgs::Image image_; //cache the image message
91  std::string cloud_topic_; //default input
92  std::string image_topic_; //default output
93  ros::Subscriber sub_; //cloud subscriber
94  ros::Publisher image_pub_; //image message publisher
95 };
96 
97 int
98 main (int argc, char **argv)
99 {
100  ros::init (argc, argv, "convert_pointcloud_to_image");
101  PointCloudToImage pci; //this loads up the node
102  ros::spin (); //where she stops nobody knows
103  return 0;
104 }
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string resolveName(const std::string &name, bool remap=true) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void cloud_cb(const sensor_msgs::PointCloud2ConstPtr &cloud)
#define ROS_INFO_STREAM(args)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR(...)


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Jun 5 2019 19:52:52