37 #include <gtest/gtest.h> 48 using CollisionGeometryPtr_t = std::shared_ptr<fcl::CollisionGeometry<S>>;
53 CollisionGeometryPtr_t boxGeometry (
new fcl::Box<S> (1., 2., 4.));
68 fcl::distance (&capsule, &box, distanceRequest, distanceResult);
84 distanceResult.
clear ();
85 fcl::distance (&capsule, &box, distanceRequest, distanceResult);
104 distanceResult.
clear ();
105 fcl::distance (&capsule, &box, distanceRequest, distanceResult);
129 int main(
int argc,
char* argv[])
131 ::testing::InitGoogleTest(&argc, argv);
132 return RUN_ALL_TESTS();
S min_distance
Minimum distance between two objects.
Eigen::Quaternion< S > Quaternion
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
GTEST_TEST(FCL_GEOMETRIC_SHAPES, distance_capsule_box_ccd)
S distance(const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P, Vector3< S > *Q)
Approximate distance between two kIOS bounding volumes.
#define EXPECT_NEAR(a, b, prec)
Eigen::Matrix< S, 3, 1 > Vector3
void setTransform(const Matrix3< S > &R, const Vector3< S > &T)
set object's transform
void test_distance_capsule_box(fcl::GJKSolverType solver_type, S solver_tolerance, S test_tolerance)
Center at zero point, axis aligned box.
void clear()
clear the result
Eigen::Translation< S, 3 > Translation3
GJKSolverType gjk_solver_type
narrow phase solver type
the object for collision or distance computation, contains the geometry and the transform information...
int main(int argc, char *argv[])
S distance_tolerance
the threshold used in GJK algorithm to stop distance iteration
Vector3< S > nearest_points[2]
Nearest points in the world coordinates.
request to the distance computation
GJKSolverType
Type of narrow phase GJK solver.