test_freelist.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2010, 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 the Willow Garage 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 #include <gtest/gtest.h>
00036 
00037 //#define FREE_LIST_DEBUG 1
00038 #include "lockfree/free_list.h"
00039 
00040 #include <boost/thread.hpp>
00041 
00042 #include <set>
00043 #include "ros/time.h"
00044 
00045 using namespace lockfree;
00046 
00047 TEST(FreeList, oneElement)
00048 {
00049   FreeList pool(4, 1);
00050   pool.constructAll<uint32_t>(5);
00051 
00052   uint32_t* item = static_cast<uint32_t*>(pool.allocate());
00053   ASSERT_TRUE(item);
00054   EXPECT_EQ(*item, 5UL);
00055   *item = 6;
00056   ASSERT_FALSE(pool.allocate());
00057   pool.free(item);
00058   item = static_cast<uint32_t*>(pool.allocate());
00059   ASSERT_TRUE(item);
00060   EXPECT_EQ(*item, 6UL);
00061 }
00062 
00063 TEST(FreeList, multipleElements)
00064 {
00065   const uint32_t count = 5;
00066   FreeList pool(4, count);
00067   pool.constructAll<uint32_t>(5);
00068 
00069   std::vector<uint32_t*> items;
00070   items.reserve(count);
00071 
00072   for (uint32_t i = 0; i < count; ++i)
00073   {
00074     items.push_back(static_cast<uint32_t*>(pool.allocate()));
00075     ASSERT_TRUE(items[i]);
00076     EXPECT_EQ(*items[i], 5UL);
00077     *items[i] = i;
00078   }
00079 
00080   ASSERT_FALSE(pool.allocate());
00081   pool.free(items.back());
00082   items.pop_back();
00083   items.push_back(static_cast<uint32_t*>(pool.allocate()));
00084   ASSERT_TRUE(items.back());
00085   ASSERT_FALSE(pool.allocate());
00086 
00087   std::set<uint32_t*> set;
00088   set.insert(items.begin(), items.end());
00089   EXPECT_EQ(set.size(), count);
00090 }
00091 
00092 #if FREE_LIST_DEBUG
00093 boost::mutex g_debug_mutex;
00094 std::vector<FreeList::Debug> g_debug;
00095 
00096 std::ostream& operator<<(std::ostream& o, const FreeList::Debug::Item& i)
00097 {
00098   o.width(20);
00099   o << (i.success ? 1 : 0);
00100   o << " ";
00101   o << i.time;
00102   o << ": ";
00103   o << ((i.op == FreeList::Debug::Alloc) ? std::string("alloc") : std::string("free "));
00104   o << std::string("    head: ");
00105   o << std::hex;
00106   o << i.head;
00107   o << std::string("    new_head: ");
00108   o << i.new_head;
00109   o << "   addr:" << (uint32_t*)i.addr;
00110   return o;
00111 }
00112 #endif
00113 
00114 struct PerfCounter
00115 {
00116   PerfCounter()
00117   : start(ros::WallTime::now())
00118   {}
00119 
00120   double elapsed() { return (ros::WallTime::now() - start).toSec(); }
00121   void reset() { start = ros::WallTime::now(); }
00122 
00123   ros::WallTime start;
00124 };
00125 
00126 void threadFunc(FreeList& pool, ros::atomic<bool>& done, ros::atomic<bool>& failed, boost::barrier& b)
00127 {
00128   b.wait();
00129 
00130   //ROS_INFO_STREAM("Thread " << boost::this_thread::get_id() << " starting");
00131 
00132   uint32_t* vals[10];
00133   uint64_t alloc_count = 0;
00134   while (!done.load())
00135   {
00136     for (uint32_t i = 0; i < 10; ++i)
00137     {
00138       vals[i] = static_cast<uint32_t*>(pool.allocate());
00139 
00140       if (vals[i])
00141       {
00142         ++alloc_count;
00143         *vals[i] = i;
00144       }
00145       else
00146       {
00147         ROS_ERROR_STREAM("Thread " << boost::this_thread::get_id() << " failed to allocate");
00148       }
00149     }
00150 
00151     for (uint32_t i = 0; i < 10; ++i)
00152     {
00153       if (vals[i])
00154       {
00155         if (*vals[i] != i)
00156         {
00157           ROS_ERROR_STREAM("Thread " << boost::this_thread::get_id() << " val " << vals[i] << " " << i << " = " << *vals[i]);
00158           failed.store(true);
00159         }
00160 
00161         pool.free(vals[i]);
00162       }
00163     }
00164 
00165     if (failed.load())
00166     {
00167 #if FREE_LIST_DEBUG
00168       boost::mutex::scoped_lock lock(g_debug_mutex);
00169       g_debug.push_back(*pool.getDebug());
00170 #endif
00171       return;
00172     }
00173   }
00174 
00175   //ROS_INFO_STREAM("Thread " << boost::this_thread::get_id() << " allocated " << alloc_count << " blocks");
00176 }
00177 
00178 TEST(FreeList, multipleThreads)
00179 {
00180   const uint32_t thread_count = boost::thread::hardware_concurrency() * 2;
00181   FreeList pool(4, thread_count * 10);
00182   ros::atomic<bool> done(false);
00183   ros::atomic<bool> failed(false);
00184   boost::thread_group tg;
00185   boost::barrier bar(thread_count);
00186   for (uint32_t i = 0; i < thread_count; ++i)
00187   {
00188     tg.create_thread(boost::bind(threadFunc, boost::ref(pool), boost::ref(done), boost::ref(failed), boost::ref(bar)));
00189   }
00190 
00191   ros::WallTime start = ros::WallTime::now();
00192   while (ros::WallTime::now() - start < ros::WallDuration(10.0))
00193   {
00194     ros::WallDuration(0.01).sleep();
00195 
00196     if (failed.load())
00197     {
00198       break;
00199     }
00200   }
00201   done.store(true);
00202   tg.join_all();
00203 
00204 #if FREE_LIST_DEBUG
00205   if (failed.load())
00206   {
00207     std::vector<std::vector<FreeList::Debug::Item>::iterator> its;
00208     its.resize(g_debug.size());
00209     for (size_t i = 0; i < its.size(); ++i)
00210     {
00211       int32_t start = std::max((int32_t)g_debug[i].items.size() - 10000, 0);
00212       ROS_INFO_STREAM(start << " " << g_debug[i].items.size());
00213       its[i] = g_debug[i].items.begin() + start;
00214     }
00215     while (true)
00216     {
00217       size_t ind = 999999;
00218       ros::WallTime time(0xffffffff, 0);
00219       for (size_t j = 0; j < its.size(); ++j)
00220       {
00221         if (its[j] != g_debug[j].items.end() && its[j]->time < time)
00222         {
00223           ind = j;
00224           time = its[j]->time;
00225         }
00226       }
00227 
00228       if (ind == 999999)
00229       {
00230         break;
00231       }
00232 
00233       ROS_ERROR_STREAM("[" << std::setw(20) << g_debug[ind].thread << "] " << *its[ind]);
00234       ++its[ind];
00235     }
00236   }
00237 #endif
00238 
00239   ASSERT_TRUE(!failed.load());
00240 }
00241 
00242 TEST(FreeList, hasOutstandingAllocations)
00243 {
00244   const uint32_t count = 5;
00245   FreeList pool(4, count);
00246 
00247   std::vector<uint32_t*> items;
00248   items.reserve(count);
00249 
00250   ASSERT_TRUE(pool.hasOutstandingAllocations());
00251 
00252   for (uint32_t i = 0; i < count; ++i)
00253   {
00254     items.push_back(static_cast<uint32_t*>(pool.allocate()));
00255     ASSERT_FALSE(pool.hasOutstandingAllocations());
00256   }
00257 
00258   for (uint32_t i = 0; i < count; ++i)
00259   {
00260     ASSERT_FALSE(pool.hasOutstandingAllocations());
00261     pool.free(items[i]);
00262   }
00263 
00264   ASSERT_TRUE(pool.hasOutstandingAllocations());
00265 }
00266 
00267 int main(int argc, char** argv)
00268 {
00269   testing::InitGoogleTest(&argc, argv);
00270   return RUN_ALL_TESTS();
00271 }
00272 


lockfree
Author(s): Josh Faust
autogenerated on Wed Aug 26 2015 16:00:00