quantized_map.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  */
00037 
00038 #ifndef PCL_FEATURES_QUANTIZED_MAP
00039 #define PCL_FEATURES_QUANTIZED_MAP
00040 
00041 #include <vector>
00042 #include <pcl/pcl_macros.h>
00043 
00044 namespace pcl
00045 {
00046   class PCL_EXPORTS QuantizedMap
00047   {
00048     public:
00049 
00050       QuantizedMap ();
00051       QuantizedMap (size_t width, size_t height);
00052       QuantizedMap (const QuantizedMap & copy_me);
00053 
00054       virtual ~QuantizedMap ();
00055 
00056       inline size_t
00057       getWidth () const { return (width_); }
00058       
00059       inline size_t
00060       getHeight () const { return (height_); }
00061       
00062       inline unsigned char*
00063       getData () { return (&data_[0]); }
00064 
00065       inline const unsigned char*
00066       getData () const { return (&data_[0]); }
00067 
00068       inline QuantizedMap
00069       getSubMap (size_t x,
00070                  size_t y,
00071                  size_t width,
00072                  size_t height)
00073       {
00074         QuantizedMap subMap(width, height);
00075 
00076         for (size_t row_index = 0; row_index < height; ++row_index)
00077         {
00078           for (size_t col_index = 0; col_index < width; ++col_index)
00079           {
00080             //const size_t index = (row_index+y)*width_ + (col_index+x);
00081             //const unsigned char value = data_[index];
00082             //subMap.data_[row_index*width + col_index] = value;//data_[(row_index+y)*width_ + (col_index+x)];
00083             subMap (col_index, row_index) = (*this) (col_index + x, row_index + y);
00084           }
00085         }
00086 
00087         return subMap;
00088       }
00089 
00090       void 
00091       resize (size_t width, size_t height);
00092 
00093       inline unsigned char & 
00094       operator() (const size_t x, const size_t y) 
00095       { 
00096         return (data_[y*width_+x]); 
00097       }
00098 
00099       inline const unsigned char & 
00100       operator() (const size_t x, const size_t y) const
00101       { 
00102         return (data_[y*width_+x]); 
00103       }
00104 
00105       static void
00106       spreadQuantizedMap (const QuantizedMap & input_map, QuantizedMap & output_map, size_t spreading_size);
00107 
00108       void 
00109       serialize (std::ostream & stream) const
00110       {
00111         const int width = static_cast<int> (width_);
00112         const int height = static_cast<int> (height_);
00113         
00114         stream.write (reinterpret_cast<const char*> (&width), sizeof (width));
00115         stream.write (reinterpret_cast<const char*> (&height), sizeof (height));
00116 
00117         const int num_of_elements = static_cast<int> (data_.size ());
00118         stream.write (reinterpret_cast<const char*> (&num_of_elements), sizeof (num_of_elements));
00119         for (int element_index = 0; element_index < num_of_elements; ++element_index)
00120         {
00121           stream.write (reinterpret_cast<const char*> (&(data_[element_index])), sizeof (data_[element_index]));
00122         }
00123       }
00124 
00125       void 
00126       deserialize (std::istream & stream)
00127       {
00128         int width;
00129         int height;
00130 
00131         stream.read (reinterpret_cast<char*> (&width), sizeof (width));
00132         stream.read (reinterpret_cast<char*> (&height), sizeof (height));
00133 
00134         width_ = static_cast<size_t> (width);
00135         height_ = static_cast<size_t> (height);
00136 
00137         int num_of_elements;
00138         stream.read (reinterpret_cast<char*> (&num_of_elements), sizeof (num_of_elements));
00139         data_.resize (num_of_elements);
00140         for (int element_index = 0; element_index < num_of_elements; ++element_index)
00141         {
00142           stream.read (reinterpret_cast<char*> (&(data_[element_index])), sizeof (data_[element_index]));
00143         }
00144       }
00145 
00146 
00147     //private:
00148       std::vector<unsigned char> data_;
00149       size_t width_;
00150       size_t height_;  
00151     
00152   };
00153 }
00154 
00155 #endif   


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