utest.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <boost/thread.hpp>
00031 #include <boost/bind.hpp>
00032 #include <iostream>
00033 #include <string>
00034 #include <vector>
00035 
00036 #include "class_loader/class_loader.hpp"
00037 #include "class_loader/multi_library_class_loader.hpp"
00038 
00039 #include "gtest/gtest.h"
00040 
00041 #include "./base.hpp"
00042 
00043 const char LIBRARY_1[] = "libclass_loader_TestPlugins1.so";
00044 const char LIBRARY_2[] = "libclass_loader_TestPlugins2.so";
00045 
00046 /*****************************************************************************/
00047 TEST(ClassLoaderTest, basicLoad) {
00048   try {
00049     class_loader::ClassLoader loader1(LIBRARY_1, false);
00050     loader1.createInstance<Base>("Cat")->saySomething();  // See if lazy load works
00051   } catch (class_loader::ClassLoaderException & e) {
00052     FAIL() << "ClassLoaderException: " << e.what() << "\n";
00053   }
00054 
00055   SUCCEED();
00056 }
00057 
00058 /*****************************************************************************/
00059 TEST(ClassLoaderTest, correctNonLazyLoadUnload) {
00060   try {
00061     ASSERT_FALSE(class_loader::class_loader_private::isLibraryLoadedByAnybody(LIBRARY_1));
00062     class_loader::ClassLoader loader1(LIBRARY_1, false);
00063     ASSERT_TRUE(class_loader::class_loader_private::isLibraryLoadedByAnybody(LIBRARY_1));
00064     ASSERT_TRUE(loader1.isLibraryLoaded());
00065     loader1.unloadLibrary();
00066     ASSERT_FALSE(class_loader::class_loader_private::isLibraryLoadedByAnybody(LIBRARY_1));
00067     ASSERT_FALSE(loader1.isLibraryLoaded());
00068     return;
00069   } catch (class_loader::ClassLoaderException & e) {
00070     FAIL() << "ClassLoaderException: " << e.what() << "\n";
00071   } catch (...) {
00072     FAIL() << "Unhandled exception";
00073   }
00074 }
00075 
00076 /*****************************************************************************/
00077 TEST(ClassLoaderTest, correctLazyLoadUnload) {
00078   try {
00079     ASSERT_FALSE(class_loader::class_loader_private::isLibraryLoadedByAnybody(LIBRARY_1));
00080     class_loader::ClassLoader loader1(LIBRARY_1, true);
00081     ASSERT_FALSE(class_loader::class_loader_private::isLibraryLoadedByAnybody(LIBRARY_1));
00082     ASSERT_FALSE(loader1.isLibraryLoaded());
00083 
00084     {
00085       boost::shared_ptr<Base> obj = loader1.createInstance<Base>("Cat");
00086       ASSERT_TRUE(class_loader::class_loader_private::isLibraryLoadedByAnybody(LIBRARY_1));
00087       ASSERT_TRUE(loader1.isLibraryLoaded());
00088     }
00089 
00090     // The library will unload automatically when the only plugin object left is destroyed
00091     ASSERT_FALSE(class_loader::class_loader_private::isLibraryLoadedByAnybody(LIBRARY_1));
00092     return;
00093   } catch (class_loader::ClassLoaderException & e) {
00094     FAIL() << "ClassLoaderException: " << e.what() << "\n";
00095   } catch (...) {
00096     FAIL() << "Unhandled exception";
00097   }
00098 }
00099 
00100 /*****************************************************************************/
00101 
00102 TEST(ClassLoaderTest, nonExistentPlugin) {
00103   class_loader::ClassLoader loader1(LIBRARY_1, false);
00104 
00105   try {
00106     boost::shared_ptr<Base> obj = loader1.createInstance<Base>("Bear");
00107     if (NULL == obj) {
00108       FAIL() << "Null object being returned instead of exception thrown.";
00109     }
00110 
00111     obj->saySomething();
00112   } catch (const class_loader::CreateClassException &) {
00113     SUCCEED();
00114     return;
00115   } catch (...) {
00116     FAIL() << "Unknown exception caught.\n";
00117   }
00118 
00119   FAIL() << "Did not throw exception as expected.\n";
00120 }
00121 
00122 /*****************************************************************************/
00123 TEST(ClassLoaderTest, nonExistentLibrary) {
00124   try {
00125     class_loader::ClassLoader loader1("libDoesNotExist.so", false);
00126   } catch (const class_loader::LibraryLoadException &) {
00127     SUCCEED();
00128     return;
00129   } catch (...) {
00130     FAIL() << "Unknown exception caught.\n";
00131   }
00132 
00133   FAIL() << "Did not throw exception as expected.\n";
00134 }
00135 
00136 /*****************************************************************************/
00137 
00138 class InvalidBase
00139 {
00140 };
00141 
00142 TEST(ClassLoaderTest, invalidBase) {
00143   try {
00144     class_loader::ClassLoader loader1(LIBRARY_1, false);
00145     if (loader1.isClassAvailable<InvalidBase>("Cat")) {
00146       FAIL() << "Cat should not be available for InvalidBase";
00147     } else if (loader1.isClassAvailable<Base>("Cat")) {
00148       SUCCEED();
00149       return;
00150     } else {
00151       FAIL() << "Class not available for correct base class.";
00152     }
00153   } catch (const class_loader::LibraryLoadException &) {
00154     FAIL() << "Unexpected exception";
00155   } catch (...) {
00156     FAIL() << "Unexpected and unknown exception caught.\n";
00157   }
00158 }
00159 
00160 /*****************************************************************************/
00161 
00162 void wait(int seconds)
00163 {
00164   boost::this_thread::sleep(boost::posix_time::seconds(seconds));
00165 }
00166 
00167 void run(class_loader::ClassLoader * loader)
00168 {
00169   std::vector<std::string> classes = loader->getAvailableClasses<Base>();
00170   for (unsigned int c = 0; c < classes.size(); c++) {
00171     loader->createInstance<Base>(classes.at(c))->saySomething();
00172   }
00173 }
00174 
00175 TEST(ClassLoaderTest, threadSafety) {
00176   class_loader::ClassLoader loader1(LIBRARY_1);
00177   ASSERT_TRUE(loader1.isLibraryLoaded());
00178 
00179   // Note: Hard to test thread safety to make sure memory isn't corrupted.
00180   // The hope is this test is hard enough that once in a while it'll segfault
00181   // or something if there's some implementation error.
00182   try {
00183     std::vector<boost::thread *> client_threads;
00184 
00185     for (unsigned int c = 0; c < 1000; c++) {
00186       client_threads.push_back(new boost::thread(boost::bind(&run, &loader1)));
00187     }
00188 
00189     for (unsigned int c = 0; c < client_threads.size(); c++) {
00190       client_threads.at(c)->join();
00191     }
00192 
00193     for (unsigned int c = 0; c < client_threads.size(); c++) {
00194       delete (client_threads.at(c));
00195     }
00196 
00197     loader1.unloadLibrary();
00198     ASSERT_FALSE(loader1.isLibraryLoaded());
00199   } catch (const class_loader::ClassLoaderException &) {
00200     FAIL() << "Unexpected ClassLoaderException.";
00201   } catch (...) {
00202     FAIL() << "Unknown exception.";
00203   }
00204 }
00205 
00206 /*****************************************************************************/
00207 
00208 TEST(ClassLoaderTest, loadRefCountingNonLazy) {
00209   try {
00210     class_loader::ClassLoader loader1(LIBRARY_1, false);
00211     ASSERT_TRUE(loader1.isLibraryLoaded());
00212 
00213     loader1.loadLibrary();
00214     loader1.loadLibrary();
00215     ASSERT_TRUE(loader1.isLibraryLoaded());
00216 
00217     loader1.unloadLibrary();
00218     ASSERT_TRUE(loader1.isLibraryLoaded());
00219 
00220     loader1.unloadLibrary();
00221     ASSERT_TRUE(loader1.isLibraryLoaded());
00222 
00223     loader1.unloadLibrary();
00224     ASSERT_FALSE(loader1.isLibraryLoaded());
00225 
00226     loader1.unloadLibrary();
00227     ASSERT_FALSE(loader1.isLibraryLoaded());
00228 
00229     loader1.loadLibrary();
00230     ASSERT_TRUE(loader1.isLibraryLoaded());
00231 
00232     return;
00233   } catch (const class_loader::ClassLoaderException &) {
00234     FAIL() << "Unexpected exception.\n";
00235   } catch (...) {
00236     FAIL() << "Unknown exception caught.\n";
00237   }
00238 
00239   FAIL() << "Did not throw exception as expected.\n";
00240 }
00241 
00242 /*****************************************************************************/
00243 
00244 TEST(ClassLoaderTest, loadRefCountingLazy) {
00245   try {
00246     class_loader::ClassLoader loader1(LIBRARY_1, true);
00247     ASSERT_FALSE(loader1.isLibraryLoaded());
00248 
00249     {
00250       boost::shared_ptr<Base> obj = loader1.createInstance<Base>("Dog");
00251       ASSERT_TRUE(loader1.isLibraryLoaded());
00252     }
00253 
00254     ASSERT_FALSE(loader1.isLibraryLoaded());
00255 
00256     loader1.loadLibrary();
00257     ASSERT_TRUE(loader1.isLibraryLoaded());
00258 
00259     loader1.loadLibrary();
00260     ASSERT_TRUE(loader1.isLibraryLoaded());
00261 
00262     loader1.unloadLibrary();
00263     ASSERT_TRUE(loader1.isLibraryLoaded());
00264 
00265     loader1.unloadLibrary();
00266     ASSERT_FALSE(loader1.isLibraryLoaded());
00267 
00268     loader1.unloadLibrary();
00269     ASSERT_FALSE(loader1.isLibraryLoaded());
00270 
00271     loader1.loadLibrary();
00272     ASSERT_TRUE(loader1.isLibraryLoaded());
00273 
00274     return;
00275   } catch (const class_loader::ClassLoaderException &) {
00276     FAIL() << "Unexpected exception.\n";
00277   } catch (...) {
00278     FAIL() << "Unknown exception caught.\n";
00279   }
00280 
00281   FAIL() << "Did not throw exception as expected.\n";
00282 }
00283 
00284 
00285 /*****************************************************************************/
00286 
00287 void testMultiClassLoader(bool lazy)
00288 {
00289   try {
00290     class_loader::MultiLibraryClassLoader loader(lazy);
00291     loader.loadLibrary(LIBRARY_1);
00292     loader.loadLibrary(LIBRARY_2);
00293     for (int i = 0; i < 2; ++i) {
00294       loader.createInstance<Base>("Cat")->saySomething();
00295       loader.createInstance<Base>("Dog")->saySomething();
00296       loader.createInstance<Base>("Robot")->saySomething();
00297     }
00298   } catch (class_loader::ClassLoaderException & e) {
00299     FAIL() << "ClassLoaderException: " << e.what() << "\n";
00300   }
00301 
00302   SUCCEED();
00303 }
00304 
00305 TEST(MultiClassLoaderTest, lazyLoad) {
00306   testMultiClassLoader(true);
00307 }
00308 TEST(MultiClassLoaderTest, lazyLoadSecondTime) {
00309   testMultiClassLoader(true);
00310 }
00311 TEST(MultiClassLoaderTest, nonLazyLoad) {
00312   testMultiClassLoader(false);
00313 }
00314 TEST(MultiClassLoaderTest, noWarningOnLazyLoad) {
00315   try {
00316     boost::shared_ptr<Base> cat, dog, rob;
00317     {
00318       class_loader::MultiLibraryClassLoader loader(true);
00319       loader.loadLibrary(LIBRARY_1);
00320       loader.loadLibrary(LIBRARY_2);
00321 
00322       cat = loader.createInstance<Base>("Cat");
00323       dog = loader.createInstance<Base>("Dog");
00324       rob = loader.createInstance<Base>("Robot");
00325     }
00326     cat->saySomething();
00327     dog->saySomething();
00328     rob->saySomething();
00329   } catch (class_loader::ClassLoaderException & e) {
00330     FAIL() << "ClassLoaderException: " << e.what() << "\n";
00331   }
00332 
00333   SUCCEED();
00334 }
00335 
00336 /*****************************************************************************/
00337 
00338 // Run all the tests that were declared with TEST()
00339 int main(int argc, char ** argv)
00340 {
00341   testing::InitGoogleTest(&argc, argv);
00342   return RUN_ALL_TESTS();
00343 }


class_loader
Author(s): Mirza Shah
autogenerated on Thu Jun 6 2019 20:43:27