00001
00042 #include <iostream>
00043 #include <boost/filesystem.hpp>
00044
00045 #include <pcl/pcl_base.h>
00046 #include <pcl/point_types.h>
00047 #include <pcl/point_cloud.h>
00048 #include <pcl/console/parse.h>
00049 #include <pcl/console/print.h>
00050 #include <pcl/io/pcd_io.h>
00051
00052 #include <pcl/io/vtk_lib_io.h>
00053 #include <vtkSmartPointer.h>
00054 #include <vtkImageViewer2.h>
00055 #include <vtkTIFFReader.h>
00056 #include <vtkRenderWindow.h>
00057 #include <vtkRenderWindowInteractor.h>
00058 #include <vtkRenderer.h>
00059
00060 using namespace pcl;
00061
00062 void processAndSave( vtkSmartPointer<vtkImageData> depth_data,
00063 vtkSmartPointer<vtkImageData> rgb_data,
00064 std::string time,
00065 float focal_length,
00066 bool format,
00067 bool color,
00068 bool depth,
00069 bool use_output_path,
00070 std::string output_path)
00071 {
00072
00073 int rgb_components = rgb_data->GetNumberOfScalarComponents();
00074
00075
00076 if(rgb_components != 3)
00077 {
00078 std::cout << "RGB image doesn't have 3 components, proceed with next image" << std::endl;
00079 return;
00080 }
00081
00082 int rgb_dimensions[3];
00083 rgb_data->GetDimensions (rgb_dimensions);
00084
00085
00086
00087 int depth_components = depth_data->GetNumberOfScalarComponents();
00088
00089
00090 if(depth_components != 1)
00091 {
00092 std::cout << "Depth image doesn't have a single component, proceed with next image" << std::endl;
00093 return;
00094 }
00095
00096 int depth_dimensions[3];
00097 depth_data->GetDimensions (depth_dimensions);
00098
00099
00100
00101 if(rgb_dimensions[0] != depth_dimensions[0] || rgb_dimensions[1] != depth_dimensions[1] || rgb_dimensions[2] != depth_dimensions[2])
00102 {
00103 std::cout << "RGB and Depth dimensions don't match, proceed with next image" << std::endl;
00104 return;
00105 }
00106
00107
00108 PointCloud<RGB> pc_image;
00109 PointCloud<Intensity> pc_depth;
00110 PointCloud<PointXYZRGBA> pc_xyzrgba;
00111
00112 pc_image.width = pc_depth.width = pc_xyzrgba.width = rgb_dimensions[0];
00113 pc_image.height = pc_depth.height = pc_xyzrgba.height = rgb_dimensions[1];
00114
00115 float constant = 1.0f / focal_length;
00116 float bad_point = std::numeric_limits<float>::quiet_NaN ();
00117
00118 for(int v = 0; v < rgb_dimensions[1]; v++)
00119 {
00120 for(int u = 0; u < rgb_dimensions[0]; u++)
00121 {
00122 RGB color_point;
00123 Intensity depth_point;
00124 PointXYZRGBA xyzrgba_point;
00125
00126 color_point.r = xyzrgba_point.r = static_cast<uint8_t> (rgb_data->GetScalarComponentAsFloat(u,v,0,0));
00127 color_point.g = xyzrgba_point.g = static_cast<uint8_t> (rgb_data->GetScalarComponentAsFloat(u,v,0,1));
00128 color_point.b = xyzrgba_point.b = static_cast<uint8_t> (rgb_data->GetScalarComponentAsFloat(u,v,0,2));
00129 xyzrgba_point.a = 0;
00130
00131 pc_image.points.push_back(color_point);
00132 pc_depth.points.push_back(depth_point);
00133
00134 float d = depth_data->GetScalarComponentAsFloat(u,v,0,0);
00135 depth_point.intensity = d;
00136
00137 if(d != 0 && !pcl_isnan(d) && !pcl_isnan(d))
00138 {
00139 xyzrgba_point.z = d * 0.001f;
00140 xyzrgba_point.x = static_cast<float> (u) * d * 0.001f * constant;
00141 xyzrgba_point.y = static_cast<float> (v) * d * 0.001f * constant;
00142 }
00143 else
00144 {
00145 xyzrgba_point.z = xyzrgba_point.x = xyzrgba_point.y = bad_point;
00146 }
00147 pc_xyzrgba.points.push_back(xyzrgba_point);
00148
00149 }
00150 }
00151
00152 std::stringstream ss;
00153
00154 if(depth)
00155 {
00156 if(use_output_path)
00157 ss << output_path << "/frame_" << time << "_depth.pcd";
00158 else
00159 ss << "frame_" << time << "_depth.pcd";
00160 pcl::io::savePCDFile (ss.str(), pc_depth, format);
00161 ss.str("");
00162 }
00163
00164 if(color)
00165 {
00166 if(use_output_path)
00167 ss << output_path << "/frame_" << time << "_color.pcd";
00168 else
00169 ss << "frame_" << time << "_color.pcd";
00170 pcl::io::savePCDFile (ss.str(), pc_image, format);
00171 ss.str("");
00172 }
00173
00174 if(use_output_path)
00175 ss << output_path << "/frame_" << time << "_xyzrgba.pcd";
00176 else
00177 ss << "frame_" << time << "_xyzrgba.pcd";
00178 pcl::io::savePCDFile (ss.str(), pc_xyzrgba, format);
00179
00180 std::cout << "Saved " << time << " to pcd" << std::endl;
00181 return;
00182 }
00183
00184 void print_usage(void)
00185 {
00186 PCL_INFO("usage: convert -rgb <rgb_path> -depth <depth_path> -out <output_path> options\n");
00187 PCL_INFO("This program converts rgb and depth tiff files to pcd files");
00188 PCL_INFO("Options:\n");
00189 PCL_INFO("\t -v \t Set verbose output\n");
00190 PCL_INFO("\t -c \t Create color pcd output\n");
00191 PCL_INFO("\t -d \t Create depth output\n");
00192 PCL_INFO("\t -b \t Set to save pcd binary, otherwise ascii\n");
00193 PCL_INFO("\t -f \t Focal length, default 525\n");
00194 PCL_INFO("\t -h \t This help\n");
00195 }
00196
00197 int main(int argc, char ** argv)
00198 {
00199
00200 if(argc < 3)
00201 {
00202 print_usage();
00203 exit(-1);
00204 }
00205
00206 bool verbose = 0;
00207 pcl::console::parse_argument (argc, argv, "-v", verbose);
00208
00209 bool format = 0;
00210 pcl::console::parse_argument (argc, argv, "-b", format);
00211
00212 bool color = 0;
00213 pcl::console::parse_argument (argc, argv, "-c", format);
00214
00215 bool depth = 0;
00216 pcl::console::parse_argument (argc, argv, "-d", format);
00217
00218 std::string rgb_path_, depth_path_, output_path_;
00219
00220 if(pcl::console::parse_argument (argc, argv, "-rgb", rgb_path_) == 0)
00221 {
00222 PCL_ERROR("No RGB Path given\n");
00223 print_usage();
00224 exit(-1);
00225 }
00226 if(pcl::console::parse_argument (argc, argv, "-depth", depth_path_) == 0)
00227 {
00228 PCL_ERROR("No Depth Path given\n");
00229 print_usage();
00230 exit(-1);
00231 }
00232 bool use_output_path = false;
00233 if(pcl::console::parse_argument (argc, argv, "-out", output_path_) == 0)
00234 {
00235 PCL_ERROR("No Output Path given\n");
00236 print_usage();
00237 exit(-1);
00238 }
00239 else
00240 {
00241 use_output_path = true;
00242 }
00243
00244 float focal_length = 525.0;
00245 pcl::console::parse_argument (argc, argv, "-f", focal_length);
00246
00247 if(verbose)
00248 PCL_INFO ("Creating RGB Tiff List\n");
00249
00250 std::vector<std::string> tiff_rgb_files;
00251 std::vector<boost::filesystem::path> tiff_rgb_paths;
00252 boost::filesystem::directory_iterator end_itr;
00253
00254 if(boost::filesystem::is_directory(rgb_path_))
00255 {
00256 for (boost::filesystem::directory_iterator itr(rgb_path_); itr != end_itr; ++itr)
00257 {
00258 std::string ext = itr->path().extension().string();
00259 if(ext.compare(".tiff") == 0)
00260 {
00261 tiff_rgb_files.push_back (itr->path ().string ());
00262 tiff_rgb_paths.push_back (itr->path ());
00263 }
00264 else
00265 {
00266
00267 }
00268
00269 if(verbose)
00270 {
00271 std::cout << "Extension" << itr->path().extension() << std::endl;
00272 std::cout << "Filename" << itr->path().filename() << std::endl;
00273
00274
00275
00276
00277
00278 }
00279 }
00280 }
00281 else
00282 {
00283 PCL_ERROR("RGB path is not a directory\n");
00284 exit(-1);
00285 }
00286
00287 sort (tiff_rgb_files.begin (), tiff_rgb_files.end ());
00288 sort (tiff_rgb_paths.begin (), tiff_rgb_paths.end ());
00289
00290 if(verbose)
00291 PCL_INFO ("Creating Depth Tiff List\n");
00292
00293 std::vector<std::string> tiff_depth_files;
00294 std::vector<boost::filesystem::path> tiff_depth_paths;
00295
00296 if(boost::filesystem::is_directory(depth_path_))
00297 {
00298 for (boost::filesystem::directory_iterator itr(depth_path_); itr != end_itr; ++itr)
00299 {
00300 std::string ext = itr->path().extension().string();
00301 if(ext.compare(".tiff") == 0)
00302 {
00303 tiff_depth_files.push_back (itr->path ().string ());
00304 tiff_depth_paths.push_back (itr->path ());
00305 }
00306 else
00307 {
00308
00309 }
00310
00311 if(verbose)
00312 {
00313 std::cout << "Extension" << itr->path().extension() << std::endl;
00314 std::cout << "Filename" << itr->path().filename() << std::endl;
00315 }
00316 }
00317 }
00318 else
00319 {
00320 PCL_ERROR("Depth path is not a directory\n");
00321 exit(-1);
00322 }
00323
00324 sort (tiff_depth_files.begin (), tiff_depth_files.end ());
00325 sort (tiff_depth_paths.begin (), tiff_depth_paths.end ());
00326
00327 for(unsigned int i=0; i<tiff_rgb_paths.size(); i++)
00328 {
00329
00330 vtkSmartPointer<vtkImageData> rgb_data;
00331 vtkSmartPointer<vtkTIFFReader> reader = vtkSmartPointer<vtkTIFFReader>::New ();
00332
00333
00334 int ret = reader->CanReadFile (tiff_rgb_files[i].c_str());
00335
00336 if(ret == 0 || ret == 1)
00337 {
00338 std::cout << "We have a broken tiff file: " << tiff_rgb_files[i] << std::endl;
00339 continue;
00340 }
00341
00342 if(ret == 2 || ret == 3)
00343 {
00344 reader->SetFileName (tiff_rgb_files[i].c_str());
00345 rgb_data = reader->GetOutput ();
00346 rgb_data->Update ();
00347
00348 std::string rgb_filename = tiff_rgb_paths[i].filename().string();
00349 std::string rgb_time = rgb_filename.substr(6,22);
00350
00351
00352
00353
00354 int found = 0;
00355
00356 for(int j = 0; j < tiff_depth_paths.size(); j++)
00357 {
00358 std::string depth_filename = tiff_depth_paths[i].filename().string();
00359 std::string depth_time = depth_filename.substr(6,22);
00360
00361 if(depth_time.compare(rgb_time) == 0)
00362 {
00363
00364 found = 1;
00365
00366
00367
00368 vtkSmartPointer<vtkImageData> depth_data;
00369 vtkSmartPointer<vtkTIFFReader> depth_reader = vtkSmartPointer<vtkTIFFReader>::New ();
00370
00371
00372 int read = depth_reader->CanReadFile (tiff_depth_files[j].c_str());
00373
00374 if(read == 0 || read == 1)
00375 {
00376 std::cout << "We have a broken tiff file: " << tiff_depth_files[j] << std::endl;
00377 continue;
00378 }
00379
00380 if(read == 2 || read == 3)
00381 {
00382 depth_reader->SetFileName (tiff_depth_files[j].c_str());
00383 depth_data = depth_reader->GetOutput ();
00384 depth_data->Update ();
00385
00386 processAndSave(depth_data, rgb_data, depth_time, focal_length, format, color, depth, use_output_path, output_path_);
00387 }
00388
00389
00390 break;
00391 }
00392 else
00393 {
00394
00395 continue;
00396 }
00397 if(found == 0)
00398 {
00399 std::cout << "We couldn't find a Depth file for this RGB image" << std::endl;
00400 }
00401 }
00402 }
00403 }
00404 return 0;
00405 }