BitPacker.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, LABUST, UNIZG-FER
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the LABUST nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *  Author: Dula Nad
00035  *  Created: 29.04.2013.
00036  *********************************************************************/
00037 #ifndef BITPACKER_HPP_
00038 #define BITPACKER_HPP_
00039 #include <vector>
00040 #include <cstdint>
00041 #include <cassert>
00042 
00043 //#include <bitset>
00044 //#include <iostream>
00045 
00046 namespace labust
00047 {
00048         namespace tools
00049         {
00056                 struct BitPacker
00057                 {
00058                         template <class BitMapType, class DataType>
00059                         static uint64_t pack(const std::vector<BitMapType>& bitmap,
00060                                         const std::vector<DataType>& data)
00061                         {
00062                                 uint64_t retVal(0);
00063                                 assert(bitmap.size() == data.size() &&
00064                                                 "The bitmap and data size have to be the same length.");
00065 
00066                                 for (uint32_t i=0,j=1; i<bitmap.size(); ++i,++j)
00067                                 {
00068                                         DataType bitmask = (1 << bitmap[i]) -1;
00069                                         retVal |= data[i] & bitmask;
00070                                         if (j < bitmap.size()) retVal <<= bitmap[j];
00071                                 }
00072 
00073                                 return retVal;
00074                         }
00075 
00076                         template <class BitMapType, class DataType>
00077                         static void unpack(uint64_t msg, const std::vector<BitMapType>& bitmap,
00078                                         std::vector<DataType>& data)
00079                         {
00080                                 data.clear();
00081                                 data.resize(bitmap.size());
00082                                 for (int i=bitmap.size()-1; i>=0; --i)
00083                                 {
00084                                         DataType bitmask = DataType(DataType(1) << bitmap[i]) -1;
00085                                         data[i]=(msg & bitmask);
00086                                         //std::cout<<"Unpacking message:"<<std::bitset<48>(msg)<<" with bitmap: "<<std::bitset<sizeof(DataType)*8>(bitmask)<<std::endl;
00087                                         msg >>= bitmap[i];
00088                                 }
00089                         };
00090 
00091                         template <class BitMapType, class DataType>
00092                         static uint64_t pack_flipped(const std::vector<BitMapType>& bitmap,
00093                                         const std::vector<DataType>& data)
00094                         {
00095                                 uint64_t retVal(0);
00096                                 assert(bitmap.size() == data.size() &&
00097                                                 "The bitmap and data size have to be the same length.");
00098 
00099                                 for (int i=bitmap.size()-1,j=bitmap.size()-2; i>=0; --i,--j)
00100                                 {
00101                                         DataType bitmask = (1 << bitmap[i]) -1;
00102                                         retVal |= data[i] & bitmask;
00103                                         if (j >= 0) retVal <<= bitmap[j];
00104                                 }
00105 
00106                                 return retVal;
00107                         }
00108 
00109                         template <class BitMapType, class DataType>
00110                         static void unpack_flipped(uint64_t msg, const std::vector<BitMapType>& bitmap,
00111                                         std::vector<DataType>& data)
00112                         {
00113                                 data.clear();
00114                                 for (uint32_t i=0; i<bitmap.size(); ++i)
00115                                 {
00116                                         DataType bitmask = (1 << bitmap[i]) -1;
00117                                         data.push_back(msg & bitmask);
00118                                         msg >>= bitmap[i];
00119                                 }
00120                         };
00121                 };
00122         }
00123 }
00124 /* BITPACKER_HPP_ */
00125 #endif
00126 
00127 
00128 


usbl_comms
Author(s): Gyula Nagy
autogenerated on Fri Feb 7 2014 11:36:13