malloc.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 <rosrt/malloc_wrappers.h>
00036 
00037 #include <ros/assert.h>
00038 #include <ros/atomic.h>
00039 
00040 #include <boost/thread.hpp>
00041 
00042 #include <iostream>
00043 #include <dlfcn.h>
00044 
00045 #if defined(WIN32)
00046 #define STATIC_TLS_KW __declspec(thread)
00047 #define HAS_TLS_KW 1
00048 #elif defined(__APPLE__)
00049 #define HAS_TLS_KW 0
00050 #else
00051 #define STATIC_TLS_KW __thread
00052 #define HAS_TLS_KW 1
00053 #endif
00054 
00055 #if !HAS_TLS_KW
00056 #include <pthread.h>
00057 #define MAX_ALLOC_INFO 1000
00058 #endif
00059 
00060 namespace rosrt
00061 {
00062 namespace detail
00063 {
00064 
00065 #if HAS_TLS_KW
00066 STATIC_TLS_KW uint64_t g_mallocs = 0;
00067 STATIC_TLS_KW uint64_t g_reallocs = 0;
00068 STATIC_TLS_KW uint64_t g_callocs = 0;
00069 STATIC_TLS_KW uint64_t g_memaligns = 0;
00070 STATIC_TLS_KW uint64_t g_frees = 0;
00071 STATIC_TLS_KW uint64_t g_total_ops = 0;
00072 STATIC_TLS_KW uint64_t g_total_memory_allocated = 0;
00073 STATIC_TLS_KW bool g_break_on_alloc_or_free = false;
00074 #else // HAS_TLS_KW
00075 
00076 pthread_key_t g_tls_key;
00077 bool g_tls_key_initialized = false;
00078 
00079 AllocInfo g_thread_alloc_info[MAX_ALLOC_INFO];
00080 ros::atomic_bool g_alloc_info_used[MAX_ALLOC_INFO];
00081 
00082 void tlsDestructor(void* mem)
00083 {
00084   AllocInfo* info = reinterpret_cast<AllocInfo*>(mem);
00085   uint32_t index = info - g_thread_alloc_info;
00086   ROS_ASSERT(index < MAX_ALLOC_INFO);
00087   g_alloc_info_used[index].store(false);
00088 }
00089 
00090 struct MallocTLSInit
00091 {
00092   MallocTLSInit()
00093   {
00094     int ret = pthread_key_create(&g_tls_key, tlsDestructor);
00095     ROS_ASSERT_MSG(!ret, "Failed to create TLS");
00096 
00097     for (size_t i = 0; i < MAX_ALLOC_INFO; ++i)
00098     {
00099       g_alloc_info_used[i].store(false);
00100     }
00101 
00102     g_tls_key_initialized = true;
00103   }
00104 
00105   ~MallocTLSInit()
00106   {
00107     g_tls_key_initialized = false;
00108 
00109     pthread_key_delete(g_tls_key);
00110   }
00111 };
00112 MallocTLSInit g_malloc_tls_init;
00113 
00114 AllocInfo* allocateAllocInfo()
00115 {
00116   if (!g_tls_key_initialized)
00117   {
00118     return 0;
00119   }
00120 
00121   void* info = pthread_getspecific(g_tls_key);
00122   if (!info)
00123   {
00124     for (size_t i = 0; i < MAX_ALLOC_INFO; ++i)
00125     {
00126       if (g_alloc_info_used[i].exchange(true) == false)
00127       {
00128         info = g_thread_alloc_info + i;
00129         pthread_setspecific(g_tls_key, info);
00130         break;
00131       }
00132     }
00133   }
00134 
00135   return reinterpret_cast<AllocInfo*>(info);
00136 }
00137 
00138 #endif // !HAS_TLS_KW
00139 
00140 } // namespace malloc_tls
00141 
00142 AllocInfo getThreadAllocInfo()
00143 {
00144   AllocInfo info;
00145 
00146 #if HAS_TLS_KW
00147   info.mallocs = detail::g_mallocs;
00148   info.callocs = detail::g_callocs;
00149   info.reallocs = detail::g_reallocs;
00150   info.memaligns = detail::g_memaligns;
00151   info.frees = detail::g_frees;
00152   info.total_ops = detail::g_total_ops;
00153   info.total_memory_allocated = detail::g_total_memory_allocated;
00154   info.break_on_alloc_or_free = detail::g_break_on_alloc_or_free;
00155 #else
00156   AllocInfo* tls = detail::allocateAllocInfo();
00157   if (tls)
00158   {
00159     info = *tls;
00160   }
00161 #endif
00162   return info;
00163 }
00164 
00165 void resetThreadAllocInfo()
00166 {
00167 #if HAS_TLS_KW
00168   detail::g_mallocs = 0;
00169   detail::g_reallocs = 0;
00170   detail::g_callocs = 0;
00171   detail::g_memaligns = 0;
00172   detail::g_frees = 0;
00173   detail::g_total_ops = 0;
00174   detail::g_total_memory_allocated = 0;
00175 #else
00176   AllocInfo* info = detail::allocateAllocInfo();
00177   if (info)
00178   {
00179     *info = AllocInfo();
00180   }
00181 #endif
00182 }
00183 
00184 void setThreadBreakOnAllocOrFree(bool b)
00185 {
00186 #if HAS_TLS_KW
00187   detail::g_break_on_alloc_or_free = b;
00188 #else
00189   AllocInfo* info = detail::allocateAllocInfo();
00190   if (info)
00191   {
00192     info->break_on_alloc_or_free = b;
00193   }
00194 #endif
00195 }
00196 
00197 } // namespace rosrt
00198 
00199 extern "C"
00200 {
00201 
00202 typedef void* (*MallocType)(size_t size);
00203 typedef void* (*CallocType)(size_t nmemb, size_t size);
00204 typedef void* (*ReallocType)(void *ptr, size_t size);
00205 typedef void* (*MemalignType)(size_t boundary, size_t size);
00206 typedef int (*PosixMemalignType)(void **memptr, size_t alignment, size_t size);
00207 typedef void (*FreeType)(void* ptr);
00208 
00209 #if HAS_TLS_KW
00210 #define UPDATE_ALLOC_INFO(result, size, type) \
00211   if (result) \
00212   { \
00213     rosrt::detail::g_total_memory_allocated += size; \
00214   } \
00215 \
00216   ++rosrt::detail::g_##type; \
00217   ++rosrt::detail::g_total_ops; \
00218 \
00219   if (rosrt::detail::g_break_on_alloc_or_free) \
00220   { \
00221     std::cerr << "Issuing break due to break_on_alloc_or_free being set" << std::endl; \
00222     ROS_ISSUE_BREAK(); \
00223   }
00224 #else
00225 #define UPDATE_ALLOC_INFO(result, size, type) \
00226   rosrt::AllocInfo* tls = rosrt::detail::allocateAllocInfo(); \
00227   if (tls) \
00228   { \
00229     if (result) \
00230     { \
00231       tls->total_memory_allocated += size; \
00232     } \
00233   \
00234     ++tls->type; \
00235     ++tls->total_ops; \
00236   \
00237     if (tls->break_on_alloc_or_free) \
00238     { \
00239       std::cerr << "Issuing break due to break_on_alloc_or_free being set" << std::endl; \
00240       ROS_ISSUE_BREAK(); \
00241     } \
00242   }
00243 #endif
00244 
00245 void* malloc(size_t size)
00246 {
00247   static MallocType original_function = reinterpret_cast<MallocType>(dlsym(RTLD_NEXT, "malloc"));
00248 
00249   void* result = original_function(size);
00250 
00251   UPDATE_ALLOC_INFO(result, size, mallocs);
00252 
00253   return result;
00254 }
00255 
00256 void* __libc_malloc(size_t size)
00257 {
00258   return malloc(size);
00259 }
00260 
00261 void* realloc(void* ptr, size_t size)
00262 {
00263   static ReallocType original_function = reinterpret_cast<ReallocType>(dlsym(RTLD_NEXT, "realloc"));
00264 
00265   void* result = original_function(ptr, size);
00266 
00267   UPDATE_ALLOC_INFO(result, size, reallocs);
00268 
00269   return result;
00270 }
00271 
00272 void* __libc_realloc(void* ptr, size_t size)
00273 {
00274   return realloc(ptr, size);
00275 }
00276 
00277 void* memalign(size_t boundary, size_t size)
00278 {
00279   static MemalignType original_function = reinterpret_cast<MemalignType>(dlsym(RTLD_NEXT, "memalign"));
00280 
00281   void* result = original_function(boundary, size);
00282 
00283   UPDATE_ALLOC_INFO(result, size, memaligns);
00284 
00285   return result;
00286 }
00287 
00288 void* __libc_memalign(size_t boundary, size_t size)
00289 {
00290   return memalign(boundary, size);
00291 }
00292 
00293 void free(void *ptr)
00294 {
00295   static FreeType original_function = reinterpret_cast<FreeType>(dlsym(RTLD_NEXT, "free"));
00296 
00297   original_function(ptr);
00298 
00299   uint32_t size = 0;
00300   void* result = 0;
00301   UPDATE_ALLOC_INFO(result, size, frees);
00302 }
00303 
00304 void __libc_free(void* ptr)
00305 {
00306   return free(ptr);
00307 }
00308 
00309 // dlsym uses calloc so it has to be treated specially. Solution found at http://crbug.com/28244
00310 static void* nullCalloc(size_t nmemb, size_t size)
00311 {
00312   return 0;
00313 }
00314 
00315 void* calloc(size_t nmemb, size_t size)
00316 {
00317   static CallocType original_function = 0;
00318   if (original_function == 0)
00319   {
00320       original_function = nullCalloc;
00321       original_function = reinterpret_cast<CallocType>(dlsym(RTLD_NEXT, "calloc"));
00322   }
00323 
00324   void* result = original_function(nmemb, size);
00325 
00326   UPDATE_ALLOC_INFO(result, size * nmemb, callocs);
00327 
00328   return result;
00329 }
00330 
00331 void* __libc_calloc(size_t nmemb, size_t size)
00332 {
00333   return calloc(nmemb, size);
00334 }
00335 
00336 int posix_memalign(void** ptr, size_t alignment, size_t size) {
00337   static PosixMemalignType original_function = reinterpret_cast<PosixMemalignType>(dlsym(RTLD_NEXT, "posix_memalign"));
00338 
00339   int result = original_function(ptr, alignment, size);
00340 
00341   UPDATE_ALLOC_INFO(!result, size, memaligns);
00342 
00343   return result;
00344 }
00345 
00346 
00347 } // extern "C"
00348 
00349 


rosrt
Author(s): Josh Faust
autogenerated on Mon Oct 6 2014 06:54:58