$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 /* author: Radu Bogdan Rusu <rusu@cs.tum.edu> */ 00031 00032 // ROS core 00033 #include "ros/node_handle.h" 00034 #include "ros/time.h" 00035 #include "ros/common.h" 00036 00037 #include "std_msgs/PointCloud.h" 00038 00039 //#include "StringTokenizer.h" 00040 #include <stdlib.h> 00041 #include "string_utils/string_utils.h" 00042 00043 #include <fstream> 00044 00045 using namespace std; 00046 00047 class PCDGenerator: public ros::node 00048 { 00049 public: 00050 00051 // ROS messages 00052 std_msgs::PointCloud msg_cloud_; 00053 00054 PCDGenerator () : ros::node ("PCD_generator") 00055 { 00056 // Maximum number of outgoing messages to be queued for delivery to subscribers = 1 00057 advertise<std_msgs::PointCloud>("cloud_stoc", 1); 00058 } 00059 00060 ~PCDGenerator () 00061 { 00062 } 00063 00065 // Load point cloud data from a PCD file containing n-D points 00067 // - the ones beginning with # (treated as comments 00068 // - COLUMNS ... 00069 // - POINTS ... 00070 // - DATA ... 00071 // ...are intepreted as data points. Failure to comply with this simple rule might result in errors and warnings! :) 00072 std_msgs::PointCloud 00073 LoadPointCloud (const char* fileName) 00074 { 00075 std_msgs::PointCloud cloud; 00076 00077 int nr_points = 0; 00078 std::ifstream fs; 00079 std::string line; 00080 00081 int idx = 0; 00082 // Open file 00083 fs.open (fileName); 00084 if (!fs.is_open ()) 00085 { 00086 fprintf (stderr, "Couldn't open %s for reading!\n", fileName); 00087 return cloud; 00088 } 00089 // Read the header and fill it in with wonderful values 00090 while (!fs.eof ()) 00091 { 00092 getline (fs, line); 00093 if (line == "") 00094 continue; 00095 00096 vector<string> st; 00097 string_utils::split (line, st, " "); 00098 // StringTokenizer st = StringTokenizer (line, " "); 00099 00100 // std::string lineType = st.nextToken (); 00101 std::string lineType = st.at (0); 00102 00104 if (lineType.substr (0, 1) == "#") 00105 continue; 00106 // Get the column indices 00107 if (lineType.substr (0, 7) == "COLUMNS") 00108 { 00109 // int remainingTokens = st.countTokens (); 00110 int remainingTokens = st.size () - (1 + 3); 00111 // st.nextToken (); st.nextToken (); st.nextToken (); // x-y-z 00112 00113 // cloud.set_chan_size (remainingTokens - 3); 00114 cloud.set_chan_size (remainingTokens); 00115 00116 // for (int i = 0; i < remainingTokens - 3; i++) 00117 for (int i = 0; i < remainingTokens; i++) 00118 { 00119 // std::string colType = st.nextToken (); 00120 std::string colType = st.at (i + 4); 00121 cloud.chan[i].name = colType; 00122 } 00123 continue; 00124 } 00125 // Get the number of points 00126 if (lineType.substr (0, 6) == "POINTS") 00127 { 00128 // nr_points = st.nextIntToken (); 00129 nr_points = atoi (st.at (1).c_str ()); 00130 cloud.set_pts_size (nr_points); 00131 00132 for (unsigned int d = 0; d < cloud.get_chan_size (); d++) 00133 cloud.chan[d].set_vals_size (nr_points); 00134 00135 continue; 00136 } 00137 00138 // Check DATA type 00139 if (lineType.substr (0, 4) == "DATA") 00140 continue; 00141 00142 // Nothing of the above? We must have points then 00143 // Convert the first token to float and use it as the first point coordinate 00144 if (idx >= nr_points) 00145 { 00146 fprintf (stderr, "Error: input file %s has more points than advertised (%d)!\n", fileName, nr_points); 00147 break; 00148 } 00149 00150 // Assume x-y-z to be the first dimensions in the file 00151 // @todo: check and improve this for errors 00152 // cloud.pts[idx].x = atof (lineType.c_str ()); 00153 // cloud.pts[idx].y = st.nextFloatToken (); 00154 // cloud.pts[idx].z = st.nextFloatToken (); 00155 cloud.pts[idx].x = atof (st.at (0).c_str ()); 00156 cloud.pts[idx].y = atof (st.at (1).c_str ()); 00157 cloud.pts[idx].z = atof (st.at (2).c_str ()); 00158 for (unsigned int i = 0; i < cloud.get_chan_size (); i++) 00159 // cloud.chan[i].vals[idx] = st.nextFloatToken (); 00160 cloud.chan[i].vals[idx] = atof (st.at (i+3).c_str ()); 00161 00162 idx++; 00163 } 00164 // Close file 00165 fs.close (); 00166 00167 if (idx != nr_points) 00168 fprintf (stderr, "Warning! Number of points read (%d) is different than expected (%d)\n", idx, nr_points); 00169 00170 return cloud; 00171 } 00172 00173 00175 // Start 00176 int 00177 start () 00178 { 00179 msg_cloud_ = LoadPointCloud ("stoc.pcd"); 00180 return (0); 00181 } 00182 00184 // Spin (!) 00185 bool spin () 00186 { 00187 while (ok ()) 00188 { 00189 usleep (100000); 00190 00191 publish ("cloud_stoc", msg_cloud_); 00192 } 00193 00194 return true; 00195 } 00196 00197 00198 }; 00199 00200 /* ---[ */ 00201 int 00202 main (int argc, char** argv) 00203 { 00204 ros::init (argc, argv); 00205 00206 PCDGenerator c; 00207 00208 c.start (); 00209 c.spin (); 00210 00211 ros::fini (); 00212 00213 return (0); 00214 } 00215 /* ]--- */