intensity.hpp
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-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 #ifndef PCL_COMMON_INTENSITY_FIELD_ACCESSOR_IMPL_HPP
00042 #define PCL_COMMON_INTENSITY_FIELD_ACCESSOR_IMPL_HPP
00043 
00044 #include <pcl/point_types.h>
00045 namespace pcl
00046 {
00047   namespace common
00048   {
00049     template<>
00050     struct IntensityFieldAccessor<pcl::PointNormal>
00051     {
00052       inline float
00053       operator () (const pcl::PointNormal &p) const
00054       {
00055         return (p.curvature);
00056       }
00057 
00058       inline void
00059       get (const pcl::PointNormal &p, float &intensity) const
00060       {
00061         intensity = p.curvature;
00062       }
00063 
00064       inline void
00065       set (pcl::PointNormal &p, float intensity) const
00066       {
00067         p.curvature = intensity;
00068       }
00069 
00070       inline void
00071       demean (pcl::PointNormal& p, float value) const
00072       {
00073         p.curvature -= value;
00074       }
00075 
00076       inline void
00077       add (pcl::PointNormal& p, float value) const
00078       {
00079         p.curvature += value;
00080       }
00081     };
00082     
00083     template<>
00084     struct IntensityFieldAccessor<pcl::PointXYZ>
00085     {
00086       inline float
00087       operator () (const pcl::PointXYZ &p) const
00088       {
00089         return (p.z);
00090       }
00091 
00092       inline void
00093       get (const pcl::PointXYZ &p, float &intensity) const
00094       {
00095         intensity = p.z;
00096       }
00097 
00098       inline void
00099       set (pcl::PointXYZ &p, float intensity) const
00100       {
00101         p.z = intensity;
00102       }
00103 
00104       inline void
00105       demean (pcl::PointXYZ& p, float value) const
00106       {
00107         p.z -= value;
00108       }
00109 
00110       inline void
00111       add (pcl::PointXYZ& p, float value) const
00112       {
00113         p.z += value;
00114       }
00115     };
00116 
00117     template<>
00118     struct IntensityFieldAccessor<pcl::PointXYZRGB>
00119     {
00120       inline float
00121       operator () (const pcl::PointXYZRGB &p) const
00122       {
00123         return (static_cast<float> (299*p.r + 587*p.g + 114*p.b) * 0.001f);
00124       }
00125 
00126       inline void
00127       get (const pcl::PointXYZRGB &p, float& intensity) const
00128       {
00129         intensity = static_cast<float> (299*p.r + 587*p.g + 114*p.b) * 0.001f;
00130       }
00131       
00132       inline void
00133       set (pcl::PointXYZRGB &p, float intensity) const
00134       {
00135         p.r = static_cast<uint8_t> (intensity * 3.34448160535f); // 1000 / 299
00136         p.g = static_cast<uint8_t> (intensity * 1.70357751278f); // 1000 / 587
00137         p.b = static_cast<uint8_t> (intensity * 8.77192982456f); // 1000 / 114
00138       }
00139       
00140       inline void
00141       demean (pcl::PointXYZRGB& p, float value) const
00142       {
00143         float intensity = this->operator () (p);
00144         intensity -= value;
00145         set (p, intensity);
00146       }
00147       
00148       inline void
00149       add (pcl::PointXYZRGB& p, float value) const
00150       {
00151         float intensity = this->operator () (p);
00152         intensity += value;
00153         set (p, intensity);
00154       }
00155     };
00156 
00157     template<>
00158     struct IntensityFieldAccessor<pcl::PointXYZRGBA>
00159     {
00160       inline float
00161       operator () (const pcl::PointXYZRGBA &p) const
00162       {
00163         return (static_cast<float> (299*p.r + 587*p.g + 114*p.b) * 0.001f);
00164       }
00165       
00166       inline void
00167       get (const pcl::PointXYZRGBA &p, float& intensity) const
00168       {
00169         intensity = static_cast<float> (299*p.r + 587*p.g + 114*p.b) * 0.001f;
00170       }
00171 
00172       inline void
00173       set (pcl::PointXYZRGBA &p, float intensity) const
00174       {
00175         p.r = static_cast<uint8_t> (intensity * 3.34448160535f); // 1000 / 299
00176         p.g = static_cast<uint8_t> (intensity * 1.70357751278f); // 1000 / 587
00177         p.b = static_cast<uint8_t> (intensity * 8.77192982456f); // 1000 / 114
00178       }
00179       
00180       inline void
00181       demean (pcl::PointXYZRGBA& p, float value) const
00182       {
00183         float intensity = this->operator () (p);
00184         intensity -= value;
00185         set (p, intensity);
00186       }
00187       
00188       inline void
00189       add (pcl::PointXYZRGBA& p, float value) const
00190       {
00191         float intensity = this->operator () (p);
00192         intensity += value;
00193         set (p, intensity);
00194       }
00195     };
00196 
00197     template<>
00198     struct IntensityFieldAccessor<pcl::PointXYZRGBNormal>
00199     {
00200       inline float
00201       operator () (const pcl::PointXYZRGBNormal &p) const
00202       {
00203         return (static_cast<float> (299*p.r + 587*p.g + 114*p.b) * 0.001f);
00204       }
00205       
00206       inline void
00207       get (const pcl::PointXYZRGBNormal &p, float& intensity) const
00208       {
00209         intensity = static_cast<float> (299*p.r + 587*p.g + 114*p.b) * 0.001f;
00210       }
00211 
00212       inline void
00213       set (pcl::PointXYZRGBNormal &p, float intensity) const
00214       {
00215         p.r = static_cast<uint8_t> (intensity * 3.34448160535f); // 1000 / 299
00216         p.g = static_cast<uint8_t> (intensity * 1.70357751278f); // 1000 / 587
00217         p.b = static_cast<uint8_t> (intensity * 8.77192982456f); // 1000 / 114
00218       }
00219       
00220       inline void
00221       demean (pcl::PointXYZRGBNormal &p, float value) const
00222       {
00223         float intensity = this->operator () (p);
00224         intensity -= value;
00225         set (p, intensity);
00226       }
00227       
00228       inline void
00229       add (pcl::PointXYZRGBNormal &p, float value) const
00230       {
00231         float intensity = this->operator () (p);
00232         intensity += value;
00233         set (p, intensity);
00234       }
00235     };
00236 
00237     template<>
00238     struct IntensityFieldAccessor<pcl::PointXYZRGBL>
00239     {
00240       inline float
00241       operator () (const pcl::PointXYZRGBL &p) const
00242       {
00243         return (static_cast<float> (299*p.r + 587*p.g + 114*p.b) * 0.001f);
00244       }
00245 
00246       inline void
00247       get (const pcl::PointXYZRGBL &p, float& intensity) const
00248       {
00249         intensity = static_cast<float> (299*p.r + 587*p.g + 114*p.b) * 0.001f;
00250       }
00251       
00252       inline void
00253       set (pcl::PointXYZRGBL &p, float intensity) const
00254       {
00255         p.r = static_cast<uint8_t> (intensity * 3.34448160535f); // 1000 / 299
00256         p.g = static_cast<uint8_t> (intensity * 1.70357751278f); // 1000 / 587
00257         p.b = static_cast<uint8_t> (intensity * 8.77192982456f); // 1000 / 114
00258       }
00259       
00260       inline void
00261       demean (pcl::PointXYZRGBL& p, float value) const
00262       {
00263         float intensity = this->operator () (p);
00264         intensity -= value;
00265         set (p, intensity);
00266       }
00267       
00268       inline void
00269       add (pcl::PointXYZRGBL& p, float value) const
00270       {
00271         float intensity = this->operator () (p);
00272         intensity += value;
00273         set (p, intensity);
00274       }
00275     };
00276   }
00277 }
00278 
00279 #endif


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