$search
00001 /* 00002 * Copyright (c) 2008 Radu Bogdan Rusu <rusu -=- cs.tum.edu> 00003 * 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions are met: 00008 * 00009 * * Redistributions of source code must retain the above copyright 00010 * notice, this list of conditions and the following disclaimer. 00011 * * Redistributions in binary form must reproduce the above copyright 00012 * notice, this list of conditions and the following disclaimer in the 00013 * documentation and/or other materials provided with the distribution. 00014 * 00015 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00016 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00017 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00018 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00019 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00020 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00021 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00022 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00023 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00024 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00025 * POSSIBILITY OF SUCH DAMAGE. 00026 * 00027 * $Id: multi_pcd_to_msg.cpp 21050 2009-08-07 21:24:30Z jfaustwg $ 00028 * 00029 */ 00030 00043 // ROS core 00044 #include <ros/node_handle.h> 00045 #include <sensor_msgs/PointCloud.h> 00046 #include <point_cloud_mapping/cloud_io.h> 00047 #include <tf/transform_broadcaster.h> 00048 00049 //for get_log_files() 00050 #include <boost/filesystem/operations.hpp> 00051 #include <boost/filesystem/fstream.hpp> 00052 #include "boost/filesystem.hpp" 00053 00054 using namespace std; 00055 using namespace boost::filesystem; 00056 00057 class MultiPCDGenerator 00058 { 00059 protected: 00060 string tf_frame_; 00061 ros::NodeHandle nh_; 00062 tf::TransformBroadcaster broadcaster_; 00063 tf::Stamped<tf::Transform> transform_; 00064 00065 public: 00066 00067 // ROS messages 00068 sensor_msgs::PointCloud msg_cloud_; 00069 00070 string file_name_, cloud_topic_, dir_; 00071 double rate_; 00072 vector<string> file_list_; 00073 00074 ros::Publisher cloud_pub_; 00075 00076 MultiPCDGenerator () : tf_frame_ ("base_link"), 00077 transform_ (btTransform (btQuaternion (0, 0, 0), btVector3 (0, 0, 0)), ros::Time::now (), tf_frame_, tf_frame_) 00078 { 00079 // Maximum number of outgoing messages to be queued for delivery to subscribers = 1 00080 cloud_topic_ = "cloud_pcd"; 00081 cloud_pub_ = nh_.advertise<sensor_msgs::PointCloud> (cloud_topic_.c_str (), 1); 00082 ROS_INFO ("Publishing data on topic %s.", nh_.resolveName (cloud_topic_).c_str ()); 00083 } 00084 00086 // Start 00087 int 00088 start () 00089 { 00090 get_log_files(dir_, file_list_); 00091 // if (file_name_ == "" || cloud_io::loadPCDFile (file_name_.c_str (), msg_cloud_) == -1) 00092 // return (-1); 00093 //msg_cloud_.header.frame_id = tf_frame_; 00094 return (0); 00095 } 00096 00098 // Get a list of pcd files 00100 void get_log_files ( const path & directory, vector <string> &file_list, string suffix=".pcd", bool recurse_into_subdirs = false ) 00101 { 00102 if( exists( directory ) ) 00103 { 00104 directory_iterator end ; 00105 for( directory_iterator iter(directory) ; iter != end ; ++iter ) 00106 if ( is_directory( *iter ) ) 00107 { 00108 ROS_WARN("Directory %s", iter->string().c_str()); 00109 //if( recurse_into_subdirs ) get_log_files(*iter) ; 00110 } 00111 else 00112 { 00113 int len = iter->string().length(); 00114 int npos = iter->string().rfind(suffix); 00115 if((len - npos) == suffix.length()) 00116 file_list.push_back(iter->string()); 00117 } 00118 } 00119 } 00120 00122 // Spin (!) 00123 bool spin () 00124 { 00125 double interval = rate_ * 1e+6; 00126 while (nh_.ok ()) 00127 { 00128 for ( int pcd = 0; pcd < file_list_.size(); pcd++) 00129 { 00130 msg_cloud_.points.resize(0); 00131 transform_.stamp_ = ros::Time::now (); 00132 broadcaster_.sendTransform (transform_); 00133 cloud_io::loadPCDFile (file_list_[pcd].c_str (), msg_cloud_); 00134 msg_cloud_.header.frame_id = tf_frame_; 00135 ROS_INFO ("Publishing data (%d points) on topic %s in frame %s.", (int)msg_cloud_.points.size (), 00136 nh_.resolveName (cloud_topic_).c_str (), msg_cloud_.header.frame_id.c_str ()); 00137 msg_cloud_.header.stamp = ros::Time::now (); 00138 cloud_pub_.publish (msg_cloud_); 00139 //if (interval == 0) // We only publish once if a 0 seconds interval is given 00140 // break; 00141 usleep (interval); 00142 ros::spinOnce (); 00143 } 00144 } 00145 return (true); 00146 } 00147 }; 00148 00149 /* ---[ */ 00150 int 00151 main (int argc, char** argv) 00152 { 00153 if (argc < 3) 00154 { 00155 ROS_ERROR ("Syntax is: %s <dir> [publishing_interval between respective pcd(in seconds)]", argv[0]); 00156 return (-1); 00157 } 00158 00159 ros::init (argc, argv, "multi_pcd_generator"); 00160 00161 MultiPCDGenerator c; 00162 c.dir_ = string (argv[1]); 00163 c.rate_ = atof (argv[2]); 00164 //ROS_INFO ("Loading file %s...", c.file_name_.c_str ()); 00165 00166 if (c.start () == -1) 00167 { 00168 ROS_ERROR ("Could not load file. Exiting."); 00169 return (-1); 00170 } 00171 c.spin (); 00172 00173 return (0); 00174 } 00175 /* ]--- */