37 #define BOOST_TEST_MODULE FCL_NESTEROV_GJK 38 #include <boost/test/included/unit_test.hpp> 40 #include <Eigen/Geometry> 88 mink_diff1.
set(&ellipsoid, &ellipsoid);
92 mink_diff2.
set(&ellipsoid, &box);
96 mink_diff3.
set(&cvx, &cvx);
102 unsigned int max_iterations = 128;
104 GJK gjk(max_iterations, tolerance);
105 GJK gjk_nesterov(max_iterations, tolerance);
114 std::vector<Transform3f> transforms;
121 init_support_guess.setZero();
123 for (
size_t i = 0; i < n; ++i) {
124 mink_diff.
set(&shape0, &shape1, identity, transforms[i]);
127 GJK::Status res_gjk_1 =
128 gjk.
evaluate(mink_diff, init_guess, init_support_guess);
130 GJK::Status res_gjk_2 =
131 gjk.
evaluate(mink_diff, init_guess, init_support_guess);
132 BOOST_CHECK(res_gjk_1 == res_gjk_2);
135 GJK::Status res_nesterov_gjk_1 =
136 gjk_nesterov.
evaluate(mink_diff, init_guess, init_support_guess);
137 Vec3f ray_nesterov = gjk_nesterov.
ray;
138 GJK::Status res_nesterov_gjk_2 =
139 gjk_nesterov.
evaluate(mink_diff, init_guess, init_support_guess);
140 BOOST_CHECK(res_nesterov_gjk_1 == res_nesterov_gjk_2);
145 BOOST_CHECK(res_nesterov_gjk_1 == res_gjk_1);
146 BOOST_CHECK_SMALL(fabs(ray_gjk.norm() - ray_nesterov.norm()), 1e-4);
178 Box box0 =
Box(0.1, 0.2, 0.3);
179 Box box1 =
Box(1.1, 1.2, 1.3);
223 Box box0 =
Box(0.1, 0.2, 0.3);
224 Box box1 =
Box(1.1, 1.2, 1.3);
231 Box box0 =
Box(0.1, 0.2, 0.3);
232 Box box1 =
Box(1.1, 1.2, 1.3);
GJKVariant gjk_variant
Variant to use for the GJK algorithm.
Ellipsoid centered at point zero.
BOOST_AUTO_TEST_CASE(set_gjk_variant)
GJKVariant
Variant to use for the GJK algorithm.
size_t getIterations()
Get GJK number of iterations.
void generateRandomTransforms(FCL_REAL extents[6], std::vector< Transform3f > &transforms, std::size_t n)
Generate n random transforms whose translations are constrained by extents.
void set(const ShapeBase *shape0, const ShapeBase *shape1)
Minkowski difference class of two shapes.
#define EIGEN_VECTOR_IS_APPROX(Va, Vb, precision)
Base class for all basic geometric shapes.
Convex< Triangle > constructPolytopeFromEllipsoid(const Ellipsoid &ellipsoid)
We give an ellipsoid as input. The output is a 20 faces polytope which vertices belong to the origina...
Center at zero point, axis aligned box.
bool normalize_support_direction
Wether or not to use the normalize heuristic in the GJK Nesterov acceleration. This setting is only a...
void test_nesterov_gjk(const ShapeBase &shape0, const ShapeBase &shape1)
Eigen::Vector2i support_func_guess_t
Capsule It is where is the distance between the point x and the capsule segment AB...
Triangle with 3 indices for points.
collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the ...
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Status evaluate(const MinkowskiDiff &shape, const Vec3f &guess, const support_func_guess_t &supportHint=support_func_guess_t::Zero())
GJK algorithm, given the initial value guess.