#include <boost/test/unit_test.hpp>
#include "fcl/broadphase/broadphase.h"
#include "fcl/shape/geometric_shape_to_BVH_model.h"
#include "fcl/math/transform.h"
#include "test_fcl_utility.h"
#include <boost/math/constants/constants.hpp>
#include <iostream>
#include <iomanip>
Go to the source code of this file.
Classes | |
struct | TStruct |
Defines | |
#define | BOOST_TEST_MODULE "FCL_BROADPHASE" |
Functions | |
BOOST_AUTO_TEST_CASE (test_core_bf_broad_phase_update_collision_binary) | |
check the update, only return collision or not | |
BOOST_AUTO_TEST_CASE (test_core_bf_broad_phase_update_collision) | |
check the update, return 10 contacts | |
BOOST_AUTO_TEST_CASE (test_core_bf_broad_phase_update_collision_exhaustive) | |
check the update, exhaustive | |
BOOST_AUTO_TEST_CASE (test_core_bf_broad_phase_distance) | |
check broad phase distance | |
BOOST_AUTO_TEST_CASE (test_core_bf_broad_phase_self_distance) | |
check broad phase self distance | |
BOOST_AUTO_TEST_CASE (test_core_bf_broad_phase_collision_binary) | |
check broad phase collision and self collision, only return collision or not | |
BOOST_AUTO_TEST_CASE (test_core_bf_broad_phase_collision) | |
check broad phase collision and self collision, return 10 contacts | |
BOOST_AUTO_TEST_CASE (test_core_mesh_bf_broad_phase_update_collision_mesh_binary) | |
check broad phase update, in mesh, only return collision or not | |
BOOST_AUTO_TEST_CASE (test_core_mesh_bf_broad_phase_update_collision_mesh) | |
check broad phase update, in mesh, return 10 contacts | |
BOOST_AUTO_TEST_CASE (test_core_mesh_bf_broad_phase_update_collision_mesh_exhaustive) | |
check broad phase update, in mesh, exhaustive | |
BOOST_AUTO_TEST_CASE (test_core_mesh_bf_broad_phase_distance_mesh) | |
check broad phase distance | |
BOOST_AUTO_TEST_CASE (test_core_mesh_bf_broad_phase_self_distance_mesh) | |
check broad phase self distance | |
BOOST_AUTO_TEST_CASE (test_core_mesh_bf_broad_phase_collision_mesh_binary) | |
check broad phase collision and self collision, return only collision or not, in mesh | |
BOOST_AUTO_TEST_CASE (test_core_mesh_bf_broad_phase_collision_mesh) | |
check broad phase collision and self collision, return 10 contacts, in mesh | |
BOOST_AUTO_TEST_CASE (test_core_mesh_bf_broad_phase_collision_mesh_exhaustive) | |
check broad phase collision and self collision, exhaustive, in mesh | |
void | broad_phase_collision_test (double env_scale, std::size_t env_size, std::size_t query_size, std::size_t num_max_contacts=1, bool exhaustive=false, bool use_mesh=false) |
test for broad phase collision and self collision | |
void | broad_phase_distance_test (double env_scale, std::size_t env_size, std::size_t query_size, bool use_mesh=false) |
test for broad phase distance | |
void | broad_phase_self_distance_test (double env_scale, std::size_t env_size, bool use_mesh=false) |
test for broad phase self distance | |
void | broad_phase_update_collision_test (double env_scale, std::size_t env_size, std::size_t query_size, std::size_t num_max_contacts=1, bool exhaustive=false, bool use_mesh=false) |
test for broad phase update | |
void | generateEnvironments (std::vector< CollisionObject * > &env, double env_scale, std::size_t n) |
Generate environment with 3 * n objects: n boxes, n spheres and n cylinders. | |
void | generateEnvironmentsMesh (std::vector< CollisionObject * > &env, double env_scale, std::size_t n) |
Generate environment with 3 * n objects, but all in meshes. | |
void | generateSelfDistanceEnvironments (std::vector< CollisionObject * > &env, double env_scale, std::size_t n) |
Generate environment with 3 * n objects for self distance, so we try to make sure none of them collide with each other. | |
void | generateSelfDistanceEnvironmentsMesh (std::vector< CollisionObject * > &env, double env_scale, std::size_t n) |
Generate environment with 3 * n objects for self distance, but all in meshes. | |
Variables | |
FCL_REAL | DELTA = 0.01 |
#define BOOST_TEST_MODULE "FCL_BROADPHASE" |
Definition at line 38 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_bf_broad_phase_update_collision_binary | ) |
check the update, only return collision or not
Definition at line 114 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_bf_broad_phase_update_collision | ) |
check the update, return 10 contacts
Definition at line 121 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_bf_broad_phase_update_collision_exhaustive | ) |
check the update, exhaustive
Definition at line 128 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_bf_broad_phase_distance | ) |
check broad phase distance
Definition at line 135 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_bf_broad_phase_self_distance | ) |
check broad phase self distance
Definition at line 144 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_bf_broad_phase_collision_binary | ) |
check broad phase collision and self collision, only return collision or not
Definition at line 152 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_bf_broad_phase_collision | ) |
check broad phase collision and self collision, return 10 contacts
Definition at line 161 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_mesh_bf_broad_phase_update_collision_mesh_binary | ) |
check broad phase update, in mesh, only return collision or not
Definition at line 168 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_mesh_bf_broad_phase_update_collision_mesh | ) |
check broad phase update, in mesh, return 10 contacts
Definition at line 175 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_mesh_bf_broad_phase_update_collision_mesh_exhaustive | ) |
check broad phase update, in mesh, exhaustive
Definition at line 182 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_mesh_bf_broad_phase_distance_mesh | ) |
check broad phase distance
Definition at line 189 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_mesh_bf_broad_phase_self_distance_mesh | ) |
check broad phase self distance
Definition at line 198 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_mesh_bf_broad_phase_collision_mesh_binary | ) |
check broad phase collision and self collision, return only collision or not, in mesh
Definition at line 206 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_mesh_bf_broad_phase_collision_mesh | ) |
check broad phase collision and self collision, return 10 contacts, in mesh
Definition at line 213 of file test_fcl_broadphase.cpp.
BOOST_AUTO_TEST_CASE | ( | test_core_mesh_bf_broad_phase_collision_mesh_exhaustive | ) |
check broad phase collision and self collision, exhaustive, in mesh
Definition at line 220 of file test_fcl_broadphase.cpp.
void broad_phase_collision_test | ( | double | env_scale, |
std::size_t | env_size, | ||
std::size_t | query_size, | ||
std::size_t | num_max_contacts = 1 , |
||
bool | exhaustive = false , |
||
bool | use_mesh = false |
||
) |
test for broad phase collision and self collision
Definition at line 419 of file test_fcl_broadphase.cpp.
void broad_phase_distance_test | ( | double | env_scale, |
std::size_t | env_size, | ||
std::size_t | query_size, | ||
bool | use_mesh = false |
||
) |
test for broad phase distance
Definition at line 726 of file test_fcl_broadphase.cpp.
void broad_phase_self_distance_test | ( | double | env_scale, |
std::size_t | env_size, | ||
bool | use_mesh = false |
||
) |
test for broad phase self distance
Definition at line 614 of file test_fcl_broadphase.cpp.
void broad_phase_update_collision_test | ( | double | env_scale, |
std::size_t | env_size, | ||
std::size_t | query_size, | ||
std::size_t | num_max_contacts = 1 , |
||
bool | exhaustive = false , |
||
bool | use_mesh = false |
||
) |
test for broad phase update
Definition at line 880 of file test_fcl_broadphase.cpp.
void generateEnvironments | ( | std::vector< CollisionObject * > & | env, |
double | env_scale, | ||
std::size_t | n | ||
) |
Generate environment with 3 * n objects: n boxes, n spheres and n cylinders.
Definition at line 226 of file test_fcl_broadphase.cpp.
void generateEnvironmentsMesh | ( | std::vector< CollisionObject * > & | env, |
double | env_scale, | ||
std::size_t | n | ||
) |
Generate environment with 3 * n objects, but all in meshes.
Definition at line 253 of file test_fcl_broadphase.cpp.
void generateSelfDistanceEnvironments | ( | std::vector< CollisionObject * > & | env, |
double | env_scale, | ||
std::size_t | n | ||
) |
Generate environment with 3 * n objects for self distance, so we try to make sure none of them collide with each other.
Definition at line 286 of file test_fcl_broadphase.cpp.
void generateSelfDistanceEnvironmentsMesh | ( | std::vector< CollisionObject * > & | env, |
double | env_scale, | ||
std::size_t | n | ||
) |
Generate environment with 3 * n objects for self distance, but all in meshes.
Definition at line 348 of file test_fcl_broadphase.cpp.
Definition at line 96 of file test_fcl_broadphase.cpp.