test_range_coder.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Willow Garage, Inc.
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 Willow Garage, Inc. 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  *
00035  * range coder based on Dmitry Subbotin's carry-less implementation (http://www.compression.ru/ds/)
00036  * Added optimized symbol lookup and fixed/static frequency tables
00037  *
00038  * Author: Julius Kammerl (julius@kammerl.de)
00039  */
00040 
00041 
00042 #include <pcl/compression/entropy_range_coder.h>
00043 #include <pcl/compression/impl/entropy_range_coder.hpp>
00044 
00045 #include <gtest/gtest.h>
00046 #include <vector>
00047 #include <sstream>
00048 
00049 
00051 TEST (PCL, Adaptive_Range_Coder_Test)
00052 {
00053   size_t i;
00054   std::stringstream sstream;
00055   std::vector<char> inputData;
00056   std::vector<char> outputData;
00057 
00058   unsigned long writeByteLen;
00059   unsigned long readByteLen;
00060 
00061   // vector size
00062   const unsigned int vectorSize = 10000;
00063 
00064   inputData.resize(vectorSize);
00065   outputData.resize(vectorSize);
00066 
00067   // fill vector with random data
00068   for (i=0; i<vectorSize; i++)
00069   {
00070     inputData[i] = static_cast<char>(rand() & 0xFF);
00071   }
00072 
00073   // initialize adaptive range coder
00074   pcl::AdaptiveRangeCoder rangeCoder;
00075 
00076   // encode char vector to stringstream
00077   writeByteLen = rangeCoder.encodeCharVectorToStream(inputData, sstream);
00078 
00079   // decode stringstream to char vector
00080   readByteLen = rangeCoder.decodeStreamToCharVector(sstream, outputData);
00081 
00082   // compare amount of bytes that are read and written to/from stream
00083   EXPECT_EQ (writeByteLen, readByteLen);
00084   EXPECT_EQ (writeByteLen, sstream.str().length());
00085 
00086   // compare input and output vector - should be identical
00087   EXPECT_EQ (inputData.size(), outputData.size());
00088   EXPECT_EQ (inputData.size(), vectorSize);
00089 
00090   for (i=0; i<vectorSize; i++)
00091   {
00092     EXPECT_EQ (inputData[i], outputData[i]);
00093   }
00094 
00095 }
00096 
00098 TEST (PCL, Static_Range_Coder_Test)
00099 {
00100   size_t i;
00101   std::stringstream sstream;
00102   std::vector<char> inputCharData;
00103   std::vector<char> outputCharData;
00104 
00105   std::vector<unsigned int> inputIntData;
00106   std::vector<unsigned int> outputIntData;
00107 
00108   unsigned long writeByteLen;
00109   unsigned long readByteLen;
00110 
00111   // vector size
00112   const unsigned int vectorSize = 10000;
00113 
00114   inputCharData.resize(vectorSize);
00115   outputCharData.resize(vectorSize);
00116 
00117   inputIntData.resize(vectorSize);
00118   outputIntData.resize(vectorSize);
00119 
00120   // fill vectors with random data
00121   for (i=0; i<vectorSize; i++)
00122   {
00123     inputCharData[i] = static_cast<char> (rand () & 0xFF);
00124     inputIntData[i] = static_cast<unsigned int> (rand () & 0xFFFF);
00125   }
00126 
00127   // initialize static range coder
00128   pcl::StaticRangeCoder rangeCoder;
00129 
00130   // encode char vector to stringstream
00131   writeByteLen = rangeCoder.encodeCharVectorToStream(inputCharData, sstream);
00132 
00133   // decode stringstream to char vector
00134   readByteLen = rangeCoder.decodeStreamToCharVector(sstream, outputCharData);
00135 
00136   // compare amount of bytes that are read and written to/from stream
00137   EXPECT_EQ (writeByteLen, readByteLen);
00138   EXPECT_EQ (writeByteLen, sstream.str().length());
00139 
00140   // compare input and output vector - should be identical
00141   EXPECT_EQ (inputCharData.size(), outputCharData.size());
00142   EXPECT_EQ (inputCharData.size(), vectorSize);
00143 
00144   for (i=0; i<vectorSize; i++)
00145   {
00146     EXPECT_EQ (inputCharData[i], outputCharData[i]);
00147   }
00148 
00149   sstream.clear();
00150 
00151   // encode integer vector to stringstream
00152   writeByteLen = rangeCoder.encodeIntVectorToStream(inputIntData, sstream);
00153 
00154   // decode stringstream to integer vector
00155   readByteLen = rangeCoder.decodeStreamToIntVector(sstream, outputIntData);
00156 
00157   // compare amount of bytes that are read and written to/from stream
00158   EXPECT_EQ (writeByteLen, readByteLen);
00159 
00160   // compare input and output vector - should be identical
00161   EXPECT_EQ (inputIntData.size(), outputIntData.size());
00162   EXPECT_EQ (inputIntData.size(), vectorSize);
00163 
00164   for (i=0; i<vectorSize; i++)
00165   {
00166     EXPECT_EQ (inputIntData[i], outputIntData[i]);
00167   }
00168 
00169 }
00170 
00171 
00172 
00173 /* ---[ */
00174 int
00175   main (int argc, char** argv)
00176 {
00177   testing::InitGoogleTest (&argc, argv);
00178   return (RUN_ALL_TESTS ());
00179 }
00180 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:18:27