38 #include <gtest/gtest.h> 54 sphere1_transform.translation() = (
Vector3<S> (0., 0., -50));
62 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Intersect_test_separated_z)
65 test_Sphere_Capsule_Intersect_test_separated_z<double>();
75 sphere1_transform.translation() = (
Vector3<S> (0., 0., 50));
83 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Intersect_test_separated_z_negative)
86 test_Sphere_Capsule_Intersect_test_separated_z_negative<double>();
96 sphere1_transform.translation() = (
Vector3<S> (0., 0., -50));
104 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Intersect_test_separated_x)
107 test_Sphere_Capsule_Intersect_test_separated_x<double>();
110 template <
typename S>
117 sphere1_transform.translation() = (
Vector3<S> (0., 0., -50));
126 capsule_transform.linear() = rotation;
127 capsule_transform.translation() =
Vector3<S>(150., 0., 0.);
132 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Intersect_test_separated_capsule_rotated)
135 test_Sphere_Capsule_Intersect_test_separated_capsule_rotated<double>();
138 template <
typename S>
149 std::vector<ContactPoint<S>> contacts;
151 bool is_intersecting = solver.
shapeIntersect(sphere1, sphere1_transform, capsule, capsule_transform, &contacts);
153 S penetration = contacts[0].penetration_depth;
163 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Intersect_test_penetration_z)
166 test_Sphere_Capsule_Intersect_test_penetration_z<double>();
169 template <
typename S>
183 capsule_transform.linear() = rotation;
184 capsule_transform.translation() =
Vector3<S> (0., 50., 75);
186 std::vector<ContactPoint<S>> contacts;
188 bool is_intersecting = solver.
shapeIntersect(sphere1, sphere1_transform, capsule, capsule_transform, &contacts);
190 S penetration = contacts[0].penetration_depth;
200 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Intersect_test_penetration_z_rotated)
203 test_Sphere_Capsule_Intersect_test_penetration_z_rotated<double>();
206 template <
typename S>
223 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Distance_test_collision)
226 test_Sphere_Capsule_Distance_test_collision<double>();
229 template <
typename S>
243 bool is_separated = solver.
shapeDistance(sphere1, sphere1_transform, capsule, capsule_transform, &distance);
249 GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Distance_test_separated)
252 test_Sphere_Capsule_Distance_test_separated<double>();
256 int main(
int argc,
char* argv[])
258 ::testing::InitGoogleTest(&argc, argv);
259 return RUN_ALL_TESTS();
FCL_DEPRECATED bool shapeIntersect(const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) const
intersection checking between two shapes
void test_Sphere_Capsule_Intersect_test_separated_z_negative()
void test_Sphere_Capsule_Intersect_test_separated_x()
void test_Sphere_Capsule_Distance_test_separated()
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
S collision_tolerance
the threshold used in GJK algorithm to stop collision iteration
Eigen::Matrix< S, 3, 3 > Matrix3
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
Eigen::AngleAxis< S > AngleAxis
collision and distance solver based on libccd library.
void test_Sphere_Capsule_Intersect_test_separated_z()
void test_Sphere_Capsule_Distance_test_collision()
GTEST_TEST(FCL_SPHERE_CAPSULE, Sphere_Capsule_Intersect_test_separated_z)
int main(int argc, char *argv[])
Eigen::Translation< S, 3 > Translation3
void test_Sphere_Capsule_Intersect_test_penetration_z()
void test_Sphere_Capsule_Intersect_test_separated_capsule_rotated()
void test_Sphere_Capsule_Intersect_test_penetration_z_rotated()
Center at zero point sphere.
#define EXPECT_TRUE(args)
bool shapeDistance(const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, S *dist=nullptr, Vector3< S > *p1=nullptr, Vector3< S > *p2=nullptr) const
distance computation between two shapes