test_fcl_utility.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2016, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
38 #include "test_fcl_utility.h"
42 #include <cstdio>
43 #include <cstddef>
44 
45 namespace fcl
46 {
47 
48 namespace test
49 {
50 
51 //==============================================================================
53 {
54 #ifdef _WIN32
55  QueryPerformanceFrequency(&frequency);
56  startCount.QuadPart = 0;
57  endCount.QuadPart = 0;
58 #else
59  startCount.tv_sec = startCount.tv_usec = 0;
60  endCount.tv_sec = endCount.tv_usec = 0;
61 #endif
62 
63  stopped = 0;
66 }
67 
68 //==============================================================================
70 {
71  // Do nothing
72 }
73 
74 //==============================================================================
76 {
77  stopped = 0; // reset stop flag
78 #ifdef _WIN32
79  QueryPerformanceCounter(&startCount);
80 #else
81  gettimeofday(&startCount, nullptr);
82 #endif
83 }
84 
85 //==============================================================================
87 {
88  stopped = 1; // set timer stopped flag
89 
90 #ifdef _WIN32
91  QueryPerformanceCounter(&endCount);
92 #else
93  gettimeofday(&endCount, nullptr);
94 #endif
95 }
96 
98 {
99 #ifdef _WIN32
100  if(!stopped)
101  QueryPerformanceCounter(&endCount);
102 
103  startTimeInMicroSec = startCount.QuadPart * (1000000.0 / frequency.QuadPart);
104  endTimeInMicroSec = endCount.QuadPart * (1000000.0 / frequency.QuadPart);
105 #else
106  if(!stopped)
107  gettimeofday(&endCount, nullptr);
108 
109  startTimeInMicroSec = (startCount.tv_sec * 1000000.0) + startCount.tv_usec;
110  endTimeInMicroSec = (endCount.tv_sec * 1000000.0) + endCount.tv_usec;
111 #endif
112 
114 }
115 
116 //==============================================================================
118 {
119  return this->getElapsedTimeInMicroSec() * 0.001;
120 }
121 
122 //==============================================================================
124 {
125  return this->getElapsedTimeInMicroSec() * 0.000001;
126 }
127 
128 //==============================================================================
130 {
131  return this->getElapsedTimeInMilliSec();
132 }
133 
134 //==============================================================================
135 std::string getNodeTypeName(NODE_TYPE node_type)
136 {
137  if (node_type == BV_UNKNOWN)
138  return std::string("BV_UNKNOWN");
139  else if (node_type == BV_AABB)
140  return std::string("BV_AABB");
141  else if (node_type == BV_OBB)
142  return std::string("BV_OBB");
143  else if (node_type == BV_RSS)
144  return std::string("BV_RSS");
145  else if (node_type == BV_kIOS)
146  return std::string("BV_kIOS");
147  else if (node_type == BV_OBBRSS)
148  return std::string("BV_OBBRSS");
149  else if (node_type == BV_KDOP16)
150  return std::string("BV_KDOP16");
151  else if (node_type == BV_KDOP18)
152  return std::string("BV_KDOP18");
153  else if (node_type == BV_KDOP24)
154  return std::string("BV_KDOP24");
155  else if (node_type == GEOM_BOX)
156  return std::string("GEOM_BOX");
157  else if (node_type == GEOM_SPHERE)
158  return std::string("GEOM_SPHERE");
159  else if (node_type == GEOM_ELLIPSOID)
160  return std::string("GEOM_ELLIPSOID");
161  else if (node_type == GEOM_CAPSULE)
162  return std::string("GEOM_CAPSULE");
163  else if (node_type == GEOM_CONE)
164  return std::string("GEOM_CONE");
165  else if (node_type == GEOM_CYLINDER)
166  return std::string("GEOM_CYLINDER");
167  else if (node_type == GEOM_CONVEX)
168  return std::string("GEOM_CONVEX");
169  else if (node_type == GEOM_PLANE)
170  return std::string("GEOM_PLANE");
171  else if (node_type == GEOM_HALFSPACE)
172  return std::string("GEOM_HALFSPACE");
173  else if (node_type == GEOM_TRIANGLE)
174  return std::string("GEOM_TRIANGLE");
175  else if (node_type == GEOM_OCTREE)
176  return std::string("GEOM_OCTREE");
177  else
178  return std::string("invalid");
179 }
180 
181 //==============================================================================
182 std::string getGJKSolverName(GJKSolverType solver_type)
183 {
184  if (solver_type == GST_LIBCCD)
185  return std::string("libccd");
186  else if (solver_type == GST_INDEP)
187  return std::string("built-in");
188  else
189  return std::string("invalid");
190 }
191 
192 } // namespace test
193 } // namespace fcl
fcl::test::Timer::getElapsedTimeInMilliSec
double getElapsedTimeInMilliSec()
get elapsed time in milli-second
Definition: test_fcl_utility.cpp:117
fcl::GJKSolverType
GJKSolverType
Type of narrow phase GJK solver.
Definition: gjk_solver_type.h:45
fcl::test::Timer::endTimeInMicroSec
double endTimeInMicroSec
ending time in micro-second
Definition: test_fcl_utility.h:92
fcl::GEOM_OCTREE
@ GEOM_OCTREE
Definition: collision_geometry.h:54
fcl::test::Timer::getElapsedTime
double getElapsedTime()
get elapsed time in milli-second
Definition: test_fcl_utility.cpp:129
fcl::GEOM_HALFSPACE
@ GEOM_HALFSPACE
Definition: collision_geometry.h:54
fcl::test::Timer::~Timer
~Timer()
Definition: test_fcl_utility.cpp:69
fcl::GEOM_CONE
@ GEOM_CONE
Definition: collision_geometry.h:54
fcl::test::Timer::start
void start()
start timer
Definition: test_fcl_utility.cpp:75
fcl::test::Timer::getElapsedTimeInMicroSec
double getElapsedTimeInMicroSec()
get elapsed time in micro-second
Definition: test_fcl_utility.cpp:97
fcl::GEOM_PLANE
@ GEOM_PLANE
Definition: collision_geometry.h:54
fcl::BV_KDOP18
@ BV_KDOP18
Definition: collision_geometry.h:53
fcl::GEOM_ELLIPSOID
@ GEOM_ELLIPSOID
Definition: collision_geometry.h:54
test_fcl_utility.h
fcl::test::Timer::getElapsedTimeInSec
double getElapsedTimeInSec()
get elapsed time in second (same as getElapsedTime)
Definition: test_fcl_utility.cpp:123
fcl::test::Timer::startTimeInMicroSec
double startTimeInMicroSec
starting time in micro-second
Definition: test_fcl_utility.h:91
distance.h
fcl::GEOM_TRIANGLE
@ GEOM_TRIANGLE
Definition: collision_geometry.h:54
fcl::BV_KDOP24
@ BV_KDOP24
Definition: collision_geometry.h:53
fcl::GST_LIBCCD
@ GST_LIBCCD
Definition: gjk_solver_type.h:45
fcl::test::getNodeTypeName
std::string getNodeTypeName(NODE_TYPE node_type)
Definition: test_fcl_utility.cpp:135
fcl::test::Timer::stopped
int stopped
stop flag
Definition: test_fcl_utility.h:93
fcl::BV_UNKNOWN
@ BV_UNKNOWN
Definition: collision_geometry.h:53
fcl::BV_OBB
@ BV_OBB
Definition: collision_geometry.h:53
fcl::test::Timer::startCount
timeval startCount
Definition: test_fcl_utility.h:99
fcl::BV_KDOP16
@ BV_KDOP16
Definition: collision_geometry.h:53
fcl::GEOM_SPHERE
@ GEOM_SPHERE
Definition: collision_geometry.h:54
continuous_collision.h
fcl::GEOM_CYLINDER
@ GEOM_CYLINDER
Definition: collision_geometry.h:54
fcl::GEOM_CONVEX
@ GEOM_CONVEX
Definition: collision_geometry.h:54
fcl::test::Timer::Timer
Timer()
Definition: test_fcl_utility.cpp:52
fcl::test::Timer::endCount
timeval endCount
Definition: test_fcl_utility.h:100
fcl::test::Timer::stop
void stop()
stop the timer
Definition: test_fcl_utility.cpp:86
fcl::BV_kIOS
@ BV_kIOS
Definition: collision_geometry.h:53
fcl::GEOM_BOX
@ GEOM_BOX
Definition: collision_geometry.h:54
fcl::BV_RSS
@ BV_RSS
Definition: collision_geometry.h:53
fcl::GST_INDEP
@ GST_INDEP
Definition: gjk_solver_type.h:45
fcl::BV_OBBRSS
@ BV_OBBRSS
Definition: collision_geometry.h:53
fcl::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: collision_geometry.h:53
fcl::BV_AABB
@ BV_AABB
Definition: collision_geometry.h:53
fcl::test::getGJKSolverName
std::string getGJKSolverName(GJKSolverType solver_type)
Definition: test_fcl_utility.cpp:182
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
fcl::GEOM_CAPSULE
@ GEOM_CAPSULE
Definition: collision_geometry.h:54
collision.h


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:49