38 #ifndef TEST_FCL_UTILITY_H 39 #define TEST_FCL_UTILITY_H 65 #define NOMINMAX // required to avoid compilation errors with Visual Studio 2010 95 LARGE_INTEGER frequency;
113 records.push_back(t);
119 template <
typename S>
120 void loadOBJFile(
const char* filename, std::vector<
Vector3<S>>& points, std::vector<Triangle>& triangles);
122 template <
typename S>
123 void saveOBJFile(
const char* filename, std::vector<
Vector3<S>>& points, std::vector<Triangle>& triangles);
125 template <
typename S>
128 template <
typename S>
133 template <
typename S>
137 template <
typename S>
141 template <
typename S>
145 template <
typename S>
147 const std::vector<
Vector3<S>>& vertices1,
const std::vector<Triangle>& triangles1,
148 const std::vector<
Vector3<S>>& vertices2,
const std::vector<Triangle>& triangles2);
151 template <
typename S>
155 template <
typename S>
159 template <
typename S>
174 template <
typename S>
175 void generateBoxesFromOctomap(std::vector<
CollisionObject<S>*>& env, OcTree<S>& tree);
178 template <
typename S>
179 void generateBoxesFromOctomapMesh(std::vector<
CollisionObject<S>*>& env, OcTree<S>& tree);
193 template <
typename S>
197 FILE* file = fopen(filename,
"rb");
200 std::cerr <<
"file not exist" << std::endl;
204 bool has_normal =
false;
205 bool has_texture =
false;
206 char line_buffer[2000];
207 while(fgets(line_buffer, 2000, file))
209 char* first_token = strtok(line_buffer,
"\r\n\t ");
210 if(!first_token || first_token[0] ==
'#' || first_token[0] == 0)
213 switch(first_token[0])
217 if(first_token[1] ==
'n')
219 strtok(
nullptr,
"\t ");
220 strtok(
nullptr,
"\t ");
221 strtok(
nullptr,
"\t ");
224 else if(first_token[1] ==
't')
226 strtok(
nullptr,
"\t ");
227 strtok(
nullptr,
"\t ");
232 S x = (S)atof(strtok(
nullptr,
"\t "));
233 S y = (S)atof(strtok(
nullptr,
"\t "));
234 S z = (S)atof(strtok(
nullptr,
"\t "));
235 points.emplace_back(x, y, z);
244 while((data[n] = strtok(
nullptr,
"\t \r\n")) !=
nullptr)
250 for(
int t = 0; t < (n - 2); ++t)
252 if((!has_texture) && (!has_normal))
254 tri[0] = atoi(data[0]) - 1;
255 tri[1] = atoi(data[1]) - 1;
256 tri[2] = atoi(data[2]) - 1;
261 for(
int i = 0; i < 3; i++)
269 tri[i] = atoi(v1) - 1;
272 triangles.push_back(tri);
280 template <
typename S>
283 std::ofstream os(filename);
286 std::cerr <<
"file not exist" << std::endl;
290 for(std::size_t i = 0; i < points.size(); ++i)
292 os <<
"v " << points[i][0] <<
" " << points[i][1] <<
" " << points[i][2] << std::endl;
295 for(std::size_t i = 0; i < triangles.size(); ++i)
297 os <<
"f " << triangles[i][0] + 1 <<
" " << triangles[i][1] + 1 <<
" " << triangles[i][2] + 1 << std::endl;
304 template <
typename S>
307 S t = rand() / ((S)RAND_MAX + 1);
308 return (t * (rmax - rmin) + rmin);
312 template <
typename S>
315 auto c1 = std::cos(a);
316 auto c2 = std::cos(b);
317 auto c3 = std::cos(c);
318 auto s1 = std::sin(a);
319 auto s2 = std::sin(b);
320 auto s3 = std::sin(c);
322 R << c1 * c2, - c2 * s1, s2,
323 c3 * s1 + c1 * s2 * s3, c1 * c3 - s1 * s2 * s3, - c2 * s3,
324 s1 * s3 - c1 * c3 * s2, c3 * s1 * s2 + c1 * s3, c2 * c3;
328 template <
typename S>
343 transform.linear() = R;
344 transform.translation() = T;
348 template <
typename S>
351 transforms.resize(n);
352 for(std::size_t i = 0; i < n; ++i)
367 transforms[i].setIdentity();
368 transforms[i].linear() = R;
369 transforms[i].translation() = T;
375 template <
typename S>
378 transforms.resize(n);
379 transforms2.resize(n);
380 for(std::size_t i = 0; i < n; ++i)
395 transforms[i].setIdentity();
396 transforms[i].linear() = R;
397 transforms[i].translation() = T;
400 auto deltax =
rand_interval(-delta_trans[0], delta_trans[0]);
401 auto deltay =
rand_interval(-delta_trans[1], delta_trans[1]);
402 auto deltaz =
rand_interval(-delta_trans[2], delta_trans[2]);
411 Vector3<S> T(x + deltax, y + deltay, z + deltaz);
412 transforms2[i].setIdentity();
413 transforms2[i].linear() = R;
414 transforms2[i].translation() = T;
420 template <
typename S>
422 const std::vector<
Vector3<S>>& vertices1,
const std::vector<Triangle>& triangles1,
423 const std::vector<
Vector3<S>>& vertices2,
const std::vector<Triangle>& triangles2)
430 transforms.resize(n);
431 transforms2.resize(n);
433 for(std::size_t i = 0; i < n;)
450 tf.translation() = T;
452 std::vector<std::pair<int, int> > results;
456 auto deltax =
rand_interval(-delta_trans[0], delta_trans[0]);
457 auto deltay =
rand_interval(-delta_trans[1], delta_trans[1]);
458 auto deltaz =
rand_interval(-delta_trans[2], delta_trans[2]);
466 Vector3<S> T2(x + deltax, y + deltay, z + deltaz);
467 transforms2[i].linear() = R2;
468 transforms2[i].translation() = T2;
475 template <
typename S>
478 S extents[] = {-env_scale, env_scale, -env_scale, env_scale, -env_scale, env_scale};
482 for(std::size_t i = 0; i < n; ++i)
489 for(std::size_t i = 0; i < n; ++i)
496 for(std::size_t i = 0; i < n; ++i)
504 template <
typename S>
507 S extents[] = {-env_scale, env_scale, -env_scale, env_scale, -env_scale, env_scale};
512 for(std::size_t i = 0; i < n; ++i)
521 for(std::size_t i = 0; i < n; ++i)
530 for(std::size_t i = 0; i < n; ++i)
541 template <
typename S>
542 void generateBoxesFromOctomap(std::vector<
CollisionObject<S>*>& boxes, OcTree<S>& tree)
544 std::vector<std::array<S, 6> > boxes_ = tree.toBoxes();
546 for(std::size_t i = 0; i < boxes_.size(); ++i)
551 S size = boxes_[i][3];
552 S cost = boxes_[i][4];
553 S threshold = boxes_[i][5];
559 boxes.push_back(obj);
562 std::cout <<
"boxes size: " << boxes.size() << std::endl;
567 template <
typename S>
568 void generateBoxesFromOctomapMesh(std::vector<
CollisionObject<S>*>& boxes, OcTree<S>& tree)
570 std::vector<std::array<S, 6> > boxes_ = tree.toBoxes();
572 for(std::size_t i = 0; i < boxes_.size(); ++i)
577 S size = boxes_[i][3];
578 S cost = boxes_[i][4];
579 S threshold = boxes_[i][5];
581 Box<S> box(size, size, size);
587 boxes.push_back(obj);
590 std::cout <<
"boxes size: " << boxes.size() << std::endl;
599 for(
int x = -20; x < 20; x++)
601 for(
int y = -20; y < 20; y++)
603 for(
int z = -20; z < 20; z++)
611 for(
int x = -30; x < 30; x++)
613 for(
int y = -30; y < 30; y++)
615 for(
int z = -30; z < 30; z++)
625 #endif // FCL_HAVE_OCTOMAP void generateEnvironmentsMesh(std::vector< CollisionObject< S > *> &env, S env_scale, std::size_t n)
Generate environment with 3 * n objects, but all in meshes.
double endTimeInMicroSec
ending time in micro-second
std::array< S, 6 > & extents()
double getElapsedTimeInMicroSec()
get elapsed time in micro-second
double getElapsedTime()
get elapsed time in milli-second
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, ellipsoid, capsule, cone, cylinder, convex, plane, halfspace, triangle), and octree
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
virtual OcTreeNode * updateNode(const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
std::vector< double > records
void generateRandomTransform(S extents[6], Transform3< S > &transform)
Generate one random transform whose translation is constrained by extents and rotation without constr...
void eulerToMatrix(S a, S b, S c, Matrix3< S > &R)
void stop()
stop the timer
S rand_interval(S rmin, S rmax)
Eigen::Matrix< S, 3, 3 > Matrix3
void saveOBJFile(const char *filename, std::vector< Vector3< S >> &points, std::vector< Triangle > &triangles)
Eigen::Matrix< S, 3, 1 > Vector3
double startTimeInMicroSec
starting time in micro-second
The geometry for the object for collision or distance computation.
Triangle with 3 indices for points.
double getElapsedTimeInMilliSec()
get elapsed time in milli-second
std::string getGJKSolverName(GJKSolverType solver_type)
void generateEnvironments(std::vector< CollisionObject< S > *> &env, S env_scale, std::size_t n)
Generate environment with 3 * n objects: n boxes, n spheres and n cylinders.
double getElapsedTimeInSec()
get elapsed time in second (same as getElapsedTime)
Structure for minimum distance between two meshes and the corresponding nearest point pair...
std::string getNodeTypeName(NODE_TYPE node_type)
Center at zero point, axis aligned box.
S_ threshold_occupied
threshold for occupied ( >= is occupied)
static constexpr S pi()
The mathematical constant pi.
int generateBVHModel(BVHModel< BV > &model, const Box< typename BV::S > &shape, const Transform3< typename BV::S > &pose, FinalizeModel finalize_model)
Generate BVH model from box.
void generateRandomTransforms_ccd(S extents[6], aligned_vector< Transform3< S >> &transforms, aligned_vector< Transform3< S >> &transforms2, S delta_trans[3], S delta_rot, std::size_t n, const std::vector< Vector3< S >> &vertices1, const std::vector< Triangle > &triangles1, const std::vector< Vector3< S >> &vertices2, const std::vector< Triangle > &triangles2)
Generate n random tranforms and transform2 with addtional random translation/rotation. The transforms and transform2 are used as initial and goal configurations for the first mesh. The second mesh is in I. This is used for continuous collision detection checking.
Eigen::Translation< S, 3 > Translation3
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
the object for collision or distance computation, contains the geometry and the transform information...
S_ cost_density
collision cost for unit volume
void generateRandomTransforms(S extents[6], aligned_vector< Transform3< S >> &transforms, std::size_t n)
Generate n random transforms whose translations are constrained by extents.
CollisionObject< S > * obj
object
Center at zero point sphere.
void loadOBJFile(const char *filename, std::vector< Vector3< S >> &points, std::vector< Triangle > &triangles)
Load an obj mesh file.
GJKSolverType
Type of narrow phase GJK solver.
std::vector< _Tp, Eigen::aligned_allocator< _Tp > > aligned_vector