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 #ifndef PCL_IO_PCD_IO_H_
00039 #define PCL_IO_PCD_IO_H_
00040
00041 #include "pcl/io/io.h"
00042
00043 namespace pcl
00044 {
00048
00051 class PCDReader
00052 {
00053 public:
00077 enum
00078 {
00079 PCD_V6 = 0,
00080 PCD_V7 = 1
00081 };
00082
00097 int readHeader (const std::string &file_name, sensor_msgs::PointCloud2 &cloud,
00098 Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version);
00099
00107 int read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud,
00108 Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version);
00109
00119 int read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud);
00120
00125 template<typename PointT> inline int
00126 read (const std::string &file_name, pcl::PointCloud<PointT> &cloud)
00127 {
00128 sensor_msgs::PointCloud2 blob;
00129 int pcd_version;
00130 int res = read (file_name, blob, cloud.sensor_origin_, cloud.sensor_orientation_, pcd_version);
00131
00132
00133 if (res < 0)
00134 return res;
00135 pcl::fromROSMsg (blob, cloud);
00136 return 0;
00137 }
00138 };
00139
00143
00146 class PCDWriter
00147 {
00148 public:
00154 std::string
00155 generateHeaderBinary (const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin,
00156 const Eigen::Quaternionf &orientation);
00162 std::string
00163 generateHeaderASCII (const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin,
00164 const Eigen::Quaternionf &orientation);
00165
00173 int writeASCII (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud,
00174 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
00175 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00176 int precision = 7);
00177
00184 int writeBinary (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud,
00185 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
00186 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity ());
00187
00195 inline int
00196 write (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud,
00197 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
00198 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00199 bool binary = false)
00200 {
00201 if (binary)
00202 return (writeBinary (file_name, cloud, origin, orientation));
00203 else
00204 return (writeASCII (file_name, cloud, origin, orientation, 7));
00205 }
00206
00214 inline int
00215 write (const std::string &file_name, const sensor_msgs::PointCloud2::ConstPtr &cloud,
00216 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
00217 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00218 bool binary = false)
00219 {
00220 return (write (file_name, *cloud, origin, orientation, binary));
00221 }
00222
00228 template<typename PointT> inline int
00229 write (const std::string &file_name, const pcl::PointCloud<PointT> &cloud, bool binary = false)
00230 {
00231 Eigen::Vector4f origin = cloud.sensor_origin_;
00232 Eigen::Quaternionf orientation = cloud.sensor_orientation_;
00233
00234 sensor_msgs::PointCloud2 blob;
00235 pcl::toROSMsg (cloud, blob);
00236
00237
00238 return (write (file_name, blob, origin, orientation, binary));
00239 }
00240 };
00241
00242 namespace io
00243 {
00245
00250 inline int
00251 loadPCDFile (const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
00252 {
00253 pcl::PCDReader p;
00254 return (p.read (file_name, cloud));
00255 }
00256
00258
00264 inline int
00265 loadPCDFile (const std::string &file_name, sensor_msgs::PointCloud2 &cloud,
00266 Eigen::Vector4f &origin, Eigen::Quaternionf &orientation)
00267 {
00268 pcl::PCDReader p;
00269 int pcd_version;
00270 return (p.read (file_name, cloud, origin, orientation, pcd_version));
00271 }
00272
00274
00278 template<typename PointT> inline int
00279 loadPCDFile (const std::string &file_name, pcl::PointCloud<PointT> &cloud)
00280 {
00281 pcl::PCDReader p;
00282 return (p.read (file_name, cloud));
00283 }
00284
00286
00293 inline int
00294 savePCDFile (std::string file_name, const sensor_msgs::PointCloud2 &cloud,
00295 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
00296 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
00297 bool binary_mode = false)
00298 {
00299 PCDWriter w;
00300 return (w.write (file_name, cloud, origin, orientation, binary_mode));
00301 }
00302
00304
00309 template<typename PointT> inline int
00310 savePCDFile (const std::string &file_name, const pcl::PointCloud<PointT> &cloud, bool binary_mode = false)
00311 {
00312 PCDWriter w;
00313 return (w.write<PointT> (file_name, cloud, binary_mode));
00314 }
00315
00316
00318
00323 template<typename PointT> inline int
00324 savePCDFileASCII (const std::string &file_name, const pcl::PointCloud<PointT> &cloud)
00325 {
00326 PCDWriter w;
00327 return (w.write<PointT> (file_name, cloud, false));
00328 }
00329
00330
00332
00337 template<typename PointT> inline int
00338 savePCDFileBinary (const std::string &file_name, const pcl::PointCloud<PointT> &cloud)
00339 {
00340 PCDWriter w;
00341 return (w.write<PointT> (file_name, cloud, true));
00342 }
00343
00344
00346
00352 template<typename PointT> int
00353 savePCDFile (const std::string &file_name, const pcl::PointCloud<PointT> &cloud,
00354 const std::vector<int> &indices, bool binary_mode = false)
00355 {
00356
00357 pcl::PointCloud<PointT> cloud_out;
00358 copyPointCloud (cloud, indices, cloud_out);
00359
00360 PCDWriter w;
00361 return (w.write<PointT> (file_name, cloud_out, binary_mode));
00362 }
00363 };
00364 }
00365
00366 #endif //#ifndef PCL_IO_PCD_IO_H_