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  *
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: intensity.hpp 5299 2012-03-26 03:27:10Z svn $
00037  *
00038  */
00039 
00040 #ifndef PCL_COMMON_INTENSITY_FIELD_ACCESSOR_IMPL_HPP
00041 #define PCL_COMMON_INTENSITY_FIELD_ACCESSOR_IMPL_HPP
00042 
00043 #include <pcl/point_types.h>
00044 namespace pcl
00045 {
00046   namespace common
00047   {
00048     template<>
00049     struct IntensityFieldAccessor<pcl::PointNormal>
00050     {
00051       inline float
00052       operator () (const pcl::PointNormal &p) const
00053       {
00054         return p.curvature;
00055       }
00056 
00057       inline void
00058       get (const pcl::PointNormal &p, float &intensity) const
00059       {
00060         intensity = p.curvature;
00061       }
00062 
00063       inline void
00064       set (pcl::PointNormal &p, float intensity) const
00065       {
00066         p.curvature = intensity;
00067       }
00068 
00069       inline void
00070       demean (pcl::PointNormal& p, float value) const
00071       {
00072         p.curvature -= value;
00073       }
00074 
00075       inline void
00076       add (pcl::PointNormal& p, float value) const
00077       {
00078         p.curvature += value;
00079       }
00080     };
00081 
00082     template<>
00083     struct IntensityFieldAccessor<pcl::PointXYZRGB>
00084     {
00085       inline float
00086       operator () (const pcl::PointXYZRGB &p) const
00087       {
00088         return (static_cast<float> (299*p.r + 587*p.g + 114*p.b) / 1000.0f);
00089       }
00090 
00091       inline void
00092       get (const pcl::PointXYZRGB &p, float& intensity) const
00093       {
00094         intensity = static_cast<float> (299*p.r + 587*p.g + 114*p.b) / 1000.0f;
00095       }
00096       
00097       inline void
00098       set (pcl::PointXYZRGB &p, float intensity) const
00099       {
00100         p.r = static_cast<uint8_t> (1000 * intensity / 299);
00101         p.g = static_cast<uint8_t> (1000 * intensity / 587);
00102         p.b = static_cast<uint8_t> (1000 * intensity / 114);
00103       }
00104       
00105       inline void
00106       demean (pcl::PointXYZRGB& p, float value) const
00107       {
00108         float intensity = this->operator () (p);
00109         intensity -= value;
00110         set (p, intensity);
00111       }
00112       
00113       inline void
00114       add (pcl::PointXYZRGB& p, float value) const
00115       {
00116         float intensity = this->operator () (p);
00117         intensity += value;
00118         set (p, intensity);
00119       }
00120     };
00121 
00122     template<>
00123     struct IntensityFieldAccessor<pcl::PointXYZRGBA>
00124     {
00125       inline float
00126       operator () (const pcl::PointXYZRGBA &p) const
00127       {
00128         return (static_cast<float> (299*p.r + 587*p.g + 114*p.b) / 1000.0f);
00129       }
00130       
00131       inline void
00132       get (const pcl::PointXYZRGBA &p, float& intensity) const
00133       {
00134         intensity = static_cast<float> (299*p.r + 587*p.g + 114*p.b) / 1000.0f;
00135       }
00136 
00137       inline void
00138       set (pcl::PointXYZRGBA &p, float intensity) const
00139       {
00140         p.r = static_cast<uint8_t> (1000 * intensity / 299);
00141         p.g = static_cast<uint8_t> (1000 * intensity / 587);
00142         p.b = static_cast<uint8_t> (1000 * intensity / 114);
00143       }
00144       
00145       inline void
00146       demean (pcl::PointXYZRGBA& p, float value) const
00147       {
00148         float intensity = this->operator () (p);
00149         intensity -= value;
00150         set (p, intensity);
00151       }
00152       
00153       inline void
00154       add (pcl::PointXYZRGBA& p, float value) const
00155       {
00156         float intensity = this->operator () (p);
00157         intensity += value;
00158         set (p, intensity);
00159       }
00160     };
00161   }
00162 }
00163 
00164 #endif


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:28