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 #include <pcl/console/time.h>
00038 #include <pcl/io/lzf_image_io.h>
00039 #include <pcl/io/lzf.h>
00040 #include <pcl/console/print.h>
00041 #include <fcntl.h>
00042 #include <string.h>
00043 #include <boost/filesystem.hpp>
00044 #include <boost/property_tree/ptree.hpp>
00045 #include <boost/property_tree/xml_parser.hpp>
00046
00047 #ifdef _WIN32
00048 # include <io.h>
00049 # include <windows.h>
00050 # define pcl_open _open
00051 # define pcl_close(fd) _close(fd)
00052 # define pcl_lseek(fd,offset,origin) _lseek(fd,offset,origin)
00053 #else
00054 # include <sys/mman.h>
00055 # define pcl_open open
00056 # define pcl_close(fd) close(fd)
00057 # define pcl_lseek(fd,offset,origin) lseek(fd,offset,origin)
00058 #endif
00059
00060 #define LZF_HEADER_SIZE 37
00061
00063 bool
00064 pcl::io::LZFImageWriter::saveImageBlob (const char* data,
00065 size_t data_size,
00066 const std::string &filename)
00067 {
00068 #ifdef _WIN32
00069 HANDLE h_native_file = CreateFile (filename.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL);
00070 if (h_native_file == INVALID_HANDLE_VALUE)
00071 return (false);
00072 HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, data_size, NULL);
00073 char *map = static_cast<char*> (MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, data_size));
00074 CloseHandle (fm);
00075 memcpy (&map[0], data, data_size);
00076 UnmapViewOfFile (map);
00077 CloseHandle (h_native_file);
00078 #else
00079 int fd = pcl_open (filename.c_str (), O_RDWR | O_CREAT | O_TRUNC, static_cast<mode_t> (0600));
00080 if (fd < 0)
00081 return (false);
00082
00083 off_t result = pcl_lseek (fd, data_size - 1, SEEK_SET);
00084 if (result < 0)
00085 {
00086 pcl_close (fd);
00087 return (false);
00088 }
00089
00090 result = static_cast<int> (::write (fd, "", 1));
00091 if (result != 1)
00092 {
00093 pcl_close (fd);
00094 return (false);
00095 }
00096
00097 char *map = static_cast<char*> (mmap (0, data_size, PROT_WRITE, MAP_SHARED, fd, 0));
00098 if (map == reinterpret_cast<char*> (-1))
00099 {
00100 pcl_close (fd);
00101 return (false);
00102 }
00103
00104
00105 memcpy (&map[0], data, data_size);
00106
00107 if (munmap (map, (data_size)) == -1)
00108 {
00109 pcl_close (fd);
00110 return (false);
00111 }
00112 pcl_close (fd);
00113 #endif
00114 return (true);
00115 }
00116
00118 pcl::uint32_t
00119 pcl::io::LZFImageWriter::compress (const char* input,
00120 uint32_t uncompressed_size,
00121 uint32_t width,
00122 uint32_t height,
00123 const std::string &image_type,
00124 char *output)
00125 {
00126 static const int header_size = LZF_HEADER_SIZE;
00127 float finput_size = static_cast<float> (uncompressed_size);
00128 unsigned int compressed_size = pcl::lzfCompress (input,
00129 uncompressed_size,
00130 &output[header_size],
00131 uint32_t (finput_size * 1.5f));
00132
00133 uint32_t compressed_final_size = 0;
00134 if (compressed_size)
00135 {
00136
00137 const char header[] = "PCLZF";
00138 memcpy (&output[0], &header[0], 5);
00139 memcpy (&output[5], &width, sizeof (uint32_t));
00140 memcpy (&output[9], &height, sizeof (uint32_t));
00141 std::string itype = image_type;
00142
00143 if (itype.size () > 16)
00144 {
00145 PCL_WARN ("[pcl::io::LZFImageWriter::compress] Image type should be a string of maximum 16 characters! Cutting %s to %s.\n", image_type.c_str (), image_type.substr (0, 15).c_str ());
00146 itype = itype.substr (0, 15);
00147 }
00148 if (itype.size () < 16)
00149 itype.insert (itype.end (), 16 - itype.size (), ' ');
00150
00151 memcpy (&output[13], &itype[0], 16);
00152 memcpy (&output[29], &compressed_size, sizeof (uint32_t));
00153 memcpy (&output[33], &uncompressed_size, sizeof (uint32_t));
00154 compressed_final_size = uint32_t (compressed_size + header_size);
00155 }
00156
00157 return (compressed_final_size);
00158 }
00159
00161 bool
00162 pcl::io::LZFDepth16ImageWriter::write (const char* data,
00163 uint32_t width, uint32_t height,
00164 const std::string &filename)
00165 {
00166
00167 unsigned int depth_size = width * height * 2;
00168 char* compressed_depth = static_cast<char*> (malloc (size_t (float (depth_size) * 1.5f + float (LZF_HEADER_SIZE))));
00169
00170 size_t compressed_size = compress (data,
00171 depth_size,
00172 width, height,
00173 "depth16",
00174 compressed_depth);
00175 if (compressed_size == 0)
00176 {
00177 free (compressed_depth);
00178 return (false);
00179 }
00180
00181
00182 saveImageBlob (compressed_depth, compressed_size, filename);
00183 free (compressed_depth);
00184 return (true);
00185 }
00186
00188 bool
00189 pcl::io::LZFImageWriter::writeParameter (const double ¶meter,
00190 const std::string &tag,
00191 const std::string &filename)
00192 {
00193 boost::property_tree::ptree pt;
00194 try
00195 {
00196 boost::property_tree::xml_parser::read_xml (filename, pt, boost::property_tree::xml_parser::trim_whitespace);
00197 }
00198 catch (std::exception& e)
00199 {}
00200
00201 boost::property_tree::xml_writer_settings<char> settings ('\t', 1);
00202 pt.put (tag, parameter);
00203 write_xml (filename, pt, std::locale (), settings);
00204
00205 return (true);
00206 }
00207
00209 bool
00210 pcl::io::LZFDepth16ImageWriter::writeParameters (const pcl::io::CameraParameters ¶meters,
00211 const std::string &filename)
00212 {
00213 boost::property_tree::ptree pt;
00214 try
00215 {
00216 boost::property_tree::xml_parser::read_xml (filename, pt, boost::property_tree::xml_parser::trim_whitespace);
00217 }
00218 catch (std::exception& e)
00219 {}
00220
00221 boost::property_tree::xml_writer_settings<char> settings ('\t', 1);
00222 pt.put ("depth.focal_length_x", parameters.focal_length_x);
00223 pt.put ("depth.focal_length_y", parameters.focal_length_y);
00224 pt.put ("depth.principal_point_x", parameters.principal_point_x);
00225 pt.put ("depth.principal_point_y", parameters.principal_point_y);
00226 pt.put ("depth.z_multiplication_factor", z_multiplication_factor_);
00227 write_xml (filename, pt, std::locale (), settings);
00228
00229 return (true);
00230 }
00231
00233 bool
00234 pcl::io::LZFRGB24ImageWriter::write (const char *data,
00235 uint32_t width, uint32_t height,
00236 const std::string &filename)
00237 {
00238
00239 std::vector<char> rrggbb (width * height * 3);
00240 int ptr1 = 0,
00241 ptr2 = width * height,
00242 ptr3 = 2 * width * height;
00243 for (int i = 0; i < width * height; ++i, ++ptr1, ++ptr2, ++ptr3)
00244 {
00245 rrggbb[ptr1] = data[i * 3 + 0];
00246 rrggbb[ptr2] = data[i * 3 + 1];
00247 rrggbb[ptr3] = data[i * 3 + 2];
00248 }
00249
00250 char* compressed_rgb = static_cast<char*> (malloc (size_t (float (rrggbb.size ()) * 1.5f + float (LZF_HEADER_SIZE))));
00251 size_t compressed_size = compress (reinterpret_cast<const char*> (&rrggbb[0]),
00252 uint32_t (rrggbb.size ()),
00253 width, height,
00254 "rgb24",
00255 compressed_rgb);
00256
00257 if (compressed_size == 0)
00258 {
00259 free (compressed_rgb);
00260 return (false);
00261 }
00262
00263
00264 saveImageBlob (compressed_rgb, compressed_size, filename);
00265 free (compressed_rgb);
00266 return (true);
00267 }
00268
00270 bool
00271 pcl::io::LZFRGB24ImageWriter::writeParameters (const pcl::io::CameraParameters ¶meters,
00272 const std::string &filename)
00273 {
00274 boost::property_tree::ptree pt;
00275 try
00276 {
00277 boost::property_tree::xml_parser::read_xml (filename, pt, boost::property_tree::xml_parser::trim_whitespace);
00278 }
00279 catch (std::exception& e)
00280 {}
00281
00282 boost::property_tree::xml_writer_settings<char> settings ('\t', 1);
00283 pt.put ("rgb.focal_length_x", parameters.focal_length_x);
00284 pt.put ("rgb.focal_length_y", parameters.focal_length_y);
00285 pt.put ("rgb.principal_point_x", parameters.principal_point_x);
00286 pt.put ("rgb.principal_point_y", parameters.principal_point_y);
00287 write_xml (filename, pt, std::locale (), settings);
00288
00289 return (true);
00290 }
00291
00293 bool
00294 pcl::io::LZFYUV422ImageWriter::write (const char *data,
00295 uint32_t width, uint32_t height,
00296 const std::string &filename)
00297 {
00298
00299 std::vector<char> uuyyvv (width * height * 2);
00300 int wh2 = width * height / 2,
00301 ptr1 = 0,
00302 ptr2 = wh2,
00303 ptr3 = wh2 + width * height;
00304 for (int i = 0; i < wh2; ++i, ++ptr1, ptr2 += 2, ++ptr3)
00305 {
00306 uuyyvv[ptr1] = data[i * 4 + 0];
00307 uuyyvv[ptr2 + 0] = data[i * 4 + 1];
00308 uuyyvv[ptr2 + 1] = data[i * 4 + 3];
00309 uuyyvv[ptr3] = data[i * 4 + 2];
00310 }
00311
00312 char* compressed_yuv = static_cast<char*> (malloc (size_t (float (uuyyvv.size ()) * 1.5f + float (LZF_HEADER_SIZE))));
00313 size_t compressed_size = compress (reinterpret_cast<const char*> (&uuyyvv[0]),
00314 uint32_t (uuyyvv.size ()),
00315 width, height,
00316 "yuv422",
00317 compressed_yuv);
00318
00319 if (compressed_size == 0)
00320 {
00321 free (compressed_yuv);
00322 return (false);
00323 }
00324
00325
00326 saveImageBlob (compressed_yuv, compressed_size, filename);
00327 free (compressed_yuv);
00328 return (true);
00329 }
00330
00332 bool
00333 pcl::io::LZFBayer8ImageWriter::write (const char *data,
00334 uint32_t width, uint32_t height,
00335 const std::string &filename)
00336 {
00337 unsigned int bayer_size = width * height;
00338 char* compressed_bayer = static_cast<char*> (malloc (size_t (float (bayer_size) * 1.5f + float (LZF_HEADER_SIZE))));
00339 size_t compressed_size = compress (data,
00340 bayer_size,
00341 width, height,
00342 "bayer8",
00343 compressed_bayer);
00344
00345 if (compressed_size == 0)
00346 {
00347 free (compressed_bayer);
00348 return (false);
00349 }
00350
00351
00352 saveImageBlob (compressed_bayer, compressed_size, filename);
00353 free (compressed_bayer);
00354 return (true);
00355 }
00356
00360 pcl::io::LZFImageReader::LZFImageReader ()
00361 : width_ ()
00362 , height_ ()
00363 , image_type_identifier_ ()
00364 , parameters_ ()
00365 {
00366 }
00367
00369 bool
00370 pcl::io::LZFImageReader::loadImageBlob (const std::string &filename,
00371 std::vector<char> &data,
00372 uint32_t &uncompressed_size)
00373 {
00374 if (filename == "" || !boost::filesystem::exists (filename))
00375 {
00376 PCL_ERROR ("[pcl::io::LZFImageReader::loadImage] Could not find file '%s'.\n", filename.c_str ());
00377 return (false);
00378 }
00379
00380 int fd = pcl_open (filename.c_str (), O_RDONLY);
00381 if (fd == -1)
00382 {
00383 PCL_ERROR ("[pcl::io::LZFImageReader::loadImage] Failure to open file %s\n", filename.c_str () );
00384 return (false);
00385 }
00386
00387
00388 off_t data_size = pcl_lseek (fd, 0, SEEK_END);
00389 if (data_size < 0)
00390 {
00391 pcl_close (fd);
00392 PCL_ERROR ("[pcl::io::LZFImageReader::loadImage] lseek errno: %d strerror: %s\n", errno, strerror (errno));
00393 PCL_ERROR ("[pcl::io::LZFImageReader::loadImage] Error during lseek ()!\n");
00394 return (false);
00395 }
00396 pcl_lseek (fd, 0, SEEK_SET);
00397
00398 #ifdef _WIN32
00399
00400
00401 HANDLE fm = CreateFileMapping ((HANDLE) _get_osfhandle (fd), NULL, PAGE_READONLY, 0, 0, NULL);
00402
00403
00404 char *map = static_cast<char*>(MapViewOfFile (fm, FILE_MAP_READ, 0, 0, 0));
00405 if (map == NULL)
00406 {
00407 CloseHandle (fm);
00408 pcl_close (fd);
00409 PCL_ERROR ("[pcl::io::LZFImageReader::loadImage] Error mapping view of file, %s\n", filename.c_str ());
00410 return (false);
00411 }
00412 #else
00413 char *map = static_cast<char*> (mmap (0, data_size, PROT_READ, MAP_SHARED, fd, 0));
00414 if (map == reinterpret_cast<char*> (-1))
00415 {
00416 pcl_close (fd);
00417 PCL_ERROR ("[pcl::io::LZFImageReader::loadImage] Error preparing mmap for PCLZF file.\n");
00418 return (false);
00419 }
00420 #endif
00421
00422
00423 char header_string[5];
00424 memcpy (&header_string, &map[0], 5);
00425 if (std::string (header_string).substr (0, 5) != "PCLZF")
00426 {
00427 PCL_ERROR ("[pcl::io::LZFImageReader::loadImage] Wrong signature header! Should be 'P'C'L'Z'F'.\n");
00428 #ifdef _WIN32
00429 UnmapViewOfFile (map);
00430 CloseHandle (fm);
00431 #else
00432 munmap (map, data_size);
00433 #endif
00434 return (false);
00435 }
00436 memcpy (&width_, &map[5], sizeof (uint32_t));
00437 memcpy (&height_, &map[9], sizeof (uint32_t));
00438 char imgtype_string[16];
00439 memcpy (&imgtype_string, &map[13], 16);
00440 image_type_identifier_ = std::string (imgtype_string).substr (0, 15);
00441 image_type_identifier_.insert (image_type_identifier_.end (), 1, '\0');
00442
00443 static const int header_size = LZF_HEADER_SIZE;
00444 uint32_t compressed_size;
00445 memcpy (&compressed_size, &map[29], sizeof (uint32_t));
00446
00447 if (compressed_size + header_size != data_size)
00448 {
00449 PCL_ERROR ("[pcl::io::LZFImageReader::loadImage] Number of bytes to decompress written in file (%u) differs from what it should be (%u)!\n", compressed_size, data_size - header_size);
00450 #ifdef _WIN32
00451 UnmapViewOfFile (map);
00452 CloseHandle (fm);
00453 #else
00454 munmap (map, data_size);
00455 #endif
00456 return (false);
00457 }
00458
00459 memcpy (&uncompressed_size, &map[33], sizeof (uint32_t));
00460
00461 data.resize (compressed_size);
00462 memcpy (&data[0], &map[header_size], compressed_size);
00463
00464 #ifdef _WIN32
00465 UnmapViewOfFile (map);
00466 CloseHandle (fm);
00467 #else
00468 if (munmap (map, data_size) == -1)
00469 PCL_ERROR ("[pcl::io::LZFImageReader::loadImage] Munmap failure\n");
00470 #endif
00471 pcl_close (fd);
00472
00473 data_size = off_t (compressed_size);
00474 return (true);
00475 }
00476
00478 bool
00479 pcl::io::LZFImageReader::decompress (const std::vector<char> &input,
00480 std::vector<char> &output)
00481 {
00482 if (output.empty ())
00483 {
00484 PCL_ERROR ("[pcl::io::LZFImageReader::decompress] Output array needs to be preallocated! The correct uncompressed array value should have been stored during the compression.\n");
00485 return (false);
00486 }
00487 unsigned int tmp_size = pcl::lzfDecompress (static_cast<const char*>(&input[0]),
00488 uint32_t (input.size ()),
00489 static_cast<char*>(&output[0]),
00490 uint32_t (output.size ()));
00491
00492 if (tmp_size != output.size ())
00493 {
00494 PCL_WARN ("[pcl::io::LZFImageReader::decompress] Size of decompressed lzf data (%u) does not match the uncompressed size value (%u). Errno: %d\n", tmp_size, output.size (), errno);
00495 return (false);
00496 }
00497 return (true);
00498 }
00499
00501 bool
00502 pcl::io::LZFImageReader::readParameters (const std::string &filename)
00503 {
00504 std::filebuf fb;
00505 std::filebuf *f = fb.open (filename.c_str (), std::ios::in);
00506 if (f == NULL)
00507 return (false);
00508 std::istream is (&fb);
00509 bool res = readParameters (is);
00510 fb.close ();
00511 return (res);
00512 }
00513
00515 bool
00516 pcl::io::LZFRGB24ImageReader::readParameters (std::istream& is)
00517 {
00518 boost::property_tree::ptree pt;
00519 read_xml (is, pt, boost::property_tree::xml_parser::trim_whitespace);
00520
00521 boost::optional<boost::property_tree::ptree&> tree = pt.get_child_optional ("rgb");
00522 if (!tree)
00523 return (false);
00524
00525 parameters_.focal_length_x = tree.get ().get<double>("focal_length_x");
00526 parameters_.focal_length_y = tree.get ().get<double>("focal_length_y");
00527 parameters_.principal_point_x = tree.get ().get<double>("principal_point_x");
00528 parameters_.principal_point_y = tree.get ().get<double>("principal_point_y");
00529 PCL_DEBUG ("[pcl::io::LZFRGB24ImageReader::readParameters] Read camera parameters (fx,fy,cx,cy): %g,%g,%g,%g.\n",
00530 parameters_.focal_length_x, parameters_.focal_length_y,
00531 parameters_.principal_point_x, parameters_.principal_point_y);
00532 return (true);
00533 }
00534
00536 bool
00537 pcl::io::LZFDepth16ImageReader::readParameters (std::istream& is)
00538 {
00539 boost::property_tree::ptree pt;
00540 read_xml (is, pt, boost::property_tree::xml_parser::trim_whitespace);
00541
00542 boost::optional<boost::property_tree::ptree&> tree = pt.get_child_optional ("depth");
00543 if (!tree)
00544 return (false);
00545
00546 parameters_.focal_length_x = tree.get ().get<double>("focal_length_x");
00547 parameters_.focal_length_y = tree.get ().get<double>("focal_length_y");
00548 parameters_.principal_point_x = tree.get ().get<double>("principal_point_x");
00549 parameters_.principal_point_y = tree.get ().get<double>("principal_point_y");
00550 z_multiplication_factor_ = tree.get ().get<double>("z_multiplication_factor");
00551 PCL_DEBUG ("[pcl::io::LZFDepth16ImageReader::readParameters] Read camera parameters (fx,fy,cx,cy): %g,%g,%g,%g.\n",
00552 parameters_.focal_length_x, parameters_.focal_length_y,
00553 parameters_.principal_point_x, parameters_.principal_point_y);
00554 PCL_DEBUG ("[pcl::io::LZFDepth16ImageReader::readParameters] Multiplication factor: %g.\n", z_multiplication_factor_);
00555 return (true);
00556 }
00557