point_types.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) 2012-, Open Perception, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the copyright holder(s) nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  */
00037 #include <pcl/point_types.h>
00038 
00039 namespace pcl
00040 {
00041   std::ostream& 
00042   operator << (std::ostream& os, const PointXYZ& p)
00043   {
00044     os << "(" << p.x << "," << p.y << "," << p.z << ")";
00045     return (os);
00046   }
00047 
00048   std::ostream&
00049   operator << (std::ostream& os, const RGB& p)
00050   {
00051     os << "("
00052       << static_cast<int>(p.r) << ","
00053       << static_cast<int>(p.g) << ","
00054       << static_cast<int>(p.b) << ","
00055       << static_cast<int>(p.a) << ")";
00056     return (os);
00057   }
00058 
00059   std::ostream&
00060   operator << (std::ostream& os, const Intensity& p)
00061   {
00062     os << "( " << static_cast<int>(p.intensity) << " )";
00063     return (os);
00064   }
00065 
00066   std::ostream&
00067   operator << (std::ostream& os, const Intensity8u& p)
00068   {
00069     os << "( " << static_cast<int>(p.intensity) << " )";
00070     return (os);
00071   }
00072 
00073   std::ostream&
00074   operator << (std::ostream& os, const PointXYZI& p)
00075   {
00076     os << "(" << p.x << "," << p.y << "," << p.z << " - " << p.intensity << ")";
00077     return (os);
00078   }
00079 
00080   std::ostream& 
00081   operator << (std::ostream& os, const PointXYZL& p)
00082   {
00083     os << "(" << p.x << "," << p.y << "," << p.z << " - " << p.label << ")";
00084     return (os);
00085   }
00086 
00087   std::ostream& 
00088   operator << (std::ostream& os, const Label& p)
00089   {
00090     os << "(" << p.label << ")";
00091     return (os);
00092   }
00093 
00094   std::ostream&
00095   operator << (std::ostream& os, const PointXYZRGBA& p)
00096   {
00097     os << "(" << p.x << "," << p.y << "," << p.z << " - "
00098       << static_cast<int>(p.r) << ","
00099       << static_cast<int>(p.g) << ","
00100       << static_cast<int>(p.b) << ","
00101       << static_cast<int>(p.a) << ")";
00102     return (os);
00103   }
00104 
00105   std::ostream& 
00106   operator << (std::ostream& os, const PointXYZRGB& p)
00107   {
00108     os << "(" << p.x << "," << p.y << "," << p.z << " - "
00109       << static_cast<int>(p.r) << ","
00110       << static_cast<int>(p.g) << ","
00111       << static_cast<int>(p.b) << ")";
00112     return (os);
00113   }
00114 
00115   std::ostream& 
00116   operator << (std::ostream& os, const PointXYZRGBL& p)
00117   {
00118     os << "(" << p.x << "," << p.y << "," << p.z << " - " << p.r << "," << p.g << "," << p.b << " - " << p.label << ")";
00119     return (os);
00120   }
00121 
00122   std::ostream& 
00123   operator << (std::ostream& os, const PointXYZHSV& p)
00124   {
00125     os << "(" << p.x << "," << p.y << "," << p.z << " - " << p.h << " , " <<  p.s << " , " << p.v << ")";
00126     return (os);
00127   }
00128 
00129   std::ostream& 
00130   operator << (std::ostream& os, const PointXY& p)
00131   {
00132     os << "(" << p.x << "," << p.y << ")";
00133     return (os);
00134   }
00135 
00136   std::ostream& 
00137   operator << (std::ostream& os, const PointUV& p)
00138   {
00139     os << "(" << p.u << "," << p.v << ")";
00140     return (os);
00141   }
00142 
00143   std::ostream& 
00144   operator << (std::ostream& os, const InterestPoint& p)
00145   {
00146     os << "(" << p.x << "," << p.y << "," << p.z << " - " << p.strength << ")";
00147     return (os);
00148   }
00149 
00150   std::ostream& 
00151   operator << (std::ostream& os, const Normal& p)
00152   {
00153     os << "(" << p.normal[0] << "," << p.normal[1] << "," << p.normal[2] << " - " << p.curvature << ")";
00154     return (os);
00155   }
00156 
00157   std::ostream& 
00158   operator << (std::ostream& os, const Axis& p)
00159   {
00160     os << "(" << p.normal[0] << "," << p.normal[1] << "," << p.normal[2] << ")";
00161     return os;
00162   }
00163 
00164   std::ostream& 
00165   operator << (std::ostream& os, const _Axis& p)
00166   {
00167     os << "(" << p.normal[0] << "," << p.normal[1] << "," << p.normal[2] << ")";
00168     return os;
00169   }
00170 
00171   std::ostream& 
00172   operator << (std::ostream& os, const PointNormal& p)
00173   {
00174     os << "(" << p.x << "," << p.y << "," << p.z << " - " << p.normal[0] << "," << p.normal[1] << "," << p.normal[2] << " - " << p.curvature << ")";
00175     return (os);
00176   }
00177 
00178   std::ostream& 
00179   operator << (std::ostream& os, const PointXYZRGBNormal& p)
00180   {
00181     os << "(" << p.x << "," << p.y << "," << p.z << " - " << p.rgb << " - " << p.normal[0] << "," << p.normal[1] << "," << p.normal[2] << " - " << p.r << ", " << p.g << ", " << p.b << " - " << p.curvature << ")";
00182     return (os);
00183   }
00184 
00185   std::ostream& 
00186   operator << (std::ostream& os, const PointXYZINormal& p)
00187   {
00188     os << "(" << p.x << "," << p.y << "," << p.z << " - " << p.intensity << " - " << p.normal[0] << "," << p.normal[1] << "," << p.normal[2] << " - " << p.curvature << ")";
00189     return (os);
00190   }
00191 
00192   std::ostream& 
00193   operator << (std::ostream& os, const PointWithRange& p)
00194   {
00195     os << "(" << p.x << "," << p.y << "," << p.z << " - " << p.range << ")";
00196     return (os);
00197   }
00198 
00199   std::ostream& 
00200   operator << (std::ostream& os, const PointWithViewpoint& p)
00201   {
00202     os << "(" << p.x << "," << p.y << "," << p.z << " - " << p.vp_x << "," << p.vp_y << "," << p.vp_z << ")";
00203     return (os);
00204   }
00205 
00206   std::ostream& 
00207   operator << (std::ostream& os, const MomentInvariants& p)
00208   {
00209     os << "(" << p.j1 << "," << p.j2 << "," << p.j3 << ")";
00210     return (os);
00211   }
00212 
00213   std::ostream& 
00214   operator << (std::ostream& os, const PrincipalRadiiRSD& p)
00215   {
00216     os << "(" << p.r_min << "," << p.r_max << ")";
00217     return (os);
00218   }
00219 
00220   std::ostream& 
00221   operator << (std::ostream& os, const Boundary& p)
00222   {
00223     os << p.boundary_point;
00224     return (os);
00225   }
00226 
00227   std::ostream& 
00228   operator << (std::ostream& os, const PrincipalCurvatures& p)
00229   {
00230     os << "(" << p.principal_curvature[0] << "," << p.principal_curvature[1] << "," << p.principal_curvature[2] << " - " << p.pc1 << "," << p.pc2 << ")";
00231     return (os);
00232   }
00233 
00234   std::ostream& 
00235   operator << (std::ostream& os, const PFHSignature125& p)
00236   {
00237     for (int i = 0; i < 125; ++i)
00238     os << (i == 0 ? "(" : "") << p.histogram[i] << (i < 124 ? ", " : ")");
00239     return (os);
00240   }
00241 
00242   std::ostream& 
00243   operator << (std::ostream& os, const PFHRGBSignature250& p)
00244   {
00245     for (int i = 0; i < 250; ++i)
00246     os << (i == 0 ? "(" : "") << p.histogram[i] << (i < 249 ? ", " : ")");
00247     return (os);
00248   }
00249 
00250   std::ostream& 
00251   operator << (std::ostream& os, const PPFSignature& p)
00252   {
00253     os << "(" << p.f1 << ", " << p.f2 << ", " << p.f3 << ", " << p.f4 << ", " << p.alpha_m << ")";
00254     return (os);
00255   }
00256 
00257   std::ostream& 
00258   operator << (std::ostream& os, const PPFRGBSignature& p)
00259    {
00260      os << "(" << p.f1 << ", " << p.f2 << ", " << p.f3 << ", " << p.f4 << ", " <<
00261          p.r_ratio << ", " << p.g_ratio << ", " << p.b_ratio << ", " << p.alpha_m << ")";
00262      return (os);
00263    }
00264 
00265   std::ostream& 
00266   operator << (std::ostream& os, const NormalBasedSignature12& p)
00267   {
00268     for (int i = 0; i < 12; ++i)
00269     os << (i == 0 ? "(" : "") << p.values[i] << (i < 11 ? ", " : ")");
00270     return (os);
00271   }
00272 
00273   std::ostream& 
00274   operator << (std::ostream& os, const ShapeContext1980& p)
00275   {
00276     for (int i = 0; i < 9; ++i)
00277     os << (i == 0 ? "(" : "") << p.rf[i] << (i < 8 ? ", " : ")");
00278     for (size_t i = 0; i < 1980; ++i)
00279       os << (i == 0 ? "(" : "") << p.descriptor[i] << (i < 1979 ? ", " : ")");
00280     return (os);
00281   }
00282 
00283   std::ostream& 
00284   operator << (std::ostream& os, const SHOT352& p)
00285   {
00286     for (int i = 0; i < 9; ++i)
00287     os << (i == 0 ? "(" : "") << p.rf[i] << (i < 8 ? ", " : ")");
00288     for (size_t i = 0; i < 352; ++i)
00289     os << (i == 0 ? "(" : "") << p.descriptor[i] << (i < 351 ? ", " : ")");
00290     return (os);
00291   }
00292 
00293   std::ostream& 
00294   operator << (std::ostream& os, const SHOT1344& p)
00295   {
00296     for (int i = 0; i < 9; ++i)
00297     os << (i == 0 ? "(" : "") << p.rf[i] << (i < 8 ? ", " : ")");
00298     for (size_t i = 0; i < 1344; ++i)
00299     os << (i == 0 ? "(" : "") << p.descriptor[i] << (i < 1343 ? ", " : ")");
00300     return (os);
00301   }
00302 
00303   std::ostream& 
00304   operator << (std::ostream& os, const ReferenceFrame& p)
00305   {
00306     os << "("
00307        << p.x_axis[0] << " " << p.x_axis[1] << " " << p.x_axis[2] << ","
00308        << p.y_axis[0] << " " << p.y_axis[1] << " " << p.y_axis[2] << ","
00309        << p.z_axis[0] << " " << p.z_axis[1] << " " << p.z_axis[2] << ")";
00310     return (os);
00311   }
00312 
00313   std::ostream& 
00314   operator << (std::ostream& os, const FPFHSignature33& p)
00315   {
00316     for (int i = 0; i < 33; ++i)
00317     os << (i == 0 ? "(" : "") << p.histogram[i] << (i < 32 ? ", " : ")");
00318     return (os);
00319   }
00320 
00321   std::ostream& 
00322   operator << (std::ostream& os, const VFHSignature308& p)
00323   {
00324     for (int i = 0; i < 308; ++i)
00325     os << (i == 0 ? "(" : "") << p.histogram[i] << (i < 307 ? ", " : ")");
00326     return (os);
00327   }
00328 
00329   std::ostream& 
00330   operator << (std::ostream& os, const ESFSignature640& p)
00331   {
00332     for (int i = 0; i < 640; ++i)
00333     os << (i == 0 ? "(" : "") << p.histogram[i] << (i < 639 ? ", " : ")");
00334     return (os);
00335   }
00336 
00337   std::ostream& 
00338   operator << (std::ostream& os, const GFPFHSignature16& p)
00339   {
00340     for (int i = 0; i < p.descriptorSize (); ++i)
00341     os << (i == 0 ? "(" : "") << p.histogram[i] << (i < (p.descriptorSize () - 1) ? ", " : ")");
00342     return (os);
00343   }
00344 
00345   std::ostream& 
00346   operator << (std::ostream& os, const Narf36& p)
00347   {
00348     os << p.x<<","<<p.y<<","<<p.z<<" - "<<p.roll*360.0/M_PI<<"deg,"<<p.pitch*360.0/M_PI<<"deg,"<<p.yaw*360.0/M_PI<<"deg - ";
00349     for (int i = 0; i < 36; ++i)
00350     os << (i == 0 ? "(" : "") << p.descriptor[i] << (i < 35 ? ", " : ")");
00351     return (os);
00352   }
00353 
00354   std::ostream& 
00355   operator << (std::ostream& os, const BorderDescription& p)
00356   {
00357     os << "(" << p.x << "," << p.y << ")";
00358     return (os);
00359   }
00360 
00361   std::ostream& 
00362   operator << (std::ostream& os, const IntensityGradient& p)
00363   {
00364     os << "(" << p.gradient[0] << "," << p.gradient[1] << "," << p.gradient[2] << ")";
00365     return (os);
00366   }
00367 
00368   std::ostream& 
00369   operator << (std::ostream& os, const PointWithScale& p)
00370   {
00371     os << "(" << p.x << "," << p.y << "," << p.z << " - " << p.scale << "," << p.angle << "," << p.response << "," << p.octave << ")";
00372     return (os);
00373   }
00374 
00375   std::ostream& 
00376   operator << (std::ostream& os, const PointSurfel& p)
00377   {
00378     const unsigned char* rgba_ptr = reinterpret_cast<const unsigned char*>(&p.rgba);
00379     os <<
00380     "(" << p.x << "," << p.y << "," << p.z << " - " <<
00381     p.normal_x << "," << p.normal_y << "," << p.normal_z << " - "
00382     << static_cast<int>(*rgba_ptr) << ","
00383     << static_cast<int>(*(rgba_ptr+1)) << ","
00384     << static_cast<int>(*(rgba_ptr+2)) << ","
00385     << static_cast<int>(*(rgba_ptr+3)) << " - " <<
00386     p.radius << " - " << p.confidence << " - " << p.curvature << ")";
00387     return (os);
00388   }
00389 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:31:02