point_operators.h
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) 2010-2011, Willow Garage, 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 Willow Garage, Inc. 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  * $Id: point_operators.h 5355 2012-03-27 23:52:01Z nizar $
00037  *
00038  */
00039 
00040 #ifndef PCL_COMMON_POINT_OPERATORS_H
00041 #define PCL_COMMON_POINT_OPERATORS_H
00042 
00043 #include <pcl/point_types.h>
00044 
00045 namespace pcl
00046 {
00047   namespace common
00048   {
00053 
00054     template <typename PointT> inline PointT
00055     operator+ (const PointT& lhs, const PointT& rhs)
00056     {
00057       PointT result = lhs;
00058       result.getVector3fMap () += rhs.getVector3fMap ();
00059       return (result);
00060     }
00062     template <typename PointT> inline PointT
00063     operator- (const PointT& lhs, const PointT& rhs)
00064     {
00065       PointT result = lhs;
00066       result.getVector3fMap () -= rhs.getVector3fMap ();
00067       return (result);
00068     }
00070     template <typename PointT> inline PointT
00071     operator* (const float& scalar, const PointT& p)
00072     {
00073       PointT result = p;
00074       result.getVector3fMap () *= scalar;
00075       return (result);
00076     }
00078     template <typename PointT> inline PointT
00079     operator* (const PointT& p, const float& scalar)
00080     {
00081       PointT result = p;
00082       result.getVector3fMap () *= scalar;
00083       return (result);
00084     }
00086     template <typename PointT> inline PointT
00087     operator/ (const float& scalar, const PointT& p)
00088     {
00089       PointT result = p;
00090       result.getVector3fMap () /= scalar;
00091       return (result);
00092     }
00094     template <typename PointT> inline PointT
00095     operator/ (const PointT& p, const float& scalar)
00096     {
00097       PointT result = p;
00098       result.getVector3fMap () /= scalar;
00099       return (result);
00100     }
00102     template <typename PointT> inline PointT&
00103     operator+= (PointT& lhs, const PointT& rhs)
00104     {
00105       lhs.getVector3fMap () += rhs.getVector3fMap ();
00106       return (lhs);
00107     }
00109     template <typename PointT> inline PointT&
00110     operator-= (PointT& lhs, const PointT& rhs)
00111     {
00112       lhs.getVector3fMap () -= rhs.getVector3fMap ();
00113       return (lhs);
00114     }
00116     template <typename PointT> inline PointT&
00117     operator*= (PointT& p, const float& scalar)
00118     {
00119       p.getVector3fMap () *= scalar;
00120       return (PointT ());
00121     }
00123     template <typename PointT> inline PointT&
00124     operator/= (PointT& p, const float& scalar)
00125     {
00126       p.getVector3fMap () /= scalar;
00127       return (p);
00128     }
00129 
00131     template <> inline pcl::PointXYZI
00132     operator+ (const pcl::PointXYZI& lhs, const pcl::PointXYZI& rhs)
00133     {
00134       pcl::PointXYZI result = lhs;
00135       result.getVector3fMap () += rhs.getVector3fMap ();
00136       result.intensity += rhs.intensity;
00137       return (result);
00138     }
00140     template <> inline pcl::PointXYZI
00141     operator- (const pcl::PointXYZI& lhs, const pcl::PointXYZI& rhs)
00142     {
00143       pcl::PointXYZI result = lhs;
00144       result.getVector3fMap () -= rhs.getVector3fMap ();
00145       result.intensity -= rhs.intensity;
00146       return (result);
00147     }
00149     template <> inline pcl::PointXYZI
00150     operator* (const float& scalar, const pcl::PointXYZI& p)
00151     {
00152       pcl::PointXYZI result = p;
00153       result.getVector3fMap () *= scalar;
00154       result.intensity *= scalar;
00155       return (result);
00156     }
00158     template <> inline pcl::PointXYZI
00159     operator* (const pcl::PointXYZI& p, const float& scalar)
00160     {
00161       pcl::PointXYZI result = p;
00162       result.getVector3fMap () *= scalar;
00163       result.intensity *= scalar;
00164       return (result);
00165     }
00167     template <> inline pcl::PointXYZI&
00168     operator+= (pcl::PointXYZI& lhs, const pcl::PointXYZI& rhs)
00169     {
00170       lhs.getVector3fMap () += rhs.getVector3fMap ();
00171       lhs.intensity += rhs.intensity;
00172       return (lhs);
00173     }
00175     template <> inline pcl::PointXYZI&
00176     operator-= (pcl::PointXYZI& lhs, const pcl::PointXYZI& rhs)
00177     {
00178       lhs.getVector3fMap () -= rhs.getVector3fMap ();
00179       lhs.intensity -= rhs.intensity;
00180       return (lhs);
00181     }
00183     template <> inline pcl::PointXYZI&
00184     operator*= (pcl::PointXYZI& lhs, const float& scalar)
00185     {
00186       lhs.getVector3fMap () *= scalar;
00187       lhs.intensity *= scalar;
00188       return (lhs);
00189     }
00190     template <> inline pcl::PointXYZINormal
00191     operator+ (const pcl::PointXYZINormal& lhs, const pcl::PointXYZINormal& rhs)
00192     {
00193       pcl::PointXYZINormal result = lhs;
00194       result.getVector3fMap () += rhs.getVector3fMap ();
00195       result.getNormalVector3fMap () += rhs.getNormalVector3fMap ();
00196       result.intensity += rhs.intensity;
00197       result.curvature += rhs.curvature;
00198       return (result);
00199     }
00200 
00201     template <> inline pcl::PointXYZINormal
00202     operator- (const pcl::PointXYZINormal& lhs, const pcl::PointXYZINormal& rhs)
00203     {
00204       pcl::PointXYZINormal result = lhs;
00205       result.getVector3fMap () -= rhs.getVector3fMap ();
00206       result.getNormalVector3fMap () -= rhs.getNormalVector3fMap ();
00207       result.intensity -= rhs.intensity;
00208       result.curvature -= rhs.curvature;
00209       return (result);
00210     }
00211 
00212     template <> inline pcl::PointXYZINormal&
00213     operator+= (pcl::PointXYZINormal& lhs, const pcl::PointXYZINormal& rhs)
00214     {
00215       lhs.getVector3fMap () += rhs.getVector3fMap ();
00216       lhs.getNormalVector3fMap () += rhs.getNormalVector3fMap ();
00217       lhs.intensity += rhs.intensity;
00218       lhs.curvature += rhs.curvature;
00219       return (lhs);
00220     }
00221 
00222     template <> inline pcl::PointXYZINormal&
00223     operator-= (pcl::PointXYZINormal& lhs, const pcl::PointXYZINormal& rhs)
00224     {
00225       lhs.getVector3fMap () -= rhs.getVector3fMap ();
00226       lhs.getNormalVector3fMap () -= rhs.getNormalVector3fMap ();
00227       lhs.intensity-= rhs.intensity;
00228       lhs.curvature-= rhs.curvature;
00229       return (lhs);
00230     }
00231 
00232     template <> inline pcl::PointXYZINormal&
00233     operator*= (pcl::PointXYZINormal& lhs, const float& scalar)
00234     {
00235       lhs.getVector3fMap () *= scalar;
00236       lhs.getNormalVector3fMap () *= scalar;
00237       lhs.intensity *= scalar;
00238       lhs.curvature *= scalar;
00239       return (lhs);
00240     }
00241 
00242     template <> inline pcl::PointXYZINormal
00243     operator* (const float& scalar, const pcl::PointXYZINormal& p)
00244     {
00245       pcl::PointXYZINormal result = p;
00246       result.getVector3fMap () *= scalar;
00247       result.getNormalVector3fMap () *= scalar;
00248       result.intensity *= scalar;
00249       result.curvature *= scalar;
00250       return (result);
00251     }
00252 
00253     template <> inline pcl::PointXYZINormal
00254     operator* (const pcl::PointXYZINormal& p, const float& scalar)
00255     {
00256       return (operator* (scalar, p));
00257     }
00258 
00260     template <> inline pcl::Normal
00261     operator+ (const pcl::Normal& lhs, const pcl::Normal& rhs)
00262     {
00263       pcl::Normal result = lhs;
00264       result.getNormalVector3fMap () += rhs.getNormalVector3fMap ();
00265       result.curvature += rhs.curvature;
00266       return (result);
00267     }
00269     template <> inline pcl::Normal
00270     operator- (const pcl::Normal& lhs, const pcl::Normal& rhs)
00271     {
00272       pcl::Normal result = lhs;
00273       result.getNormalVector3fMap () -= rhs.getNormalVector3fMap ();
00274       result.curvature -= rhs.curvature;
00275       return (result);
00276     }
00278     template <> inline pcl::Normal
00279     operator* (const float& scalar, const pcl::Normal& p)
00280     {
00281       pcl::Normal result = p;
00282       result.getNormalVector3fMap () *= scalar;
00283       result.curvature *= scalar;
00284       return (result);
00285     }
00287     template <> inline pcl::Normal
00288     operator* (const pcl::Normal& p, const float& scalar)
00289     {
00290       pcl::Normal result = p;
00291       result.getNormalVector3fMap () *= scalar;
00292       result.curvature *= scalar;
00293       return (result);
00294     }
00296     template <> inline pcl::Normal&
00297     operator+= (pcl::Normal& lhs, const pcl::Normal& rhs)
00298     {
00299       lhs.getNormalVector3fMap () += rhs.getNormalVector3fMap ();
00300       lhs.curvature += rhs.curvature;
00301       return (lhs);
00302     }
00304     template <> inline pcl::Normal&
00305     operator-= (pcl::Normal& lhs, const pcl::Normal& rhs)
00306     {
00307       lhs.getNormalVector3fMap () -= rhs.getNormalVector3fMap ();
00308       lhs.curvature -= rhs.curvature;
00309       return (lhs);
00310     }
00312     template <> inline pcl::Normal&
00313     operator*= (pcl::Normal& lhs, const float& scalar)
00314     {
00315       lhs.getNormalVector3fMap () *= scalar;
00316       lhs.curvature *= scalar;
00317       return (lhs);
00318     }
00319 
00321     template <> inline pcl::PointXYZRGB
00322     operator+ (const pcl::PointXYZRGB& lhs, const pcl::PointXYZRGB& rhs)
00323     {
00324       pcl::PointXYZRGB result;
00325       result.getVector3fMap () = lhs.getVector3fMap ();
00326       result.getVector3fMap () += rhs.getVector3fMap ();
00327       result.r = static_cast<uint8_t> (lhs.r + rhs.r);
00328       result.g = static_cast<uint8_t> (lhs.g + rhs.g);
00329       result.b = static_cast<uint8_t> (lhs.b + rhs.b);
00330       return (result);
00331     }
00333     template <> inline pcl::PointXYZRGB
00334     operator- (const pcl::PointXYZRGB& lhs, const pcl::PointXYZRGB& rhs)
00335     {
00336       pcl::PointXYZRGB result;
00337       result.getVector3fMap () = lhs.getVector3fMap ();
00338       result.getVector3fMap () -= rhs.getVector3fMap ();
00339       result.r = static_cast<uint8_t> (lhs.r - rhs.r);
00340       result.g = static_cast<uint8_t> (lhs.g - rhs.g);
00341       result.b = static_cast<uint8_t> (lhs.b - rhs.b);
00342       return (result);
00343     }
00344 
00345     template <> inline pcl::PointXYZRGB
00346     operator* (const float& scalar, const pcl::PointXYZRGB& p)
00347     {
00348       pcl::PointXYZRGB result;
00349       result.getVector3fMap () = p.getVector3fMap ();
00350       result.getVector3fMap () *= scalar;
00351       result.r = static_cast<uint8_t> (scalar * p.r);
00352       result.g = static_cast<uint8_t> (scalar * p.g);
00353       result.b = static_cast<uint8_t> (scalar * p.b);
00354       return (result);
00355     }
00356 
00357     template <> inline pcl::PointXYZRGB
00358     operator* (const pcl::PointXYZRGB& p, const float& scalar)
00359     {
00360       pcl::PointXYZRGB result;
00361       result.getVector3fMap () = p.getVector3fMap ();
00362       result.getVector3fMap () *= scalar;
00363       result.r = static_cast<uint8_t> (scalar * p.r);
00364       result.g = static_cast<uint8_t> (scalar * p.g);
00365       result.b = static_cast<uint8_t> (scalar * p.b);
00366       return (result);
00367     }
00368 
00369     template <> inline pcl::PointXYZRGB&
00370     operator+= (pcl::PointXYZRGB& lhs, const pcl::PointXYZRGB& rhs)
00371     {
00372       lhs.getVector3fMap () += rhs.getVector3fMap ();
00373       lhs.r = static_cast<uint8_t> (lhs.r + rhs.r);
00374       lhs.g = static_cast<uint8_t> (lhs.g + rhs.g);
00375       lhs.b = static_cast<uint8_t> (lhs.b + rhs.b);
00376       return (lhs);
00377     }
00378 
00379     template <> inline pcl::PointXYZRGB&
00380     operator-= (pcl::PointXYZRGB& lhs, const pcl::PointXYZRGB& rhs)
00381     {
00382       lhs.getVector3fMap () -= rhs.getVector3fMap ();
00383       lhs.r = static_cast<uint8_t> (lhs.r - rhs.r);
00384       lhs.g = static_cast<uint8_t> (lhs.g - rhs.g);
00385       lhs.b = static_cast<uint8_t> (lhs.b - rhs.b);
00386       return (lhs);
00387     }
00388 
00389     template <> inline pcl::PointXYZRGB&
00390     operator*= (pcl::PointXYZRGB& lhs, const float& scalar)
00391     {
00392       lhs.getVector3fMap () *= scalar;
00393       lhs.r = static_cast<uint8_t> (lhs.r * scalar);
00394       lhs.g = static_cast<uint8_t> (lhs.g * scalar);
00395       lhs.b = static_cast<uint8_t> (lhs.b * scalar);
00396       return (lhs);
00397     }
00398 
00400     template <> inline pcl::PointXYZRGBA
00401     operator+ (const pcl::PointXYZRGBA& lhs, const pcl::PointXYZRGBA& rhs)
00402     {
00403       pcl::PointXYZRGBA result;
00404       result.getVector3fMap () = lhs.getVector3fMap ();
00405       result.getVector3fMap () += rhs.getVector3fMap ();
00406       result.r = static_cast<uint8_t> (lhs.r + rhs.r);
00407       result.g = static_cast<uint8_t> (lhs.g + rhs.g);
00408       result.b = static_cast<uint8_t> (lhs.b + rhs.b);
00409       return (result);
00410     }
00412     template <> inline pcl::PointXYZRGBA
00413     operator- (const pcl::PointXYZRGBA& lhs, const pcl::PointXYZRGBA& rhs)
00414     {
00415       pcl::PointXYZRGBA result;
00416       result.getVector3fMap () = lhs.getVector3fMap ();
00417       result.getVector3fMap () -= rhs.getVector3fMap ();
00418       result.r = static_cast<uint8_t> (lhs.r - rhs.r);
00419       result.g = static_cast<uint8_t> (lhs.g - rhs.g);
00420       result.b = static_cast<uint8_t> (lhs.b - rhs.b);
00421       return (result);
00422     }
00423 
00424     template <> inline pcl::PointXYZRGBA
00425     operator* (const float& scalar, const pcl::PointXYZRGBA& p)
00426     {
00427       pcl::PointXYZRGBA result;
00428       result.getVector3fMap () = p.getVector3fMap ();
00429       result.getVector3fMap () *= scalar;
00430       result.r = static_cast<uint8_t> (scalar * p.r);
00431       result.g = static_cast<uint8_t> (scalar * p.g);
00432       result.b = static_cast<uint8_t> (scalar * p.b);
00433       return (result);
00434     }
00435 
00436     template <> inline pcl::PointXYZRGBA
00437     operator* (const pcl::PointXYZRGBA& p, const float& scalar)
00438     {
00439       pcl::PointXYZRGBA result;
00440       result.getVector3fMap () = p.getVector3fMap ();
00441       result.getVector3fMap () *= scalar;
00442       result.r = static_cast<uint8_t> (scalar * p.r);
00443       result.g = static_cast<uint8_t> (scalar * p.g);
00444       result.b = static_cast<uint8_t> (scalar * p.b);
00445       return (result);
00446     }
00447 
00448     template <> inline pcl::PointXYZRGBA&
00449     operator+= (pcl::PointXYZRGBA& lhs, const pcl::PointXYZRGBA& rhs)
00450     {
00451       lhs.getVector3fMap () += rhs.getVector3fMap ();
00452       lhs.r = static_cast<uint8_t> (lhs.r + rhs.r);
00453       lhs.g = static_cast<uint8_t> (lhs.g + rhs.g);
00454       lhs.b = static_cast<uint8_t> (lhs.b + rhs.b);
00455       return (lhs);
00456     }
00457 
00458     template <> inline pcl::PointXYZRGBA&
00459     operator-= (pcl::PointXYZRGBA& lhs, const pcl::PointXYZRGBA& rhs)
00460     {
00461       lhs.getVector3fMap () -= rhs.getVector3fMap ();
00462       lhs.r = static_cast<uint8_t> (lhs.r - rhs.r);
00463       lhs.g = static_cast<uint8_t> (lhs.g - rhs.g);
00464       lhs.b = static_cast<uint8_t> (lhs.b - rhs.b);
00465       return (lhs);
00466     }
00467 
00468     template <> inline pcl::PointXYZRGBA&
00469     operator*= (pcl::PointXYZRGBA& lhs, const float& scalar)
00470     {
00471       lhs.getVector3fMap () *= scalar;
00472       lhs.r = static_cast<uint8_t> (lhs.r * scalar);
00473       lhs.g = static_cast<uint8_t> (lhs.g * scalar);
00474       lhs.b = static_cast<uint8_t> (lhs.b * scalar);
00475       return (lhs);
00476     }
00477 
00479     template <> inline pcl::RGB
00480     operator+ (const pcl::RGB& lhs, const pcl::RGB& rhs)
00481     {
00482       pcl::RGB result;
00483       result.r = static_cast<uint8_t> (lhs.r + rhs.r);
00484       result.g = static_cast<uint8_t> (lhs.g + rhs.g);
00485       result.b = static_cast<uint8_t> (lhs.b + rhs.b);
00486       return (result);
00487     }
00489     template <> inline pcl::RGB
00490     operator- (const pcl::RGB& lhs, const pcl::RGB& rhs)
00491     {
00492       pcl::RGB result;
00493       result.r = static_cast<uint8_t> (lhs.r - rhs.r);
00494       result.g = static_cast<uint8_t> (lhs.g - rhs.g);
00495       result.b = static_cast<uint8_t> (lhs.b - rhs.b);
00496       return (result);
00497     }
00498 
00499     template <> inline pcl::RGB
00500     operator* (const float& scalar, const pcl::RGB& p)
00501     {
00502       pcl::RGB result;
00503       result.r = static_cast<uint8_t> (scalar * p.r);
00504       result.g = static_cast<uint8_t> (scalar * p.g);
00505       result.b = static_cast<uint8_t> (scalar * p.b);
00506       return (result);
00507     }
00508 
00509     template <> inline pcl::RGB
00510     operator* (const pcl::RGB& p, const float& scalar)
00511     {
00512       pcl::RGB result;
00513       result.r = static_cast<uint8_t> (scalar * p.r);
00514       result.g = static_cast<uint8_t> (scalar * p.g);
00515       result.b = static_cast<uint8_t> (scalar * p.b);
00516       return (result);
00517     }
00518 
00519     template <> inline pcl::RGB&
00520     operator+= (pcl::RGB& lhs, const pcl::RGB& rhs)
00521     {
00522       lhs.r = static_cast<uint8_t> (lhs.r + rhs.r);
00523       lhs.g = static_cast<uint8_t> (lhs.g + rhs.g);
00524       lhs.b = static_cast<uint8_t> (lhs.b + rhs.b);
00525       return (lhs);
00526     }
00527 
00528     template <> inline pcl::RGB&
00529     operator-= (pcl::RGB& lhs, const pcl::RGB& rhs)
00530     {
00531       lhs.r = static_cast<uint8_t> (lhs.r - rhs.r);
00532       lhs.g = static_cast<uint8_t> (lhs.g - rhs.g);
00533       lhs.b = static_cast<uint8_t> (lhs.b - rhs.b);
00534       return (lhs);
00535     }
00536 
00537     template <> inline pcl::RGB&
00538     operator*= (pcl::RGB& lhs, const float& scalar)
00539     {
00540       lhs.r = static_cast<uint8_t> (lhs.r * scalar);
00541       lhs.g = static_cast<uint8_t> (lhs.g * scalar);
00542       lhs.b = static_cast<uint8_t> (lhs.b * scalar);
00543       return (lhs);
00544     }
00545   }
00546 }
00547 
00548 #endif


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:19