convert_pcd_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 
49 #include <ros/ros.h>
50 #include <sensor_msgs/Image.h>
51 #include <sensor_msgs/PointCloud2.h>
52 #include <pcl/io/io.h>
53 #include <pcl/io/pcd_io.h>
54 #include <pcl/point_types.h>
56 
57 /* ---[ */
58 int
59 main (int argc, char **argv)
60 {
61  ros::init (argc, argv, "image_publisher");
62  ros::NodeHandle nh;
63  ros::Publisher image_pub = nh.advertise <sensor_msgs::Image> ("output", 1);
64 
65  if (argc != 2)
66  {
67  std::cout << "usage:\n" << argv[0] << " cloud.pcd" << std::endl;
68  return 1;
69  }
70 
71  sensor_msgs::Image image;
72  sensor_msgs::PointCloud2 cloud;
73  pcl::io::loadPCDFile (std::string (argv[1]), cloud);
74 
75  try
76  {
77  pcl::toROSMsg (cloud, image); //convert the cloud
78  }
79  catch (std::runtime_error &e)
80  {
81  ROS_ERROR_STREAM("Error in converting cloud to image message: "
82  << e.what());
83  return 1; //fail!
84  }
85  ros::Rate loop_rate (5);
86  while (nh.ok ())
87  {
88  image_pub.publish (image);
89  ros::spinOnce ();
90  loop_rate.sleep ();
91  }
92 
93  return (0);
94 }
95 
96 /* ]--- */
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int loadPCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool sleep()
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
int main(int argc, char **argv)
bool ok() const
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()


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