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


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