00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <pcl/io/pcd_io.h>
00039 #include <pcl/io/lzf_image_io.h>
00040 #include <pcl/console/print.h>
00041 #include <pcl/console/parse.h>
00042 #include <pcl/console/time.h>
00043
00044 using namespace pcl;
00045 using namespace pcl::io;
00046 using namespace pcl::console;
00047
00048 void
00049 printHelp (int, char **argv)
00050 {
00051 print_error ("Syntax is: %s depth.pclzf rgb.pclzf parameters.xml output.pcd\n", argv[0]);
00052 }
00053
00054 bool
00055 loadPCLZF (const std::string &filename_rgb,
00056 const std::string &filename_depth,
00057 const std::string &filename_params,
00058 pcl::PointCloud<pcl::PointXYZRGBA> &cloud)
00059 {
00060 TicToc tt;
00061 print_highlight ("Loading "); print_value ("%s ", filename_rgb.c_str ());
00062 tt.tic ();
00063
00064 pcl::io::LZFRGB24ImageReader rgb;
00065 pcl::io::LZFBayer8ImageReader bayer;
00066 pcl::io::LZFYUV422ImageReader yuv;
00067 pcl::io::LZFDepth16ImageReader depth;
00068
00069 rgb.readParameters (filename_params);
00070 bayer.readParameters (filename_params);
00071 depth.readParameters (filename_params);
00072 yuv.readParameters (filename_params);
00073
00074 if (!rgb.read (filename_rgb, cloud))
00075 if (!yuv.read (filename_rgb, cloud))
00076 bayer.read (filename_rgb, cloud);
00077
00078 depth.read (filename_depth, cloud);
00079
00080 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00081 print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00082
00083 return (true);
00084 }
00085
00086 bool
00087 loadPCLZF (const std::string &filename_depth,
00088 const std::string &filename_params,
00089 pcl::PointCloud<pcl::PointXYZ> &cloud)
00090 {
00091 TicToc tt;
00092 print_highlight ("Loading "); print_value ("%s ", filename_depth.c_str ());
00093 tt.tic ();
00094
00095 pcl::io::LZFDepth16ImageReader depth;
00096 depth.readParameters (filename_params);
00097 depth.read (filename_depth, cloud);
00098
00099 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00100 print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00101
00102 return (true);
00103 }
00104
00105 template <typename T> void
00106 saveCloud (const std::string &filename, const pcl::PointCloud<T> &cloud)
00107 {
00108 TicToc tt;
00109 tt.tic ();
00110
00111 print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00112
00113 pcl::PCDWriter writer;
00114 writer.writeBinaryCompressed (filename, cloud);
00115
00116 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00117 }
00118
00119
00120 int
00121 main (int argc, char** argv)
00122 {
00123 print_info ("Convert a pair of PCLZF files (depth, rgb) to PCD format. For more information, use: %s -h\n", argv[0]);
00124
00125 if (argc < 3)
00126 {
00127 printHelp (argc, argv);
00128 return (-1);
00129 }
00130
00131 bool debug = false;
00132 pcl::console::parse_argument (argc, argv, "-debug", debug);
00133 if (debug)
00134 pcl::console::setVerbosityLevel (pcl::console::L_DEBUG);
00135
00136
00137 std::vector<int> pcd_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00138 std::vector<int> pclzf_file_indices = parse_file_extension_argument (argc, argv, ".pclzf");
00139 std::vector<int> xml_file_indices = parse_file_extension_argument (argc, argv, ".xml");
00140 if (pcd_file_indices.size () != 1 || pclzf_file_indices.size () < 1 || xml_file_indices.size () != 1)
00141 {
00142 print_error ("Need at least 1 input PCLZF file, one input XML file, and one output PCD file.\n");
00143 return (-1);
00144 }
00145
00146 std::string filename_depth (argv[pclzf_file_indices[0]]);
00147 if (pclzf_file_indices.size () > 1)
00148 {
00149 std::string filename_rgb (argv[pclzf_file_indices[1]]);
00150
00151
00152 pcl::PointCloud<pcl::PointXYZRGBA> cloud;
00153 if (!loadPCLZF (filename_rgb, filename_depth, argv[xml_file_indices[0]], cloud))
00154 return (-1);
00155
00156
00157 saveCloud (argv[pcd_file_indices[0]], cloud);
00158 }
00159 else
00160 {
00161
00162 pcl::PointCloud<pcl::PointXYZ> cloud;
00163 if (!loadPCLZF (filename_depth, argv[xml_file_indices[0]], cloud))
00164 return (-1);
00165
00166
00167 saveCloud (argv[pcd_file_indices[0]], cloud);
00168 }
00169 }
00170