#include <array>
#include <iostream>
#include <limits>
#include <gtest/gtest.h>
#include "fcl/common/unused.h"
#include "fcl/math/motion/translation_motion.h"
#include "fcl/geometry/shape/cone.h"
#include "fcl/geometry/shape/capsule.h"
#include "fcl/geometry/shape/ellipsoid.h"
#include "fcl/geometry/shape/halfspace.h"
#include "fcl/geometry/shape/plane.h"
#include "fcl/narrowphase/detail/gjk_solver_indep.h"
#include "fcl/narrowphase/detail/gjk_solver_libccd.h"
#include "fcl/narrowphase/collision.h"
#include "test_fcl_utility.h"
Go to the source code of this file.
Functions | |
template<typename Shape1 , typename Shape2 > | |
bool | checkContactPointds (const Shape1 &s1, const Transform3< typename Shape1::S > &tf1, const Shape2 &s2, const Transform3< typename Shape1::S > &tf2, GJKSolverType solver_type, const ContactPoint< typename Shape1::S > &expected, const ContactPoint< typename Shape1::S > &actual, bool check_position=false, bool check_depth=false, bool check_normal=false, bool check_opposite_normal=false, typename Shape1::S tol=1e-9) |
template<typename S > | |
bool | compareContactPointds1 (const Vector3< S > &c1, const Vector3< S > &c2) |
template<typename S > | |
bool | compareContactPointds2 (const ContactPoint< S > &cp1, const ContactPoint< S > &cp2) |
template<typename S > | |
std::array< S, 6 > & | extents () |
template<typename S > | |
void | getContactPointdsFromResult (std::vector< ContactPoint< S >> &contacts, const CollisionResult< S > &result) |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, gjkcache) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, reversibleShapeDistance_allshapes) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, reversibleShapeIntersection_allshapes) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeDistance_boxbox) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeDistance_boxsphere) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeDistance_conecone) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeDistance_conecylinder) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeDistance_cylindercylinder) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeDistance_ellipsoidellipsoid) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeDistance_spheresphere) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeDistanceGJK_boxbox) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeDistanceGJK_boxsphere) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeDistanceGJK_conecone) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeDistanceGJK_cylindercylinder) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeDistanceGJK_ellipsoidellipsoid) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeDistanceGJK_spheresphere) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_boxbox) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_conecone) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_cylindercone) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_cylindercylinder) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_ellipsoidellipsoid) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_halfspacebox) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_halfspacecapsule) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_halfspacecone) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_halfspacecylinder) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_halfspaceellipsoid) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_halfspacesphere) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_halfspacetriangle) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_planebox) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_planecapsule) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_planecone) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_planecylinder) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_planeellipsoid) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_planesphere) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_planetriangle) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_spherebox) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_spherecapsule) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_spheresphere) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersection_spheretriangle) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersectionGJK_boxbox) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersectionGJK_conecone) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersectionGJK_cylindercone) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersectionGJK_cylindercylinder) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersectionGJK_ellipsoidellipsoid) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersectionGJK_halfspacetriangle) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersectionGJK_planetriangle) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersectionGJK_spherebox) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersectionGJK_spherecapsule) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersectionGJK_spheresphere) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, shapeIntersectionGJK_spheretriangle) | |
GTEST_TEST (FCL_GEOMETRIC_SHAPES, sphere_shape) | |
template<typename Shape1 , typename Shape2 > | |
bool | inspectContactPointds (const Shape1 &s1, const Transform3< typename Shape1::S > &tf1, const Shape2 &s2, const Transform3< typename Shape1::S > &tf2, GJKSolverType solver_type, const std::vector< ContactPoint< typename Shape1::S >> &expected_contacts, const std::vector< ContactPoint< typename Shape1::S >> &actual_contacts, bool check_position=false, bool check_depth=false, bool check_normal=false, bool check_opposite_normal=false, typename Shape1::S tol=1e-9) |
int | main (int argc, char *argv[]) |
template<typename Shape1 , typename Shape2 > | |
void | printComparisonError (const std::string &comparison_type, const Shape1 &s1, const Transform3< typename Shape1::S > &tf1, const Shape2 &s2, const Transform3< typename Shape1::S > &tf2, GJKSolverType solver_type, const Vector3< typename Shape1::S > &expected_contact_or_normal, const Vector3< typename Shape1::S > &actual_contact_or_normal, bool check_opposite_normal, typename Shape1::S tol) |
template<typename Shape1 , typename Shape2 > | |
void | printComparisonError (const std::string &comparison_type, const Shape1 &s1, const Transform3< typename Shape1::S > &tf1, const Shape2 &s2, const Transform3< typename Shape1::S > &tf2, GJKSolverType solver_type, typename Shape1::S expected_depth, typename Shape1::S actual_depth, typename Shape1::S tol) |
template<typename S > | |
detail::GJKSolver_libccd< S > & | solver1 () |
template<typename S > | |
detail::GJKSolver_indep< S > & | solver2 () |
template<typename S > | |
void | test_gjkcache () |
template<typename S > | |
void | test_reversibleShapeDistance_allshapes () |
template<typename S > | |
void | test_reversibleShapeIntersection_allshapes () |
template<typename S > | |
void | test_shapeDistance_boxbox () |
template<typename S > | |
void | test_shapeDistance_boxsphere () |
template<typename S > | |
void | test_shapeDistance_conecone () |
template<typename S > | |
void | test_shapeDistance_conecylinder () |
template<typename S > | |
void | test_shapeDistance_cylindercylinder () |
template<typename S > | |
void | test_shapeDistance_ellipsoidellipsoid () |
template<typename S > | |
void | test_shapeDistance_spheresphere () |
template<typename S > | |
void | test_shapeDistanceGJK_boxbox () |
template<typename S > | |
void | test_shapeDistanceGJK_boxsphere () |
template<typename S > | |
void | test_shapeDistanceGJK_conecone () |
template<typename S > | |
void | test_shapeDistanceGJK_cylindercylinder () |
template<typename S > | |
void | test_shapeDistanceGJK_ellipsoidellipsoid () |
template<typename S > | |
void | test_shapeDistanceGJK_spheresphere () |
template<typename S > | |
void | test_shapeIntersection_boxbox () |
template<typename S > | |
void | test_shapeIntersection_conecone () |
template<typename S > | |
void | test_shapeIntersection_cylindercone () |
template<typename S > | |
void | test_shapeIntersection_cylindercylinder () |
template<typename S > | |
void | test_shapeIntersection_ellipsoidellipsoid () |
template<typename S > | |
void | test_shapeIntersection_halfspacebox () |
template<typename S > | |
void | test_shapeIntersection_halfspacecapsule () |
template<typename S > | |
void | test_shapeIntersection_halfspacecone () |
template<typename S > | |
void | test_shapeIntersection_halfspacecylinder () |
template<typename S > | |
void | test_shapeIntersection_halfspaceellipsoid () |
template<typename S > | |
void | test_shapeIntersection_halfspacesphere () |
template<typename S > | |
void | test_shapeIntersection_halfspacetriangle () |
template<typename S > | |
void | test_shapeIntersection_planebox () |
template<typename S > | |
void | test_shapeIntersection_planecapsule () |
template<typename S > | |
void | test_shapeIntersection_planecone () |
template<typename S > | |
void | test_shapeIntersection_planecylinder () |
template<typename S > | |
void | test_shapeIntersection_planeellipsoid () |
template<typename S > | |
void | test_shapeIntersection_planesphere () |
template<typename S > | |
void | test_shapeIntersection_planetriangle () |
template<typename S > | |
void | test_shapeIntersection_spherebox () |
template<typename S > | |
void | test_shapeIntersection_spherecapsule () |
template<typename S > | |
void | test_shapeIntersection_spheresphere () |
template<typename S > | |
void | test_shapeIntersection_spheretriangle () |
template<typename S > | |
void | test_shapeIntersectionGJK_boxbox () |
template<typename S > | |
void | test_shapeIntersectionGJK_conecone () |
template<typename S > | |
void | test_shapeIntersectionGJK_cylindercone () |
template<typename S > | |
void | test_shapeIntersectionGJK_cylindercylinder () |
template<typename S > | |
void | test_shapeIntersectionGJK_ellipsoidellipsoid () |
template<typename S > | |
void | test_shapeIntersectionGJK_halfspacetriangle () |
template<typename S > | |
void | test_shapeIntersectionGJK_planetriangle () |
template<typename S > | |
void | test_shapeIntersectionGJK_spherebox () |
template<typename S > | |
void | test_shapeIntersectionGJK_spherecapsule () |
template<typename S > | |
void | test_shapeIntersectionGJK_spheresphere () |
template<typename S > | |
void | test_shapeIntersectionGJK_spheretriangle () |
template<typename S > | |
void | test_sphere_shape () |
template<typename Derived > | |
void | testBoxBoxContactPointds (const Eigen::MatrixBase< Derived > &R) |
template<typename Shape1 , typename Shape2 > | |
void | testReversibleShapeDistance (const Shape1 &s1, const Shape2 &s2, typename Shape2::S distance) |
template<typename Shape1 , typename Shape2 > | |
void | testReversibleShapeIntersection (const Shape1 &s1, const Shape2 &s2, typename Shape2::S distance) |
template<typename Shape1 , typename Shape2 > | |
void | testShapeIntersection (const Shape1 &s1, const Transform3< typename Shape1::S > &tf1, const Shape2 &s2, const Transform3< typename Shape1::S > &tf2, GJKSolverType solver_type, bool expected_res, const std::vector< ContactPoint< typename Shape1::S >> &expected_contacts=std::vector< ContactPoint< typename Shape1::S >>(), bool check_position=true, bool check_depth=true, bool check_normal=true, bool check_opposite_normal=false, typename Shape1::S tol=1e-9) |
template<typename S > | |
S | tolerance () |
template<> | |
float | tolerance () |
bool checkContactPointds | ( | const Shape1 & | s1, |
const Transform3< typename Shape1::S > & | tf1, | ||
const Shape2 & | s2, | ||
const Transform3< typename Shape1::S > & | tf2, | ||
GJKSolverType | solver_type, | ||
const ContactPoint< typename Shape1::S > & | expected, | ||
const ContactPoint< typename Shape1::S > & | actual, | ||
bool | check_position = false , |
||
bool | check_depth = false , |
||
bool | check_normal = false , |
||
bool | check_opposite_normal = false , |
||
typename Shape1::S | tol = 1e-9 |
||
) |
Definition at line 232 of file test_fcl_geometric_shapes.cpp.
bool compareContactPointds1 | ( | const Vector3< S > & | c1, |
const Vector3< S > & | c2 | ||
) |
Definition at line 653 of file test_fcl_geometric_shapes.cpp.
bool compareContactPointds2 | ( | const ContactPoint< S > & | cp1, |
const ContactPoint< S > & | cp2 | ||
) |
Definition at line 659 of file test_fcl_geometric_shapes.cpp.
std::array<S, 6>& extents | ( | ) |
Definition at line 63 of file test_fcl_geometric_shapes.cpp.
void getContactPointdsFromResult | ( | std::vector< ContactPoint< S >> & | contacts, |
const CollisionResult< S > & | result | ||
) |
Definition at line 412 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
gjkcache | |||
) |
Definition at line 171 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
reversibleShapeDistance_allshapes | |||
) |
Definition at line 5349 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
reversibleShapeIntersection_allshapes | |||
) |
Definition at line 5244 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeDistance_boxbox | |||
) |
Definition at line 3802 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeDistance_boxsphere | |||
) |
Definition at line 3845 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeDistance_conecone | |||
) |
Definition at line 3931 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeDistance_conecylinder | |||
) |
Definition at line 3974 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeDistance_cylindercylinder | |||
) |
Definition at line 3888 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeDistance_ellipsoidellipsoid | |||
) |
Definition at line 4043 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeDistance_spheresphere | |||
) |
Definition at line 3729 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeDistanceGJK_boxbox | |||
) |
Definition at line 4939 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeDistanceGJK_boxsphere | |||
) |
Definition at line 4982 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeDistanceGJK_conecone | |||
) |
Definition at line 5068 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeDistanceGJK_cylindercylinder | |||
) |
Definition at line 5025 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeDistanceGJK_ellipsoidellipsoid | |||
) |
Definition at line 5135 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeDistanceGJK_spheresphere | |||
) |
Definition at line 4896 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_boxbox | |||
) |
Definition at line 828 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_conecone | |||
) |
Definition at line 1093 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_cylindercone | |||
) |
Definition at line 1166 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_cylindercylinder | |||
) |
Definition at line 1028 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_ellipsoidellipsoid | |||
) |
Definition at line 1242 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_halfspacebox | |||
) |
Definition at line 1666 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_halfspacecapsule | |||
) |
Definition at line 2473 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_halfspacecone | |||
) |
Definition at line 3413 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_halfspacecylinder | |||
) |
Definition at line 2943 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_halfspaceellipsoid | |||
) |
Definition at line 2003 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_halfspacesphere | |||
) |
Definition at line 1483 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_halfspacetriangle | |||
) |
Definition at line 1342 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_planebox | |||
) |
Definition at line 1756 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_planecapsule | |||
) |
Definition at line 2696 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_planecone | |||
) |
Definition at line 3636 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_planecylinder | |||
) |
Definition at line 3166 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_planeellipsoid | |||
) |
Definition at line 2226 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_planesphere | |||
) |
Definition at line 1568 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_planetriangle | |||
) |
Definition at line 1390 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_spherebox | |||
) |
Definition at line 899 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_spherecapsule | |||
) |
Definition at line 965 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_spheresphere | |||
) |
Definition at line 646 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersection_spheretriangle | |||
) |
Definition at line 1288 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersectionGJK_boxbox | |||
) |
Definition at line 4250 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersectionGJK_conecone | |||
) |
Definition at line 4508 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersectionGJK_cylindercone | |||
) |
Definition at line 4583 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersectionGJK_cylindercylinder | |||
) |
Definition at line 4441 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersectionGJK_ellipsoidellipsoid | |||
) |
Definition at line 4661 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersectionGJK_halfspacetriangle | |||
) |
Definition at line 4756 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersectionGJK_planetriangle | |||
) |
Definition at line 4804 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersectionGJK_spherebox | |||
) |
Definition at line 4330 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersectionGJK_spherecapsule | |||
) |
Definition at line 4385 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersectionGJK_spheresphere | |||
) |
Definition at line 4176 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
shapeIntersectionGJK_spheretriangle | |||
) |
Definition at line 4708 of file test_fcl_geometric_shapes.cpp.
GTEST_TEST | ( | FCL_GEOMETRIC_SHAPES | , |
sphere_shape | |||
) |
Definition at line 104 of file test_fcl_geometric_shapes.cpp.
bool inspectContactPointds | ( | const Shape1 & | s1, |
const Transform3< typename Shape1::S > & | tf1, | ||
const Shape2 & | s2, | ||
const Transform3< typename Shape1::S > & | tf2, | ||
GJKSolverType | solver_type, | ||
const std::vector< ContactPoint< typename Shape1::S >> & | expected_contacts, | ||
const std::vector< ContactPoint< typename Shape1::S >> & | actual_contacts, | ||
bool | check_position = false , |
||
bool | check_depth = false , |
||
bool | check_normal = false , |
||
bool | check_opposite_normal = false , |
||
typename Shape1::S | tol = 1e-9 |
||
) |
Definition at line 277 of file test_fcl_geometric_shapes.cpp.
int main | ( | int | argc, |
char * | argv[] | ||
) |
Definition at line 5356 of file test_fcl_geometric_shapes.cpp.
void printComparisonError | ( | const std::string & | comparison_type, |
const Shape1 & | s1, | ||
const Transform3< typename Shape1::S > & | tf1, | ||
const Shape2 & | s2, | ||
const Transform3< typename Shape1::S > & | tf2, | ||
GJKSolverType | solver_type, | ||
const Vector3< typename Shape1::S > & | expected_contact_or_normal, | ||
const Vector3< typename Shape1::S > & | actual_contact_or_normal, | ||
bool | check_opposite_normal, | ||
typename Shape1::S | tol | ||
) |
Definition at line 178 of file test_fcl_geometric_shapes.cpp.
void printComparisonError | ( | const std::string & | comparison_type, |
const Shape1 & | s1, | ||
const Transform3< typename Shape1::S > & | tf1, | ||
const Shape2 & | s2, | ||
const Transform3< typename Shape1::S > & | tf2, | ||
GJKSolverType | solver_type, | ||
typename Shape1::S | expected_depth, | ||
typename Shape1::S | actual_depth, | ||
typename Shape1::S | tol | ||
) |
Definition at line 208 of file test_fcl_geometric_shapes.cpp.
detail::GJKSolver_libccd<S>& solver1 | ( | ) |
Definition at line 70 of file test_fcl_geometric_shapes.cpp.
detail::GJKSolver_indep<S>& solver2 | ( | ) |
Definition at line 77 of file test_fcl_geometric_shapes.cpp.
void test_gjkcache | ( | ) |
test exploiting spatial coherence
test without exploiting spatial coherence
Definition at line 111 of file test_fcl_geometric_shapes.cpp.
void test_reversibleShapeDistance_allshapes | ( | ) |
Definition at line 5290 of file test_fcl_geometric_shapes.cpp.
void test_reversibleShapeIntersection_allshapes | ( | ) |
Definition at line 5185 of file test_fcl_geometric_shapes.cpp.
void test_shapeDistance_boxbox | ( | ) |
Definition at line 3736 of file test_fcl_geometric_shapes.cpp.
void test_shapeDistance_boxsphere | ( | ) |
Definition at line 3809 of file test_fcl_geometric_shapes.cpp.
void test_shapeDistance_conecone | ( | ) |
Definition at line 3895 of file test_fcl_geometric_shapes.cpp.
void test_shapeDistance_conecylinder | ( | ) |
Definition at line 3938 of file test_fcl_geometric_shapes.cpp.
void test_shapeDistance_cylindercylinder | ( | ) |
Definition at line 3852 of file test_fcl_geometric_shapes.cpp.
void test_shapeDistance_ellipsoidellipsoid | ( | ) |
Definition at line 3981 of file test_fcl_geometric_shapes.cpp.
void test_shapeDistance_spheresphere | ( | ) |
Definition at line 3667 of file test_fcl_geometric_shapes.cpp.
void test_shapeDistanceGJK_boxbox | ( | ) |
Definition at line 4903 of file test_fcl_geometric_shapes.cpp.
void test_shapeDistanceGJK_boxsphere | ( | ) |
Definition at line 4946 of file test_fcl_geometric_shapes.cpp.
void test_shapeDistanceGJK_conecone | ( | ) |
Definition at line 5032 of file test_fcl_geometric_shapes.cpp.
void test_shapeDistanceGJK_cylindercylinder | ( | ) |
Definition at line 4989 of file test_fcl_geometric_shapes.cpp.
void test_shapeDistanceGJK_ellipsoidellipsoid | ( | ) |
Definition at line 5075 of file test_fcl_geometric_shapes.cpp.
void test_shapeDistanceGJK_spheresphere | ( | ) |
Definition at line 4835 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_boxbox | ( | ) |
Definition at line 750 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_conecone | ( | ) |
Definition at line 1035 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_cylindercone | ( | ) |
Definition at line 1100 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_cylindercylinder | ( | ) |
Definition at line 972 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_ellipsoidellipsoid | ( | ) |
Definition at line 1173 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_halfspacebox | ( | ) |
Definition at line 1575 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_halfspacecapsule | ( | ) |
Definition at line 2233 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_halfspacecone | ( | ) |
Definition at line 3173 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_halfspacecylinder | ( | ) |
Definition at line 2703 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_halfspaceellipsoid | ( | ) |
Definition at line 1763 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_halfspacesphere | ( | ) |
Definition at line 1397 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_halfspacetriangle | ( | ) |
Definition at line 1295 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_planebox | ( | ) |
Definition at line 1673 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_planecapsule | ( | ) |
Definition at line 2480 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_planecone | ( | ) |
Definition at line 3420 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_planecylinder | ( | ) |
Definition at line 2950 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_planeellipsoid | ( | ) |
Definition at line 2010 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_planesphere | ( | ) |
Definition at line 1490 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_planetriangle | ( | ) |
Definition at line 1349 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_spherebox | ( | ) |
Definition at line 835 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_spherecapsule | ( | ) |
Definition at line 906 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_spheresphere | ( | ) |
Definition at line 544 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersection_spheretriangle | ( | ) |
Definition at line 1249 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersectionGJK_boxbox | ( | ) |
Definition at line 4183 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersectionGJK_conecone | ( | ) |
Definition at line 4448 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersectionGJK_cylindercone | ( | ) |
Definition at line 4515 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersectionGJK_cylindercylinder | ( | ) |
Definition at line 4392 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersectionGJK_ellipsoidellipsoid | ( | ) |
Definition at line 4590 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersectionGJK_halfspacetriangle | ( | ) |
Definition at line 4715 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersectionGJK_planetriangle | ( | ) |
Definition at line 4763 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersectionGJK_spherebox | ( | ) |
Definition at line 4257 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersectionGJK_spherecapsule | ( | ) |
Definition at line 4337 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersectionGJK_spheresphere | ( | ) |
Definition at line 4074 of file test_fcl_geometric_shapes.cpp.
void test_shapeIntersectionGJK_spheretriangle | ( | ) |
Definition at line 4668 of file test_fcl_geometric_shapes.cpp.
void test_sphere_shape | ( | ) |
Definition at line 93 of file test_fcl_geometric_shapes.cpp.
void testBoxBoxContactPointds | ( | const Eigen::MatrixBase< Derived > & | R | ) |
Definition at line 689 of file test_fcl_geometric_shapes.cpp.
void testReversibleShapeDistance | ( | const Shape1 & | s1, |
const Shape2 & | s2, | ||
typename Shape2::S | distance | ||
) |
Definition at line 5251 of file test_fcl_geometric_shapes.cpp.
void testReversibleShapeIntersection | ( | const Shape1 & | s1, |
const Shape2 & | s2, | ||
typename Shape2::S | distance | ||
) |
Definition at line 5142 of file test_fcl_geometric_shapes.cpp.
void testShapeIntersection | ( | const Shape1 & | s1, |
const Transform3< typename Shape1::S > & | tf1, | ||
const Shape2 & | s2, | ||
const Transform3< typename Shape1::S > & | tf2, | ||
GJKSolverType | solver_type, | ||
bool | expected_res, | ||
const std::vector< ContactPoint< typename Shape1::S >> & | expected_contacts = std::vector<ContactPoint<typename Shape1::S>>() , |
||
bool | check_position = true , |
||
bool | check_depth = true , |
||
bool | check_normal = true , |
||
bool | check_opposite_normal = false , |
||
typename Shape1::S | tol = 1e-9 |
||
) |
Definition at line 428 of file test_fcl_geometric_shapes.cpp.
S tolerance | ( | ) |
Definition at line 87 of file test_fcl_geometric_shapes.cpp.
double tolerance | ( | ) |
Definition at line 87 of file test_fcl_geometric_shapes.cpp.