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 //conversions from PCL custom types
49 //stl stuff
50 #include <string>
51 
53 {
54 public:
55  void
56  cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud)
57  {
58  if (cloud->height <= 1)
59  {
60  ROS_ERROR("Input point cloud is not organized, ignoring!");
61  return;
62  }
63  try
64  {
65  pcl::toROSMsg (*cloud, image_); //convert the cloud
66  image_.header = cloud->header;
67  image_pub_.publish (image_); //publish our cloud image
68  }
69  catch (std::runtime_error &e)
70  {
71  ROS_ERROR_STREAM("Error in converting cloud to image message: "
72  << e.what());
73  }
74  }
76  {
79  image_pub_ = nh_.advertise<sensor_msgs::Image> (image_topic_, 30);
80 
81  //print some info about the node
82  std::string r_ct = nh_.resolveName (cloud_topic_);
83  std::string r_it = nh_.resolveName (image_topic_);
84  ROS_INFO_STREAM("Listening for incoming data on topic " << r_ct );
85  ROS_INFO_STREAM("Publishing image on topic " << r_it );
86  }
87 private:
89  sensor_msgs::Image image_; //cache the image message
90  std::string cloud_topic_; //default input
91  std::string image_topic_; //default output
92  ros::Subscriber sub_; //cloud subscriber
93  ros::Publisher image_pub_; //image message publisher
94 };
95 
96 int
97 main (int argc, char **argv)
98 {
99  ros::init (argc, argv, "convert_pointcloud_to_image");
100  PointCloudToImage pci; //this loads up the node
101  ros::spin (); //where she stops nobody knows
102  return 0;
103 }
ros::Publisher
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
PointCloudToImage::image_
sensor_msgs::Image image_
Definition: convert_pointcloud_to_image.cpp:89
ros.h
PointCloudToImage::image_topic_
std::string image_topic_
Definition: convert_pointcloud_to_image.cpp:91
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
PointCloudToImage::nh_
ros::NodeHandle nh_
Definition: convert_pointcloud_to_image.cpp:88
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
PointCloudToImage::cloud_topic_
std::string cloud_topic_
Definition: convert_pointcloud_to_image.cpp:90
PointCloudToImage::cloud_cb
void cloud_cb(const sensor_msgs::PointCloud2ConstPtr &cloud)
Definition: convert_pointcloud_to_image.cpp:56
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
PointCloudToImage::image_pub_
ros::Publisher image_pub_
Definition: convert_pointcloud_to_image.cpp:93
main
int main(int argc, char **argv)
Definition: convert_pointcloud_to_image.cpp:97
ROS_ERROR
#define ROS_ERROR(...)
PointCloudToImage
Definition: convert_pointcloud_to_image.cpp:52
PointCloudToImage::sub_
ros::Subscriber sub_
Definition: convert_pointcloud_to_image.cpp:92
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
ros::spin
ROSCPP_DECL void spin()
PointCloudToImage::PointCloudToImage
PointCloudToImage()
Definition: convert_pointcloud_to_image.cpp:75
ros::NodeHandle
ros::Subscriber
pcl_conversions.h


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Fri Jul 12 2024 02:54:40