Go to the documentation of this file.
38 #ifndef TEST_HPP_FCL_UTILITY_H
39 #define TEST_HPP_FCL_UTILITY_H
47 #ifdef HPP_FCL_HAS_OCTOMAP
52 #define NOMINMAX // required to avoid compilation errors with Visual Studio
59 #define EIGEN_VECTOR_IS_APPROX(Va, Vb, precision) \
60 BOOST_CHECK_MESSAGE(((Va) - (Vb)).isZero(precision), \
61 "check " #Va ".isApprox(" #Vb \
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 \
75 #ifdef HPP_FCL_HAS_OCTOMAP
76 typedef hpp::fcl::shared_ptr<octomap::OcTree>
OcTreePtr_t;
100 LARGE_INTEGER frequency;
121 extern const Eigen::IOFormat
vfmt;
122 extern const Eigen::IOFormat
pyfmt;
130 std::vector<Triangle>& triangles);
133 std::vector<Triangle>& triangles);
135 #ifdef HPP_FCL_HAS_OCTOMAP
149 std::vector<Transform3f>& transforms,
157 std::vector<Transform3f>& transforms,
158 std::vector<Transform3f>& transforms2,
187 std::size_t
getNbRun(
const int& argc,
char const*
const* argv,
188 std::size_t defaultValue);
const Eigen::IOFormat pyfmt
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
void loadOBJFile(const char *filename, std::vector< Vec3f > &points, std::vector< Triangle > &triangles)
Load an obj mesh file.
HPP_FCL_DLLAPI Halfspace transform(const Halfspace &a, const Transform3f &tf)
const Eigen::IOFormat vfmt
shared_ptr< OcTree > OcTreePtr_t
double getElapsedTimeInMilliSec()
get elapsed time in milli-second
void generateEnvironmentsMesh(std::vector< CollisionObject * > &env, FCL_REAL env_scale, std::size_t n)
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
void generateEnvironments(std::vector< CollisionObject * > &env, FCL_REAL env_scale, std::size_t n)
Ellipsoid centered at point zero.
static std::ostream & operator<<(std::ostream &o, const Quaternion3f &q)
void stop()
stop the timer
std::string getNodeTypeName(NODE_TYPE node_type)
Quaternion3f makeQuat(FCL_REAL w, FCL_REAL x, FCL_REAL y, FCL_REAL z)
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...
Eigen::AngleAxis< FCL_REAL > AngleAxis
bool defaultDistanceFunction(CollisionObject *o1, CollisionObject *o2, void *data, FCL_REAL &dist)
Collision data for use with the DefaultContinuousCollisionFunction. It stores the collision request a...
the object for collision or distance computation, contains the geometry and the transform information
double getElapsedTime()
get elapsed time in milli-second
std::size_t getNbRun(const int &argc, char const *const *argv, std::size_t defaultValue)
Get the argument –nb-run from argv.
double getElapsedTimeInSec()
void generateRandomTransforms(FCL_REAL extents[6], std::vector< Transform3f > &transforms, std::size_t n)
Generate n random transforms whose translations are constrained by extents.
double startTimeInMicroSec
starting time in micro-second
void saveOBJFile(const char *filename, std::vector< Vec3f > &points, std::vector< Triangle > &triangles)
std::vector< double > records
bool defaultCollisionFunction(CollisionObject *o1, CollisionObject *o2, void *data)
Provides a simple callback for the collision query in the BroadPhaseCollisionManager....
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
void generateRandomTransform(FCL_REAL extents[6], Transform3f &transform)
Generate one random transform whose translation is constrained by extents and rotation without constr...
double getElapsedTimeInMicroSec()
get elapsed time in micro-second
Eigen::Quaternion< FCL_REAL > Quaternion3f
double endTimeInMicroSec
ending time in micro-second
hpp-fcl
Author(s):
autogenerated on Fri Aug 2 2024 02:45:15