Bullet Collision Detection & Physics Library
btQuickprof.cpp
Go to the documentation of this file.
1 /*
2 
3 ***************************************************************************************************
4 **
5 ** profile.cpp
6 **
7 ** Real-Time Hierarchical Profiling for Game Programming Gems 3
8 **
9 ** by Greg Hjelstrom & Byon Garrabrant
10 **
11 ***************************************************************************************************/
12 
13 // Credits: The Clock class was inspired by the Timer classes in
14 // Ogre (www.ogre3d.org).
15 
16 #include "btQuickprof.h"
17 #include "btThreads.h"
18 
19 
20 
21 
22 #ifdef __CELLOS_LV2__
23 #include <sys/sys_time.h>
24 #include <sys/time_util.h>
25 #include <stdio.h>
26 #endif
27 
28 #if defined (SUNOS) || defined (__SUNOS__)
29 #include <stdio.h>
30 #endif
31 #ifdef __APPLE__
32 #include <mach/mach_time.h>
33 #include <TargetConditionals.h>
34 #endif
35 
36 #if defined(WIN32) || defined(_WIN32)
37 
38 #define BT_USE_WINDOWS_TIMERS
39 #define WIN32_LEAN_AND_MEAN
40 #define NOWINRES
41 #define NOMCX
42 #define NOIME
43 
44 #ifdef _XBOX
45  #include <Xtl.h>
46 #else //_XBOX
47  #include <windows.h>
48 
49 #if WINVER <0x0602
50 #define GetTickCount64 GetTickCount
51 #endif
52 
53 #endif //_XBOX
54 
55 #include <time.h>
56 
57 
58 #else //_WIN32
59 #include <sys/time.h>
60 
61 #ifdef BT_LINUX_REALTIME
62 //required linking against rt (librt)
63 #include <time.h>
64 #endif //BT_LINUX_REALTIME
65 
66 #endif //_WIN32
67 
68 #define mymin(a,b) (a > b ? a : b)
69 
71 {
72 
73 #ifdef BT_USE_WINDOWS_TIMERS
74  LARGE_INTEGER mClockFrequency;
75  LONGLONG mStartTick;
76  LARGE_INTEGER mStartTime;
77 #else
78 #ifdef __CELLOS_LV2__
80 #else
81 #ifdef __APPLE__
82  uint64_t mStartTimeNano;
83 #endif
84  struct timeval mStartTime;
85 #endif
86 #endif //__CELLOS_LV2__
87 
88 };
89 
92 {
93  m_data = new btClockData;
94 #ifdef BT_USE_WINDOWS_TIMERS
95  QueryPerformanceFrequency(&m_data->mClockFrequency);
96 #endif
97  reset();
98 }
99 
101 {
102  delete m_data;
103 }
104 
106 {
107  m_data = new btClockData;
108  *m_data = *other.m_data;
109 }
110 
112 {
113  *m_data = *other.m_data;
114  return *this;
115 }
116 
117 
120 {
121 #ifdef BT_USE_WINDOWS_TIMERS
122  QueryPerformanceCounter(&m_data->mStartTime);
123  m_data->mStartTick = GetTickCount64();
124 #else
125 #ifdef __CELLOS_LV2__
126 
127  typedef uint64_t ClockSize;
128  ClockSize newTime;
129  //__asm __volatile__( "mftb %0" : "=r" (newTime) : : "memory");
130  SYS_TIMEBASE_GET( newTime );
131  m_data->mStartTime = newTime;
132 #else
133 #ifdef __APPLE__
134  m_data->mStartTimeNano = mach_absolute_time();
135 #endif
136  gettimeofday(&m_data->mStartTime, 0);
137 #endif
138 #endif
139 }
140 
143 unsigned long long int btClock::getTimeMilliseconds()
144 {
145 #ifdef BT_USE_WINDOWS_TIMERS
146  LARGE_INTEGER currentTime;
147  QueryPerformanceCounter(&currentTime);
148  LONGLONG elapsedTime = currentTime.QuadPart -
149  m_data->mStartTime.QuadPart;
150  // Compute the number of millisecond ticks elapsed.
151  unsigned long msecTicks = (unsigned long)(1000 * elapsedTime /
152  m_data->mClockFrequency.QuadPart);
153 
154  return msecTicks;
155 #else
156 
157 #ifdef __CELLOS_LV2__
158  uint64_t freq=sys_time_get_timebase_frequency();
159  double dFreq=((double) freq) / 1000.0;
160  typedef uint64_t ClockSize;
161  ClockSize newTime;
162  SYS_TIMEBASE_GET( newTime );
163  //__asm __volatile__( "mftb %0" : "=r" (newTime) : : "memory");
164 
165  return (unsigned long int)((double(newTime-m_data->mStartTime)) / dFreq);
166 #else
167 
168  struct timeval currentTime;
169  gettimeofday(&currentTime, 0);
170  return (currentTime.tv_sec - m_data->mStartTime.tv_sec) * 1000 +
171  (currentTime.tv_usec - m_data->mStartTime.tv_usec) / 1000;
172 #endif //__CELLOS_LV2__
173 #endif
174 }
175 
178 unsigned long long int btClock::getTimeMicroseconds()
179 {
180 #ifdef BT_USE_WINDOWS_TIMERS
181  //see https://msdn.microsoft.com/en-us/library/windows/desktop/dn553408(v=vs.85).aspx
182  LARGE_INTEGER currentTime, elapsedTime;
183 
184  QueryPerformanceCounter(&currentTime);
185  elapsedTime.QuadPart = currentTime.QuadPart -
186  m_data->mStartTime.QuadPart;
187  elapsedTime.QuadPart *= 1000000;
188  elapsedTime.QuadPart /= m_data->mClockFrequency.QuadPart;
189 
190  return (unsigned long long) elapsedTime.QuadPart;
191 #else
192 
193 #ifdef __CELLOS_LV2__
194  uint64_t freq=sys_time_get_timebase_frequency();
195  double dFreq=((double) freq)/ 1000000.0;
196  typedef uint64_t ClockSize;
197  ClockSize newTime;
198  //__asm __volatile__( "mftb %0" : "=r" (newTime) : : "memory");
199  SYS_TIMEBASE_GET( newTime );
200 
201  return (unsigned long int)((double(newTime-m_data->mStartTime)) / dFreq);
202 #else
203 
204  struct timeval currentTime;
205  gettimeofday(&currentTime, 0);
206  return (currentTime.tv_sec - m_data->mStartTime.tv_sec) * 1000000 +
207  (currentTime.tv_usec - m_data->mStartTime.tv_usec);
208 #endif//__CELLOS_LV2__
209 #endif
210 }
211 
212 unsigned long long int btClock::getTimeNanoseconds()
213 {
214 #ifdef BT_USE_WINDOWS_TIMERS
215  //see https://msdn.microsoft.com/en-us/library/windows/desktop/dn553408(v=vs.85).aspx
216  LARGE_INTEGER currentTime, elapsedTime;
217 
218  QueryPerformanceCounter(&currentTime);
219  elapsedTime.QuadPart = currentTime.QuadPart -
220  m_data->mStartTime.QuadPart;
221  elapsedTime.QuadPart *= 1000000000;
222  elapsedTime.QuadPart /= m_data->mClockFrequency.QuadPart;
223 
224  return (unsigned long long) elapsedTime.QuadPart;
225 #else
226 
227 #ifdef __CELLOS_LV2__
228  uint64_t freq=sys_time_get_timebase_frequency();
229  double dFreq=((double) freq)/ 1e9;
230  typedef uint64_t ClockSize;
231  ClockSize newTime;
232  //__asm __volatile__( "mftb %0" : "=r" (newTime) : : "memory");
233  SYS_TIMEBASE_GET( newTime );
234 
235  return (unsigned long int)((double(newTime-m_data->mStartTime)) / dFreq);
236 #else
237 #ifdef __APPLE__
238  uint64_t ticks = mach_absolute_time() - m_data->mStartTimeNano;
239  static long double conversion = 0.0L;
240  if( 0.0L == conversion )
241  {
242  // attempt to get conversion to nanoseconds
243  mach_timebase_info_data_t info;
244  int err = mach_timebase_info( &info );
245  if( err )
246  {
247  btAssert(0);
248  conversion = 1.;
249  }
250  conversion = info.numer / info.denom;
251  }
252  return (ticks * conversion);
253 
254 
255 #else//__APPLE__
256 
257 #ifdef BT_LINUX_REALTIME
258  timespec ts;
259  clock_gettime(CLOCK_REALTIME,&ts);
260  return 1000000000*ts.tv_sec + ts.tv_nsec;
261 #else
262  struct timeval currentTime;
263  gettimeofday(&currentTime, 0);
264  return (currentTime.tv_sec - m_data->mStartTime.tv_sec) * 1e9 +
265  (currentTime.tv_usec - m_data->mStartTime.tv_usec)*1000;
266 #endif //BT_LINUX_REALTIME
267 
268 #endif//__APPLE__
269 #endif//__CELLOS_LV2__
270 #endif
271 }
272 
273 
277 {
278  static const btScalar microseconds_to_seconds = btScalar(0.000001);
279  return btScalar(getTimeMicroseconds()) * microseconds_to_seconds;
280 }
281 
282 #ifndef BT_NO_PROFILE
283 
284 
286 
287 
288 inline void Profile_Get_Ticks(unsigned long int * ticks)
289 {
290  *ticks = (unsigned long int)gProfileClock.getTimeMicroseconds();
291 }
292 
293 inline float Profile_Get_Tick_Rate(void)
294 {
295 // return 1000000.f;
296  return 1000.f;
297 
298 }
299 
300 
301 /***************************************************************************************************
302 **
303 ** CProfileNode
304 **
305 ***************************************************************************************************/
306 
307 /***********************************************************************************************
308  * INPUT: *
309  * name - pointer to a static string which is the name of this profile node *
310  * parent - parent pointer *
311  * *
312  * WARNINGS: *
313  * The name is assumed to be a static pointer, only the pointer is stored and compared for *
314  * efficiency reasons. *
315  *=============================================================================================*/
316 CProfileNode::CProfileNode( const char * name, CProfileNode * parent ) :
317  Name( name ),
318  TotalCalls( 0 ),
319  TotalTime( 0 ),
320  StartTime( 0 ),
321  RecursionCounter( 0 ),
322  Parent( parent ),
323  Child( NULL ),
324  Sibling( NULL ),
325  m_userPtr(0)
326 {
327  Reset();
328 }
329 
330 
332 {
333  delete ( Child);
334  Child = NULL;
335  delete ( Sibling);
336  Sibling = NULL;
337 }
338 
340 {
341  CleanupMemory();
342 }
343 
344 
345 /***********************************************************************************************
346  * INPUT: *
347  * name - static string pointer to the name of the node we are searching for *
348  * *
349  * WARNINGS: *
350  * All profile names are assumed to be static strings so this function uses pointer compares *
351  * to find the named node. *
352  *=============================================================================================*/
354 {
355  // Try to find this sub node
356  CProfileNode * child = Child;
357  while ( child ) {
358  if ( child->Name == name ) {
359  return child;
360  }
361  child = child->Sibling;
362  }
363 
364  // We didn't find it, so add it
365 
366  CProfileNode * node = new CProfileNode( name, this );
367  node->Sibling = Child;
368  Child = node;
369  return node;
370 }
371 
372 
374 {
375  TotalCalls = 0;
376  TotalTime = 0.0f;
377 
378 
379  if ( Child ) {
380  Child->Reset();
381  }
382  if ( Sibling ) {
383  Sibling->Reset();
384  }
385 }
386 
387 
388 void CProfileNode::Call( void )
389 {
390  TotalCalls++;
391  if (RecursionCounter++ == 0) {
393  }
394 }
395 
396 
398 {
399  if ( --RecursionCounter == 0 && TotalCalls != 0 ) {
400  unsigned long int time;
401  Profile_Get_Ticks(&time);
402 
403  time-=StartTime;
404  TotalTime += (float)time / Profile_Get_Tick_Rate();
405  }
406  return ( RecursionCounter == 0 );
407 }
408 
409 
410 /***************************************************************************************************
411 **
412 ** CProfileIterator
413 **
414 ***************************************************************************************************/
416 {
417  CurrentParent = start;
418  CurrentChild = CurrentParent->Get_Child();
419 }
420 
421 
423 {
424  CurrentChild = CurrentParent->Get_Child();
425 }
426 
427 
429 {
430  CurrentChild = CurrentChild->Get_Sibling();
431 }
432 
433 
435 {
436  return CurrentChild == NULL;
437 }
438 
439 
441 {
442  CurrentChild = CurrentParent->Get_Child();
443  while ( (CurrentChild != NULL) && (index != 0) ) {
444  index--;
445  CurrentChild = CurrentChild->Get_Sibling();
446  }
447 
448  if ( CurrentChild != NULL ) {
449  CurrentParent = CurrentChild;
450  CurrentChild = CurrentParent->Get_Child();
451  }
452 }
453 
454 
456 {
457  if ( CurrentParent->Get_Parent() != NULL ) {
458  CurrentParent = CurrentParent->Get_Parent();
459  }
460  CurrentChild = CurrentParent->Get_Child();
461 }
462 
463 
464 /***************************************************************************************************
465 **
466 ** CProfileManager
467 **
468 ***************************************************************************************************/
469 
470 
471 
472 
474  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
475  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
476  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
477  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
478  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
479  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
480  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
481  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
482  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
483  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
484  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
485  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
486  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
487  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
488  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),
489  CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL),CProfileNode("Root",NULL)
490 };
491 
492 
494 {
495  &gRoots[ 0], &gRoots[ 1], &gRoots[ 2], &gRoots[ 3],
496  &gRoots[ 4], &gRoots[ 5], &gRoots[ 6], &gRoots[ 7],
497  &gRoots[ 8], &gRoots[ 9], &gRoots[10], &gRoots[11],
498  &gRoots[12], &gRoots[13], &gRoots[14], &gRoots[15],
499  &gRoots[16], &gRoots[17], &gRoots[18], &gRoots[19],
500  &gRoots[20], &gRoots[21], &gRoots[22], &gRoots[23],
501  &gRoots[24], &gRoots[25], &gRoots[26], &gRoots[27],
502  &gRoots[28], &gRoots[29], &gRoots[30], &gRoots[31],
503  &gRoots[32], &gRoots[33], &gRoots[34], &gRoots[35],
504  &gRoots[36], &gRoots[37], &gRoots[38], &gRoots[39],
505  &gRoots[40], &gRoots[41], &gRoots[42], &gRoots[43],
506  &gRoots[44], &gRoots[45], &gRoots[46], &gRoots[47],
507  &gRoots[48], &gRoots[49], &gRoots[50], &gRoots[51],
508  &gRoots[52], &gRoots[53], &gRoots[54], &gRoots[55],
509  &gRoots[56], &gRoots[57], &gRoots[58], &gRoots[59],
510  &gRoots[60], &gRoots[61], &gRoots[62], &gRoots[63],
511 };
512 
513 
515 unsigned long int CProfileManager::ResetTime = 0;
516 
518 {
519 
520  int threadIndex = btQuickprofGetCurrentThreadIndex2();
521  if ((threadIndex<0) || threadIndex >= BT_QUICKPROF_MAX_THREAD_COUNT)
522  return 0;
523 
524  return new CProfileIterator( &gRoots[threadIndex]);
525 }
526 
528 {
529  for (int i=0;i<BT_QUICKPROF_MAX_THREAD_COUNT;i++)
530  {
531  gRoots[i].CleanupMemory();
532  }
533 }
534 
535 
536 /***********************************************************************************************
537  * CProfileManager::Start_Profile -- Begin a named profile *
538  * *
539  * Steps one level deeper into the tree, if a child already exists with the specified name *
540  * then it accumulates the profiling; otherwise a new child node is added to the profile tree. *
541  * *
542  * INPUT: *
543  * name - name of this profiling record *
544  * *
545  * WARNINGS: *
546  * The string used is assumed to be a static string; pointer compares are used throughout *
547  * the profiling code for efficiency. *
548  *=============================================================================================*/
549 void CProfileManager::Start_Profile( const char * name )
550 {
551  int threadIndex = btQuickprofGetCurrentThreadIndex2();
552  if ((threadIndex<0) || threadIndex >= BT_QUICKPROF_MAX_THREAD_COUNT)
553  return;
554 
555  if (name != gCurrentNodes[threadIndex]->Get_Name()) {
556  gCurrentNodes[threadIndex] = gCurrentNodes[threadIndex]->Get_Sub_Node( name );
557  }
558 
559  gCurrentNodes[threadIndex]->Call();
560 }
561 
562 
563 /***********************************************************************************************
564  * CProfileManager::Stop_Profile -- Stop timing and record the results. *
565  *=============================================================================================*/
567 {
568  int threadIndex = btQuickprofGetCurrentThreadIndex2();
569  if ((threadIndex<0) || threadIndex >= BT_QUICKPROF_MAX_THREAD_COUNT)
570  return;
571 
572  // Return will indicate whether we should back up to our parent (we may
573  // be profiling a recursive function)
574  if (gCurrentNodes[threadIndex]->Return()) {
575  gCurrentNodes[threadIndex] = gCurrentNodes[threadIndex]->Get_Parent();
576  }
577 }
578 
579 
580 
581 
582 
583 
584 /***********************************************************************************************
585  * CProfileManager::Reset -- Reset the contents of the profiling system *
586  * *
587  * This resets everything except for the tree structure. All of the timing data is reset. *
588  *=============================================================================================*/
590 {
591  gProfileClock.reset();
592  int threadIndex = btQuickprofGetCurrentThreadIndex2();
593  if ((threadIndex<0) || threadIndex >= BT_QUICKPROF_MAX_THREAD_COUNT)
594  return;
595  gRoots[threadIndex].Reset();
596  gRoots[threadIndex].Call();
597  FrameCounter = 0;
598  Profile_Get_Ticks(&ResetTime);
599 }
600 
601 
602 /***********************************************************************************************
603  * CProfileManager::Increment_Frame_Counter -- Increment the frame counter *
604  *=============================================================================================*/
606 {
607  FrameCounter++;
608 }
609 
610 
611 /***********************************************************************************************
612  * CProfileManager::Get_Time_Since_Reset -- returns the elapsed time since last reset *
613  *=============================================================================================*/
615 {
616  unsigned long int time;
617  Profile_Get_Ticks(&time);
618  time -= ResetTime;
619  return (float)time / Profile_Get_Tick_Rate();
620 }
621 
622 #include <stdio.h>
623 
624 void CProfileManager::dumpRecursive(CProfileIterator* profileIterator, int spacing)
625 {
626  profileIterator->First();
627  if (profileIterator->Is_Done())
628  return;
629 
630  float accumulated_time=0,parent_time = profileIterator->Is_Root() ? CProfileManager::Get_Time_Since_Reset() : profileIterator->Get_Current_Parent_Total_Time();
631  int i;
632  int frames_since_reset = CProfileManager::Get_Frame_Count_Since_Reset();
633  for (i=0;i<spacing;i++) printf(".");
634  printf("----------------------------------\n");
635  for (i=0;i<spacing;i++) printf(".");
636  printf("Profiling: %s (total running time: %.3f ms) ---\n", profileIterator->Get_Current_Parent_Name(), parent_time );
637  float totalTime = 0.f;
638 
639 
640  int numChildren = 0;
641 
642  for (i = 0; !profileIterator->Is_Done(); i++,profileIterator->Next())
643  {
644  numChildren++;
645  float current_total_time = profileIterator->Get_Current_Total_Time();
646  accumulated_time += current_total_time;
647  float fraction = parent_time > SIMD_EPSILON ? (current_total_time / parent_time) * 100 : 0.f;
648  {
649  int i; for (i=0;i<spacing;i++) printf(".");
650  }
651  printf("%d -- %s (%.2f %%) :: %.3f ms / frame (%d calls)\n",i, profileIterator->Get_Current_Name(), fraction,(current_total_time / (double)frames_since_reset),profileIterator->Get_Current_Total_Calls());
652  totalTime += current_total_time;
653  //recurse into children
654  }
655 
656  if (parent_time < accumulated_time)
657  {
658  //printf("what's wrong\n");
659  }
660  for (i=0;i<spacing;i++) printf(".");
661  printf("%s (%.3f %%) :: %.3f ms\n", "Unaccounted:",parent_time > SIMD_EPSILON ? ((parent_time - accumulated_time) / parent_time) * 100 : 0.f, parent_time - accumulated_time);
662 
663  for (i=0;i<numChildren;i++)
664  {
665  profileIterator->Enter_Child(i);
666  dumpRecursive(profileIterator,spacing+3);
667  profileIterator->Enter_Parent();
668  }
669 }
670 
671 
672 
674 {
675  CProfileIterator* profileIterator = 0;
676  profileIterator = CProfileManager::Get_Iterator();
677 
678  dumpRecursive(profileIterator,0);
679 
680  CProfileManager::Release_Iterator(profileIterator);
681 }
682 
683 // clang-format off
684 #if defined(_WIN32) && (defined(__MINGW32__) || defined(__MINGW64__))
685  #define BT_HAVE_TLS 1
686 #elif __APPLE__ && !TARGET_OS_IPHONE
687  // TODO: Modern versions of iOS support TLS now with updated version checking.
688  #define BT_HAVE_TLS 1
689 #elif __linux__
690  #define BT_HAVE_TLS 1
691 #endif
692 
693 // __thread is broken on Andorid clang until r12b. See
694 // https://github.com/android-ndk/ndk/issues/8
695 #if defined(__ANDROID__) && defined(__clang__)
696  #if __has_include(<android/ndk-version.h>)
697  #include <android/ndk-version.h>
698  #endif // __has_include(<android/ndk-version.h>)
699  #if defined(__NDK_MAJOR__) && \
700  ((__NDK_MAJOR__ < 12) || ((__NDK_MAJOR__ == 12) && (__NDK_MINOR__ < 1)))
701  #undef BT_HAVE_TLS
702  #endif
703 #endif // defined(__ANDROID__) && defined(__clang__)
704 // clang-format on
705 
707  const unsigned int kNullIndex = ~0U;
708 
709 #if BT_THREADSAFE
710  return btGetCurrentThreadIndex();
711 #else
712 #if defined(BT_HAVE_TLS)
713  static __thread unsigned int sThreadIndex = kNullIndex;
714 #elif defined(_WIN32)
715  __declspec(thread) static unsigned int sThreadIndex = kNullIndex;
716 #else
717  unsigned int sThreadIndex = 0;
718  return -1;
719 #endif
720 
721  static int gThreadCounter = 0;
722 
723  if (sThreadIndex == kNullIndex) {
724  sThreadIndex = gThreadCounter++;
725  }
726  return sThreadIndex;
727 #endif //BT_THREADSAFE
728 }
729 
730 void btEnterProfileZoneDefault(const char* name)
731 {
732 }
734 {
735 }
736 
737 
738 #else
739 void btEnterProfileZoneDefault(const char* name)
740 {
741 }
743 {
744 }
745 #endif //BT_NO_PROFILE
746 
747 
748 
749 
750 
753 
754 void btEnterProfileZone(const char* name)
755 {
756  (bts_enterFunc)(name);
757 }
759 {
760  (bts_leaveFunc)();
761 }
762 
764 {
765  return bts_enterFunc ;
766 }
768 {
769  return bts_leaveFunc;
770 }
771 
772 
774 {
775  bts_enterFunc = enterFunc;
776 }
778 {
779  bts_leaveFunc = leaveFunc;
780 }
781 
782 CProfileSample::CProfileSample( const char * name )
783 {
784  btEnterProfileZone(name);
785 }
786 
788 {
790 }
791 
CProfileNode * Get_Sub_Node(const char *name)
#define SIMD_EPSILON
Definition: btScalar.h:521
CProfileSample(const char *name)
CProfileNode * Get_Child(void)
Definition: btQuickprof.h:104
unsigned long long int uint64_t
static CProfileIterator * Get_Iterator(void)
CProfileIterator(CProfileNode *start)
CProfileNode gRoots[BT_QUICKPROF_MAX_THREAD_COUNT]
void CleanupMemory()
static void Start_Profile(const char *name)
static void CleanupMemory(void)
int RecursionCounter
Definition: btQuickprof.h:122
btEnterProfileZoneFunc * btGetCurrentEnterProfileZoneFunc()
static void dumpAll()
btScalar getTimeSeconds()
Returns the time in s since the last call to reset or since the Clock was created.
void First(void)
unsigned int btQuickprofGetCurrentThreadIndex2()
#define btAssert(x)
Definition: btScalar.h:131
unsigned long long int getTimeNanoseconds()
const char * Get_Current_Name(void)
Definition: btQuickprof.h:145
bool Return(void)
float Get_Current_Parent_Total_Time(void)
Definition: btQuickprof.h:154
The btClock is a portable basic clock that measures accurate time in seconds, use for profiling...
Definition: btQuickprof.h:24
void Reset(void)
float Get_Current_Total_Time(void)
Definition: btQuickprof.h:147
void Enter_Child(int index)
LARGE_INTEGER mStartTime
Definition: btQuickprof.cpp:76
void reset()
Resets the initial reference time.
An iterator to navigate through the tree.
Definition: btQuickprof.h:131
float TotalTime
Definition: btQuickprof.h:120
static void Stop_Profile(void)
float Profile_Get_Tick_Rate(void)
void btSetCustomEnterProfileZoneFunc(btEnterProfileZoneFunc *enterFunc)
btLeaveProfileZoneFunc * btGetCurrentLeaveProfileZoneFunc()
CProfileNode * Child
Definition: btQuickprof.h:125
void btEnterProfileZone(const char *name)
static void dumpRecursive(CProfileIterator *profileIterator, int spacing)
static unsigned long int ResetTime
Definition: btQuickprof.h:199
btClock()
The btClock is a portable basic clock that measures accurate time in seconds, use for profiling...
Definition: btQuickprof.cpp:91
struct btClockData * m_data
Definition: btQuickprof.h:52
static ThreadsafeCounter gThreadCounter
Definition: btThreads.cpp:259
void btLeaveProfileZone()
void Profile_Get_Ticks(unsigned long int *ticks)
bool Is_Done(void)
unsigned long long int getTimeMicroseconds()
Returns the time in us since the last call to reset or since the Clock was created.
CProfileNode * gCurrentNodes[BT_QUICKPROF_MAX_THREAD_COUNT]
void btSetCustomLeaveProfileZoneFunc(btLeaveProfileZoneFunc *leaveFunc)
static void Release_Iterator(CProfileIterator *iterator)
Definition: btQuickprof.h:190
static void Reset(void)
btClock & operator=(const btClock &other)
void( btLeaveProfileZoneFunc)()
Definition: btQuickprof.h:58
static btClock gProfileClock
static float Get_Time_Since_Reset(void)
unsigned long long int getTimeMilliseconds()
Returns the time in ms since the last call to reset or since the btClock was created.
A node in the Profile Hierarchy Tree.
Definition: btQuickprof.h:94
const char * Name
Definition: btQuickprof.h:118
static void Increment_Frame_Counter(void)
void Call(void)
CProfileNode * Get_Parent(void)
Definition: btQuickprof.h:102
~CProfileNode(void)
const unsigned int BT_QUICKPROF_MAX_THREAD_COUNT
Definition: btQuickprof.h:73
static btEnterProfileZoneFunc * bts_enterFunc
int Get_Current_Total_Calls(void)
Definition: btQuickprof.h:146
void btLeaveProfileZoneDefault()
const char * Get_Name(void)
Definition: btQuickprof.h:111
unsigned long int StartTime
Definition: btQuickprof.h:121
CProfileNode(const char *name, CProfileNode *parent)
unsigned int U
Definition: btGjkEpa3.h:87
#define GetTickCount64
Definition: btQuickprof.cpp:50
LARGE_INTEGER mClockFrequency
Definition: btQuickprof.cpp:74
void Enter_Parent(void)
static int Get_Frame_Count_Since_Reset(void)
Definition: btQuickprof.h:182
unsigned int btGetCurrentThreadIndex()
Definition: btThreads.cpp:304
void( btEnterProfileZoneFunc)(const char *msg)
Definition: btQuickprof.h:57
const char * Get_Current_Parent_Name(void)
Definition: btQuickprof.h:152
bool Is_Root(void)
Definition: btQuickprof.h:138
LONGLONG mStartTick
Definition: btQuickprof.cpp:75
static int FrameCounter
Definition: btQuickprof.h:198
CProfileNode * Sibling
Definition: btQuickprof.h:126
static btLeaveProfileZoneFunc * bts_leaveFunc
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition: btScalar.h:292
void btEnterProfileZoneDefault(const char *name)