transform_pointcloud.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: transform_pointcloud.cpp 30719 2010-07-09 20:28:41Z rusu $
00035  *
00036  */
00037 
00046 // ROS core
00047 #include <ros/ros.h>
00048 
00049 #include "pcl/io/pcd_io.h"
00050 #include "pcl/point_types.h"
00051 #include "pcl_ros/transforms.h"
00052 
00053 //#include "pcl_ros/publisher.h"
00054 //#include "pcl_ros/subscriber.h"
00055 
00056 #include <tf/transform_listener.h>
00057 
00058 using namespace std;
00059 
00060 class TransformPointcloudNode
00061 {
00062 protected:
00063   ros::NodeHandle nh_;
00064 
00065 public:
00066   string output_cloud_topic_, input_cloud_topic_, to_frame_, point_cloud_name_;
00067   bool save_point_cloud_;
00068 
00069   ros::Subscriber sub_;
00070   ros::Publisher pub_;
00071   tf::TransformListener tf_;
00072   pcl::PCDWriter pcd_writer_;
00073   sensor_msgs::PointCloud2 output_cloud_;
00075   TransformPointcloudNode  (ros::NodeHandle &n) : nh_(n)
00076   {
00077     // Maximum number of outgoing messages to be queued for delivery to subscribers = 1
00078     nh_.param("input_cloud_topic", input_cloud_topic_, std::string("cloud_pcd"));
00079     output_cloud_topic_ = input_cloud_topic_ + "_transformed";
00080     nh_.param("to_frame", to_frame_, std::string("base_link"));
00081     nh_.param("point_cloud_name", point_cloud_name_, std::string("pc"));
00082     nh_.param("save_point_cloud", save_point_cloud_, false);
00083 
00084     sub_ = nh_.subscribe (input_cloud_topic_, 1,  &TransformPointcloudNode::cloud_cb, this);
00085     ROS_INFO ("[TransformPointcloudNode:] Listening for incoming data on topic %s", nh_.resolveName (input_cloud_topic_).c_str ());
00086     pub_ = nh_.advertise<sensor_msgs::PointCloud2>(output_cloud_topic_, 1);
00087     ROS_INFO ("[TransformPointcloudNode:] Will be publishing data on topic %s.", nh_.resolveName (output_cloud_topic_).c_str ());
00088   }
00089 
00091   // cloud_cb (!)
00092   void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& pc)
00093   {
00094     bool found_transform = tf_.waitForTransform(pc->header.frame_id, to_frame_,
00095                                                 pc->header.stamp, ros::Duration(10.0));
00096     if (found_transform)
00097     {
00098       //ROS_ASSERT_MSG(found_transform, "Could not transform to camera frame");
00099       tf::StampedTransform transform;
00100       tf_.lookupTransform(to_frame_,pc->header.frame_id, pc->header.stamp, transform);
00101       pcl_ros::transformPointCloud(to_frame_, transform, *pc, output_cloud_);
00102       ROS_DEBUG("[TransformPointcloudNode:] Point cloud published in frame %s", output_cloud_.header.frame_id.c_str());
00103       pub_.publish (output_cloud_);
00104       if (save_point_cloud_)
00105         {
00106           pcl::PointCloud<pcl::PointXYZ> pcl_cloud;
00107           pcl::fromROSMsg(output_cloud_, pcl_cloud);
00108           pcd_writer_.write (point_cloud_name_ + ".pcd", pcl_cloud);
00109       ROS_INFO("Point cloud saved as %s.pcd", point_cloud_name_.c_str());
00110         }
00111     }
00112   }
00113 };
00114 
00115 int main (int argc, char** argv)
00116 {
00117   ros::init (argc, argv, "transform_pointcloud_node");
00118   ros::NodeHandle n("~");
00119   TransformPointcloudNode tp(n);
00120   ros::spin ();
00121   return (0);
00122 }
00123 
00124 /* ]--- */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


pcl_cloud_tools
Author(s): Nico Blodow, Zoltan-Csaba Marton, Dejan Pangercic
autogenerated on Thu May 23 2013 17:11:36