transform_point_cloud.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2011-2012, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id$
00038  *
00039  */
00040 
00041 #include <pcl/PCLPointCloud2.h>
00042 #include <pcl/conversions.h>
00043 #include <pcl/io/pcd_io.h>
00044 #include <pcl/console/print.h>
00045 #include <pcl/console/parse.h>
00046 #include <pcl/console/time.h>
00047 #include <pcl/common/transforms.h>
00048 #include <cmath>
00049 
00050 using namespace pcl;
00051 using namespace pcl::io;
00052 using namespace pcl::console;
00053 
00054 void
00055 printHelp (int, char **argv)
00056 {
00057   print_error ("Syntax is: %s input.pcd output.pcd <options>\n", argv[0]);
00058   print_info ("  where options are:\n");
00059   print_info ("           -trans dx,dy,dz           = the translation (default: "); 
00060   print_value ("%0.1f, %0.1f, %0.1f", 0, 0, 0); print_info (")\n");
00061   print_info ("           -quat w,x,y,z             = rotation as quaternion\n"); 
00062   print_info ("           -axisangle ax,ay,az,theta = rotation in axis-angle form\n"); 
00063   print_info ("           -scale x,y,z              = scale each dimension with these values\n"); 
00064   print_info ("           -matrix v1,v2,...,v8,v9   = a 3x3 affine transform\n");
00065   print_info ("           -matrix v1,v2,...,v15,v16 = a 4x4 transformation matrix\n");
00066   print_info ("   Note: If a rotation is not specified, it will default to no rotation.\n");
00067   print_info ("         If redundant or conflicting transforms are specified, then:\n");
00068   print_info ("           -axisangle will override -quat\n");
00069   print_info ("           -matrix (3x3) will take override -axisangle and -quat\n");
00070   print_info ("           -matrix (4x4) will take override all other arguments\n");
00071 
00072 }
00073 
00074 void 
00075 printElapsedTimeAndNumberOfPoints (double t, int w, int h = 1)
00076 {
00077   print_info ("[done, "); print_value ("%g", t); print_info (" ms : "); 
00078   print_value ("%d", w*h); print_info (" points]\n");
00079 }
00080 
00081 bool
00082 loadCloud (const std::string &filename, pcl::PCLPointCloud2 &cloud)
00083 {
00084   TicToc tt;
00085   print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00086 
00087   tt.tic ();
00088   if (loadPCDFile (filename, cloud) < 0)
00089     return (false);
00090 
00091   printElapsedTimeAndNumberOfPoints (tt.toc (), cloud.width, cloud.height);
00092 
00093   print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00094 
00095   return (true);
00096 }
00097 
00098 template <typename PointT> void
00099 transformPointCloudHelper (PointCloud<PointT> & input, PointCloud<PointT> & output,
00100                            Eigen::Matrix4f &tform)
00101 {
00102   transformPointCloud (input, output, tform);
00103 }
00104 
00105 template <> void
00106 transformPointCloudHelper (PointCloud<PointNormal> & input, PointCloud<PointNormal> & output, 
00107                            Eigen::Matrix4f &tform)
00108 {
00109   transformPointCloudWithNormals (input, output, tform);
00110 }
00111 
00112 template <> void
00113 transformPointCloudHelper<PointXYZRGBNormal> (PointCloud<PointXYZRGBNormal> & input, 
00114                                               PointCloud<PointXYZRGBNormal> & output, 
00115                                               Eigen::Matrix4f &tform)
00116 {
00117   transformPointCloudWithNormals (input, output, tform);
00118 }
00119 
00120 
00121 template <typename PointT> void
00122 transformPointCloud2AsType (const pcl::PCLPointCloud2 &input, pcl::PCLPointCloud2 &output,
00123                             Eigen::Matrix4f &tform)
00124 {
00125   PointCloud<PointT> cloud;
00126   fromPCLPointCloud2 (input, cloud);
00127   transformPointCloudHelper (cloud, cloud, tform);
00128   toPCLPointCloud2 (cloud, output);
00129 }
00130 
00131 void
00132 transformPointCloud2 (const pcl::PCLPointCloud2 &input, pcl::PCLPointCloud2 &output,
00133                       Eigen::Matrix4f &tform)
00134 {
00135   // Check for 'rgb' and 'normals' fields
00136   bool has_rgb = false;
00137   bool has_normals = false;
00138   for (size_t i = 0; i < input.fields.size (); ++i)
00139   {
00140     if (input.fields[i].name == "rgb")
00141       has_rgb = true;
00142     if (input.fields[i].name == "normal_x")
00143       has_normals = true;
00144   }
00145 
00146   // Handle the following four point types differently: PointXYZ, PointXYZRGB, PointNormal, PointXYZRGBNormal
00147   if (!has_rgb && !has_normals)
00148     transformPointCloud2AsType<PointXYZ> (input, output, tform);
00149   else if (has_rgb && !has_normals)
00150     transformPointCloud2AsType<PointXYZRGB> (input, output, tform);
00151   else if (!has_rgb && has_normals)
00152     transformPointCloud2AsType<PointNormal> (input, output, tform);
00153   else // (has_rgb && has_normals)
00154     transformPointCloud2AsType<PointXYZRGBNormal> (input, output, tform);
00155 }
00156 
00157 void
00158 compute (const pcl::PCLPointCloud2::ConstPtr &input, pcl::PCLPointCloud2 &output,
00159          Eigen::Matrix4f &tform)
00160 {
00161   TicToc tt;
00162   tt.tic ();
00163   
00164   print_highlight ("Transforming ");
00165 
00166   transformPointCloud2 (*input, output, tform);
00167 
00168   printElapsedTimeAndNumberOfPoints (tt.toc (), output.width, output.height);
00169 }
00170 
00171 void
00172 saveCloud (const std::string &filename, const pcl::PCLPointCloud2 &output)
00173 {
00174   TicToc tt;
00175   tt.tic ();
00176 
00177   print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00178 
00179   PCDWriter w;
00180   w.writeBinaryCompressed (filename, output);
00181   
00182   printElapsedTimeAndNumberOfPoints (tt.toc (), output.width, output.height);
00183 }
00184 
00185 template <typename T> void
00186 multiply (pcl::PCLPointCloud2 &cloud, int field_offset, double multiplier)
00187 {
00188   T val;
00189   memcpy (&val, &cloud.data[field_offset], sizeof (T));
00190   val = static_cast<T> (val * static_cast<T> (multiplier));
00191   memcpy (&cloud.data[field_offset], &val, sizeof (T));
00192 }
00193 
00194 void
00195 scaleInPlace (pcl::PCLPointCloud2 &cloud, double* multiplier)
00196 {
00197   // Obtain the x, y, and z indices
00198   int x_idx = pcl::getFieldIndex (cloud, "x");
00199   int y_idx = pcl::getFieldIndex (cloud, "y");
00200   int z_idx = pcl::getFieldIndex (cloud, "z");
00201   Eigen::Array3i xyz_offset (cloud.fields[x_idx].offset, cloud.fields[y_idx].offset, cloud.fields[z_idx].offset);
00202  
00203   for (uint32_t cp = 0; cp < cloud.width * cloud.height; ++cp)
00204   {
00205     // Assume all 3 fields are the same (XYZ)
00206     assert ((cloud.fields[x_idx].datatype == cloud.fields[y_idx].datatype));
00207     assert ((cloud.fields[x_idx].datatype == cloud.fields[z_idx].datatype));
00208     switch (cloud.fields[x_idx].datatype)
00209     {
00210       case pcl::PCLPointField::INT8:
00211         for (int i = 0; i < 3; ++i) multiply<int8_t> (cloud, xyz_offset[i], multiplier[i]);
00212         break;
00213       case pcl::PCLPointField::UINT8:
00214         for (int i = 0; i < 3; ++i) multiply<uint8_t> (cloud, xyz_offset[i], multiplier[i]);
00215         break;
00216       case pcl::PCLPointField::INT16:
00217         for (int i = 0; i < 3; ++i) multiply<int16_t> (cloud, xyz_offset[i], multiplier[i]);
00218         break;
00219       case pcl::PCLPointField::UINT16:
00220         for (int i = 0; i < 3; ++i) multiply<uint16_t> (cloud, xyz_offset[i], multiplier[i]);
00221         break;
00222       case pcl::PCLPointField::INT32:
00223         for (int i = 0; i < 3; ++i) multiply<int32_t> (cloud, xyz_offset[i], multiplier[i]);
00224         break;
00225       case pcl::PCLPointField::UINT32:
00226         for (int i = 0; i < 3; ++i) multiply<uint32_t> (cloud, xyz_offset[i], multiplier[i]);
00227         break;
00228       case pcl::PCLPointField::FLOAT32:
00229         for (int i = 0; i < 3; ++i) multiply<float> (cloud, xyz_offset[i], multiplier[i]);
00230         break;
00231       case pcl::PCLPointField::FLOAT64:
00232         for (int i = 0; i < 3; ++i) multiply<double> (cloud, xyz_offset[i], multiplier[i]);
00233         break;
00234     }
00235     xyz_offset += cloud.point_step;
00236   }
00237 }
00238 
00239 
00240 /* ---[ */
00241 int
00242 main (int argc, char** argv)
00243 {
00244   print_info ("Transform a cloud. For more information, use: %s -h\n", argv[0]);
00245 
00246   bool help = false;
00247   parse_argument (argc, argv, "-h", help);
00248   if (argc < 3 || help)
00249   {
00250     printHelp (argc, argv);
00251     return (-1);
00252   }
00253 
00254   // Parse the command line arguments for .pcd files
00255   std::vector<int> p_file_indices;
00256   p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00257   if (p_file_indices.size () != 2)
00258   {
00259     print_error ("Need one input PCD file and one output PCD file to continue.\n");
00260     return (-1);
00261   }
00262 
00263   // Initialize the transformation matrix
00264   Eigen::Matrix4f tform; 
00265   tform.setIdentity ();
00266 
00267   // Command line parsing
00268   float dx, dy, dz;
00269   std::vector<float> values;
00270 
00271   if (parse_3x_arguments (argc, argv, "-trans", dx, dy, dz) > -1)
00272   {
00273     tform (0, 3) = dx;
00274     tform (1, 3) = dy;
00275     tform (2, 3) = dz;
00276   }
00277 
00278   if (parse_x_arguments (argc, argv, "-quat", values) > -1)
00279   {
00280     if (values.size () == 4)
00281     {
00282       const float& x = values[0];
00283       const float& y = values[1];
00284       const float& z = values[2];
00285       const float& w = values[3];
00286       tform.topLeftCorner (3, 3) = Eigen::Matrix3f (Eigen::Quaternionf (w, x, y, z));
00287     }
00288     else
00289     {
00290       print_error ("Wrong number of values given (%zu): ", values.size ());
00291       print_error ("The quaternion specified with -quat must contain 4 elements (w,x,y,z).\n");
00292     }
00293   }
00294 
00295   if (parse_x_arguments (argc, argv, "-axisangle", values) > -1)
00296   {
00297     if (values.size () == 4)
00298     {
00299       const float& ax = values[0];
00300       const float& ay = values[1];
00301       const float& az = values[2];
00302       const float& theta = values[3];
00303       tform.topLeftCorner (3, 3) = Eigen::Matrix3f (Eigen::AngleAxisf (theta, Eigen::Vector3f (ax, ay, az)));
00304     }
00305     else
00306     {
00307       print_error ("Wrong number of values given (%zu): ", values.size ());
00308       print_error ("The rotation specified with -axisangle must contain 4 elements (ax,ay,az,theta).\n");
00309     }
00310   }
00311 
00312   if (parse_x_arguments (argc, argv, "-matrix", values) > -1)
00313   {
00314     if (values.size () == 9 || values.size () == 16)
00315     {
00316       int n = values.size () == 9 ? 3 : 4;
00317       for (int r = 0; r < n; ++r)
00318         for (int c = 0; c < n; ++c)
00319           tform (r, c) = values[n*r+c];
00320     }
00321     else
00322     {
00323       print_error ("Wrong number of values given (%zu): ", values.size ());
00324       print_error ("The transformation specified with -matrix must be 3x3 (9) or 4x4 (16).\n");
00325     }
00326   }
00327 
00328   // Load the first file
00329   pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2);
00330   if (!loadCloud (argv[p_file_indices[0]], *cloud)) 
00331     return (-1);
00332 
00333   // Apply the transform
00334   pcl::PCLPointCloud2 output;
00335   compute (cloud, output, tform);
00336 
00337   // Check if a scaling parameter has been given
00338   double divider[3];
00339   if (parse_3x_arguments (argc, argv, "-scale", divider[0], divider[1], divider[2]) > -1)
00340   {
00341     print_highlight ("Scaling XYZ data with the following values: %f, %f, %f\n", divider[0], divider[1], divider[2]);
00342     scaleInPlace (output, divider);
00343   }
00344 
00345   // Save into the second file
00346   saveCloud (argv[p_file_indices[1]], output);
00347 }
00348 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:36:53