utility.h
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-2015, 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 #ifndef TEST_HPP_FCL_UTILITY_H
39 #define TEST_HPP_FCL_UTILITY_H
40 
41 #include <hpp/fcl/math/transform.h>
42 #include <hpp/fcl/collision_data.h>
45 #include <hpp/fcl/shape/convex.h>
46 
47 #ifdef HPP_FCL_HAS_OCTOMAP
48 #include <hpp/fcl/octree.h>
49 #endif
50 
51 #ifdef _WIN32
52 #define NOMINMAX // required to avoid compilation errors with Visual Studio
53  // 2010
54 #include <windows.h>
55 #else
56 #include <sys/time.h>
57 #endif
58 
59 #define EIGEN_VECTOR_IS_APPROX(Va, Vb, precision) \
60  BOOST_CHECK_MESSAGE(((Va) - (Vb)).isZero(precision), \
61  "check " #Va ".isApprox(" #Vb \
62  ") failed " \
63  "[\n" \
64  << (Va).transpose() << "\n!=\n" \
65  << (Vb).transpose() << "\n]")
66 #define EIGEN_MATRIX_IS_APPROX(Va, Vb, precision) \
67  BOOST_CHECK_MESSAGE(((Va) - (Vb)).isZero(precision), "check " #Va \
68  ".isApprox(" #Vb \
69  ") failed " \
70  "[\n" \
71  << (Va) << "\n!=\n" \
72  << (Vb) << "\n]")
73 
74 namespace octomap {
75 #ifdef HPP_FCL_HAS_OCTOMAP
76 typedef hpp::fcl::shared_ptr<octomap::OcTree> OcTreePtr_t;
77 #endif
78 } // namespace octomap
79 namespace hpp {
80 namespace fcl {
81 
82 class BenchTimer {
83  public:
84  BenchTimer();
85  ~BenchTimer();
86 
87  void start();
88  void stop();
89  double getElapsedTime();
90  double getElapsedTimeInSec();
91  double getElapsedTimeInMilliSec();
93  double getElapsedTimeInMicroSec();
94 
95  private:
98  int stopped;
99 #ifdef _WIN32
100  LARGE_INTEGER frequency;
101  LARGE_INTEGER startCount;
102  LARGE_INTEGER endCount;
103 #else
104  timeval startCount;
105  timeval endCount;
106 #endif
107 };
108 
109 struct TStruct {
110  std::vector<double> records;
111  double overall_time;
112 
114 
115  void push_back(double t) {
116  records.push_back(t);
117  overall_time += t;
118  }
119 };
120 
121 extern const Eigen::IOFormat vfmt;
122 extern const Eigen::IOFormat pyfmt;
123 typedef Eigen::AngleAxis<FCL_REAL> AngleAxis;
124 extern const Vec3f UnitX;
125 extern const Vec3f UnitY;
126 extern const Vec3f UnitZ;
127 
129 void loadOBJFile(const char* filename, std::vector<Vec3f>& points,
130  std::vector<Triangle>& triangles);
131 
132 void saveOBJFile(const char* filename, std::vector<Vec3f>& points,
133  std::vector<Triangle>& triangles);
134 
135 #ifdef HPP_FCL_HAS_OCTOMAP
136 fcl::OcTree loadOctreeFile(const std::string& filename,
137  const FCL_REAL& resolution);
138 #endif
139 
145 
149  std::vector<Transform3f>& transforms,
150  std::size_t n);
151 
155 void generateRandomTransforms(FCL_REAL extents[6], FCL_REAL delta_trans[3],
156  FCL_REAL delta_rot,
157  std::vector<Transform3f>& transforms,
158  std::vector<Transform3f>& transforms2,
159  std::size_t n);
160 
163 struct DistanceRes {
164  double distance;
167 };
168 
172  void* cdata);
173 
178  void* cdata, FCL_REAL& dist);
179 
180 std::string getNodeTypeName(NODE_TYPE node_type);
181 
183 
184 std::ostream& operator<<(std::ostream& os, const Transform3f& tf);
185 
187 std::size_t getNbRun(const int& argc, char const* const* argv,
188  std::size_t defaultValue);
189 
190 void generateEnvironments(std::vector<CollisionObject*>& env,
191  FCL_REAL env_scale, std::size_t n);
192 
193 void generateEnvironmentsMesh(std::vector<CollisionObject*>& env,
194  FCL_REAL env_scale, std::size_t n);
195 
202 
203 } // namespace fcl
204 
205 } // namespace hpp
206 
207 #endif
hpp::fcl::UnitX
const Vec3f UnitX
Definition: utility.cpp:87
hpp::fcl::TStruct
Definition: utility.h:109
hpp::fcl::TStruct::TStruct
TStruct()
Definition: utility.h:113
hpp::fcl::pyfmt
const Eigen::IOFormat pyfmt
Definition: utility.cpp:84
hpp::fcl::Vec3f
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
hpp::fcl::loadOBJFile
void loadOBJFile(const char *filename, std::vector< Vec3f > &points, std::vector< Triangle > &triangles)
Load an obj mesh file.
Definition: utility.cpp:96
hpp::fcl::transform
HPP_FCL_DLLAPI Halfspace transform(const Halfspace &a, const Transform3f &tf)
Definition: geometric_shapes_utility.cpp:248
hpp::fcl::BenchTimer::startCount
timeval startCount
Definition: utility.h:104
collision_object.h
hpp::fcl::vfmt
const Eigen::IOFormat vfmt
Definition: utility.cpp:82
hpp::fcl::OcTreePtr_t
shared_ptr< OcTree > OcTreePtr_t
Definition: include/hpp/fcl/fwd.hh:106
hpp::fcl::DistanceRes::p1
Vec3f p1
Definition: utility.h:165
default_broadphase_callbacks.h
hpp::fcl::BenchTimer::endCount
timeval endCount
Definition: utility.h:105
hpp::fcl::BenchTimer::getElapsedTimeInMilliSec
double getElapsedTimeInMilliSec()
get elapsed time in milli-second
Definition: utility.cpp:72
hpp::fcl::BenchTimer::BenchTimer
BenchTimer()
Definition: utility.cpp:18
hpp::fcl::DistanceRes::distance
double distance
Definition: utility.h:164
hpp::fcl::BenchTimer::~BenchTimer
~BenchTimer()
Definition: utility.cpp:33
hpp::fcl::generateEnvironmentsMesh
void generateEnvironmentsMesh(std::vector< CollisionObject * > &env, FCL_REAL env_scale, std::size_t n)
Definition: utility.cpp:421
hpp::fcl::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: collision_object.h:65
extents
FCL_REAL extents[6]
Definition: test/geometric_shapes.cpp:51
hpp::fcl::generateEnvironments
void generateEnvironments(std::vector< CollisionObject * > &env, FCL_REAL env_scale, std::size_t n)
Definition: utility.cpp:390
hpp::fcl::TStruct::push_back
void push_back(double t)
Definition: utility.h:115
hpp::fcl::Convex
Convex polytope.
Definition: shape/convex.h:50
hpp::fcl::Ellipsoid
Ellipsoid centered at point zero.
Definition: shape/geometric_shapes.h:258
hpp::fcl::FCL_REAL
double FCL_REAL
Definition: data_types.h:65
hpp::fcl::operator<<
static std::ostream & operator<<(std::ostream &o, const Quaternion3f &q)
Definition: transform.h:48
hpp::fcl::BenchTimer::stop
void stop()
stop the timer
Definition: utility.cpp:44
hpp::fcl::getNodeTypeName
std::string getNodeTypeName(NODE_TYPE node_type)
Definition: utility.cpp:325
hpp::fcl::makeQuat
Quaternion3f makeQuat(FCL_REAL w, FCL_REAL x, FCL_REAL y, FCL_REAL z)
Definition: utility.cpp:368
hpp::fcl::constructPolytopeFromEllipsoid
Convex< Triangle > constructPolytopeFromEllipsoid(const Ellipsoid &ellipsoid)
We give an ellipsoid as input. The output is a 20 faces polytope which vertices belong to the origina...
Definition: utility.cpp:477
hpp::fcl::AngleAxis
Eigen::AngleAxis< FCL_REAL > AngleAxis
Definition: utility.h:123
hpp::fcl::defaultDistanceFunction
bool defaultDistanceFunction(CollisionObject *o1, CollisionObject *o2, void *data, FCL_REAL &dist)
Collision data for use with the DefaultContinuousCollisionFunction. It stores the collision request a...
Definition: default_broadphase_callbacks.cpp:67
collision-bench.filename
filename
Definition: collision-bench.py:6
collision_data.h
hpp
Main namespace.
Definition: broadphase_bruteforce.h:44
hpp::fcl::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: collision_object.h:215
hpp::fcl::BenchTimer::getElapsedTime
double getElapsedTime()
get elapsed time in milli-second
Definition: utility.cpp:80
hpp::fcl::getNbRun
std::size_t getNbRun(const int &argc, char const *const *argv, std::size_t defaultValue)
Get the argument –nb-run from argv.
Definition: utility.cpp:382
t
tuple t
hpp::fcl::BenchTimer::getElapsedTimeInSec
double getElapsedTimeInSec()
Definition: utility.cpp:76
hpp::fcl::generateRandomTransforms
void generateRandomTransforms(FCL_REAL extents[6], std::vector< Transform3f > &transforms, std::size_t n)
Generate n random transforms whose translations are constrained by extents.
Definition: utility.cpp:224
hpp::fcl::BenchTimer::startTimeInMicroSec
double startTimeInMicroSec
starting time in micro-second
Definition: utility.h:96
hpp::fcl::saveOBJFile
void saveOBJFile(const char *filename, std::vector< Vec3f > &points, std::vector< Triangle > &triangles)
Definition: utility.cpp:162
hpp::fcl::TStruct::records
std::vector< double > records
Definition: utility.h:110
hpp::fcl::BenchTimer
Definition: utility.h:82
hpp::fcl::Transform3f
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
hpp::fcl::BenchTimer::stopped
int stopped
stop flag
Definition: utility.h:98
hpp::fcl::defaultCollisionFunction
bool defaultCollisionFunction(CollisionObject *o1, CollisionObject *o2, void *data)
Provides a simple callback for the collision query in the BroadPhaseCollisionManager....
Definition: default_broadphase_callbacks.cpp:43
hpp::fcl::UnitY
const Vec3f UnitY
Definition: utility.cpp:88
hpp::fcl::UnitZ
const Vec3f UnitZ
Definition: utility.cpp:89
transform.h
hpp::fcl::TStruct::overall_time
double overall_time
Definition: utility.h:111
hpp::fcl::OcTree
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
Definition: octree.h:53
octomap
convex.h
hpp::fcl::DistanceRes::p2
Vec3f p2
Definition: utility.h:166
hpp::fcl::DistanceRes
Definition: utility.h:163
octree.h
hpp::fcl::generateRandomTransform
void generateRandomTransform(FCL_REAL extents[6], Transform3f &transform)
Generate one random transform whose translation is constrained by extents and rotation without constr...
Definition: utility.cpp:208
hpp::fcl::BenchTimer::getElapsedTimeInMicroSec
double getElapsedTimeInMicroSec()
get elapsed time in micro-second
Definition: utility.cpp:54
hpp::fcl::BenchTimer::start
void start()
start timer
Definition: utility.cpp:35
hpp::fcl::Quaternion3f
Eigen::Quaternion< FCL_REAL > Quaternion3f
Definition: transform.h:46
hpp::fcl::BenchTimer::endTimeInMicroSec
double endTimeInMicroSec
ending time in micro-second
Definition: utility.h:97


hpp-fcl
Author(s):
autogenerated on Fri Jan 26 2024 03:46:15