13 #include <boost/test/unit_test.hpp>
14 #include <boost/utility/binary.hpp>
16 #ifdef PINOCCHIO_WITH_HPP_FCL
18 #endif // PINOCCHIO_WITH_HPP_FCL
32 pos.translation() = SE3::LinearType(0, 0., 0.);
35 Eigen::VectorXd effortMax = Eigen::VectorXd::Constant(3, 0.2);
36 Eigen::VectorXd velLim = Eigen::VectorXd::Constant(3, 0.5);
37 Eigen::VectorXd posMin(4);
38 posMin << 0, 0, 0.70710678, 0.70710678;
39 Eigen::VectorXd posMax(4);
40 posMax << 0.0, 0.0, 1.0, 0.0;
43 pos.translation() = SE3::LinearType(
length, 0., 0.);
62 pos.translation() = SE3::LinearType(0, 0., 0.);
66 q = Eigen::VectorXd::Zero(3);
90 #ifdef PINOCCHIO_WITH_HPP_FCL
97 std::shared_ptr<pinocchio::fcl::CollisionGeometry>
geometry =
98 std::make_shared<pinocchio::fcl::Box>(dimension, dimension, dimension);
99 std::string geometry_object_name =
"obstacle";
107 geometry_object_name, idxJ, idxF, geomPlacement,
geometry);
108 geom_model.addGeometryObject(geometry_object);
111 BOOST_AUTO_TEST_SUITE(ReachableWorkspace)
120 Eigen::VectorXi indices = Eigen::VectorXi::Zero(ncomb);
122 int size =
static_cast<int>(
123 boost::math::factorial<double>(ndof) / boost::math::factorial<double>(ncomb)
124 / boost::math::factorial<double>(ndof - ncomb));
125 Eigen::MatrixXi
res(
size, ncomb);
126 for (
int k = 0; k <
size; k++)
130 res.row(k) = indices;
133 Eigen::MatrixXi trueRes(
size, ncomb);
134 trueRes << 0, 1, 0, 2, 0, 3, 0, 4, 0, 5, 1, 2, 1, 3, 1, 4, 1, 5, 2, 3, 2, 4, 2, 5, 3, 4, 3, 5, 4,
136 BOOST_CHECK(res == trueRes);
145 Eigen::VectorXd temp(3);
147 int n_ps =
static_cast<int>(std::pow(temp.size(), repeat));
149 Eigen::VectorXi indices = Eigen::VectorXi::Zero(repeat);
151 Eigen::MatrixXd
res(n_ps, repeat);
152 Eigen::VectorXd temp_(repeat);
153 for (
int k = 0; k < n_ps; k++)
159 Eigen::MatrixXd trueRes(n_ps, repeat);
160 trueRes << 2, 2, 2, 2, 2, 2, 2, 2, 2, 1, 2, 2, 2, 2, 0, 2, 2, 2, 1, 2, 2, 2, 2, 1, 1, 2, 2, 2, 1,
161 0, 2, 2, 2, 0, 2, 2, 2, 2, 0, 1, 2, 2, 2, 0, 0, 2, 2, 1, 2, 2, 2, 2, 1, 2, 1, 2, 2, 1, 2, 0, 2,
162 2, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 1, 1, 0, 2, 2, 1, 0, 2, 2, 2, 1, 0, 1, 2, 2, 1, 0, 0, 2, 2, 0,
163 2, 2, 2, 2, 0, 2, 1, 2, 2, 0, 2, 0, 2, 2, 0, 1, 2, 2, 2, 0, 1, 1, 2, 2, 0, 1, 0, 2, 2, 0, 0, 2,
164 2, 2, 0, 0, 1, 2, 2, 0, 0, 0, 2, 1, 2, 2, 2, 2, 1, 2, 2, 1, 2, 1, 2, 2, 0, 2, 1, 2, 1, 2, 2, 1,
165 2, 1, 1, 2, 1, 2, 1, 0, 2, 1, 2, 0, 2, 2, 1, 2, 0, 1, 2, 1, 2, 0, 0, 2, 1, 1, 2, 2, 2, 1, 1, 2,
166 1, 2, 1, 1, 2, 0, 2, 1, 1, 1, 2, 2, 1, 1, 1, 1, 2, 1, 1, 1, 0, 2, 1, 1, 0, 2, 2, 1, 1, 0, 1, 2,
167 1, 1, 0, 0, 2, 1, 0, 2, 2, 2, 1, 0, 2, 1, 2, 1, 0, 2, 0, 2, 1, 0, 1, 2, 2, 1, 0, 1, 1, 2, 1, 0,
168 1, 0, 2, 1, 0, 0, 2, 2, 1, 0, 0, 1, 2, 1, 0, 0, 0, 2, 0, 2, 2, 2, 2, 0, 2, 2, 1, 2, 0, 2, 2, 0,
169 2, 0, 2, 1, 2, 2, 0, 2, 1, 1, 2, 0, 2, 1, 0, 2, 0, 2, 0, 2, 2, 0, 2, 0, 1, 2, 0, 2, 0, 0, 2, 0,
170 1, 2, 2, 2, 0, 1, 2, 1, 2, 0, 1, 2, 0, 2, 0, 1, 1, 2, 2, 0, 1, 1, 1, 2, 0, 1, 1, 0, 2, 0, 1, 0,
171 2, 2, 0, 1, 0, 1, 2, 0, 1, 0, 0, 2, 0, 0, 2, 2, 2, 0, 0, 2, 1, 2, 0, 0, 2, 0, 2, 0, 0, 1, 2, 2,
172 0, 0, 1, 1, 2, 0, 0, 1, 0, 2, 0, 0, 0, 2, 2, 0, 0, 0, 1, 2, 0, 0, 0, 0, 1, 2, 2, 2, 2, 1, 2, 2,
173 2, 1, 1, 2, 2, 2, 0, 1, 2, 2, 1, 2, 1, 2, 2, 1, 1, 1, 2, 2, 1, 0, 1, 2, 2, 0, 2, 1, 2, 2, 0, 1,
174 1, 2, 2, 0, 0, 1, 2, 1, 2, 2, 1, 2, 1, 2, 1, 1, 2, 1, 2, 0, 1, 2, 1, 1, 2, 1, 2, 1, 1, 1, 1, 2,
175 1, 1, 0, 1, 2, 1, 0, 2, 1, 2, 1, 0, 1, 1, 2, 1, 0, 0, 1, 2, 0, 2, 2, 1, 2, 0, 2, 1, 1, 2, 0, 2,
176 0, 1, 2, 0, 1, 2, 1, 2, 0, 1, 1, 1, 2, 0, 1, 0, 1, 2, 0, 0, 2, 1, 2, 0, 0, 1, 1, 2, 0, 0, 0, 1,
177 1, 2, 2, 2, 1, 1, 2, 2, 1, 1, 1, 2, 2, 0, 1, 1, 2, 1, 2, 1, 1, 2, 1, 1, 1, 1, 2, 1, 0, 1, 1, 2,
178 0, 2, 1, 1, 2, 0, 1, 1, 1, 2, 0, 0, 1, 1, 1, 2, 2, 1, 1, 1, 2, 1, 1, 1, 1, 2, 0, 1, 1, 1, 1, 2,
179 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 1, 1, 1, 0, 2, 1, 1, 1, 0, 1, 1, 1, 1, 0, 0, 1, 1, 0, 2, 2, 1, 1,
180 0, 2, 1, 1, 1, 0, 2, 0, 1, 1, 0, 1, 2, 1, 1, 0, 1, 1, 1, 1, 0, 1, 0, 1, 1, 0, 0, 2, 1, 1, 0, 0,
181 1, 1, 1, 0, 0, 0, 1, 0, 2, 2, 2, 1, 0, 2, 2, 1, 1, 0, 2, 2, 0, 1, 0, 2, 1, 2, 1, 0, 2, 1, 1, 1,
182 0, 2, 1, 0, 1, 0, 2, 0, 2, 1, 0, 2, 0, 1, 1, 0, 2, 0, 0, 1, 0, 1, 2, 2, 1, 0, 1, 2, 1, 1, 0, 1,
183 2, 0, 1, 0, 1, 1, 2, 1, 0, 1, 1, 1, 1, 0, 1, 1, 0, 1, 0, 1, 0, 2, 1, 0, 1, 0, 1, 1, 0, 1, 0, 0,
184 1, 0, 0, 2, 2, 1, 0, 0, 2, 1, 1, 0, 0, 2, 0, 1, 0, 0, 1, 2, 1, 0, 0, 1, 1, 1, 0, 0, 1, 0, 1, 0,
185 0, 0, 2, 1, 0, 0, 0, 1, 1, 0, 0, 0, 0, 0, 2, 2, 2, 2, 0, 2, 2, 2, 1, 0, 2, 2, 2, 0, 0, 2, 2, 1,
186 2, 0, 2, 2, 1, 1, 0, 2, 2, 1, 0, 0, 2, 2, 0, 2, 0, 2, 2, 0, 1, 0, 2, 2, 0, 0, 0, 2, 1, 2, 2, 0,
187 2, 1, 2, 1, 0, 2, 1, 2, 0, 0, 2, 1, 1, 2, 0, 2, 1, 1, 1, 0, 2, 1, 1, 0, 0, 2, 1, 0, 2, 0, 2, 1,
188 0, 1, 0, 2, 1, 0, 0, 0, 2, 0, 2, 2, 0, 2, 0, 2, 1, 0, 2, 0, 2, 0, 0, 2, 0, 1, 2, 0, 2, 0, 1, 1,
189 0, 2, 0, 1, 0, 0, 2, 0, 0, 2, 0, 2, 0, 0, 1, 0, 2, 0, 0, 0, 0, 1, 2, 2, 2, 0, 1, 2, 2, 1, 0, 1,
190 2, 2, 0, 0, 1, 2, 1, 2, 0, 1, 2, 1, 1, 0, 1, 2, 1, 0, 0, 1, 2, 0, 2, 0, 1, 2, 0, 1, 0, 1, 2, 0,
191 0, 0, 1, 1, 2, 2, 0, 1, 1, 2, 1, 0, 1, 1, 2, 0, 0, 1, 1, 1, 2, 0, 1, 1, 1, 1, 0, 1, 1, 1, 0, 0,
192 1, 1, 0, 2, 0, 1, 1, 0, 1, 0, 1, 1, 0, 0, 0, 1, 0, 2, 2, 0, 1, 0, 2, 1, 0, 1, 0, 2, 0, 0, 1, 0,
193 1, 2, 0, 1, 0, 1, 1, 0, 1, 0, 1, 0, 0, 1, 0, 0, 2, 0, 1, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 2, 2, 2,
194 0, 0, 2, 2, 1, 0, 0, 2, 2, 0, 0, 0, 2, 1, 2, 0, 0, 2, 1, 1, 0, 0, 2, 1, 0, 0, 0, 2, 0, 2, 0, 0,
195 2, 0, 1, 0, 0, 2, 0, 0, 0, 0, 1, 2, 2, 0, 0, 1, 2, 1, 0, 0, 1, 2, 0, 0, 0, 1, 1, 2, 0, 0, 1, 1,
196 1, 0, 0, 1, 1, 0, 0, 0, 1, 0, 2, 0, 0, 1, 0, 1, 0, 0, 1, 0, 0, 0, 0, 0, 2, 2, 0, 0, 0, 2, 1, 0,
197 0, 0, 2, 0, 0, 0, 0, 1, 2, 0, 0, 0, 1, 1, 0, 0, 0, 1, 0, 0, 0, 0, 0, 2, 0, 0, 0, 0, 1, 0, 0, 0,
199 BOOST_CHECK(
res == trueRes);
208 Eigen::VectorXd res1 = Eigen::VectorXd::Constant(c1, 2.);
209 Eigen::VectorXd res2 = Eigen::VectorXd::Constant(
c2, 4.);
211 Eigen::VectorXi comb(c1);
214 Eigen::VectorXd resTotal(ndof);
218 Eigen::VectorXd resTrue(ndof);
219 resTrue << 4, 2, 4, 4, 4, 2, 4, 4, 2;
221 BOOST_CHECK(resTrue == resTotal);
230 Eigen::VectorXd
q = Eigen::VectorXd::Zero(3);
232 Eigen::MatrixXd vertex;
234 double constraint = 0.2;
237 if (
pos.translation()(0) < constraint)
245 BOOST_CHECK(vertex.rows() > 0);
246 BOOST_CHECK(vertex.cols() > 0);
247 for (
int k = 0; k < vertex.cols(); k++)
249 BOOST_CHECK(vertex(0, k) <=
length && vertex(0, k) >= constraint);
250 BOOST_CHECK(vertex(1, k) <=
length && vertex(1, k) >= 0);
251 BOOST_CHECK(vertex(2, k) <=
length && vertex(2, k) >= 0);
255 #ifdef PINOCCHIO_WITH_HPP_FCL
273 pinocchio::reachableWorkspaceWithCollisionsHull(
276 BOOST_CHECK(
res.vertex.rows() > 0);
277 BOOST_CHECK(
res.faces.rows() > 0);
279 for (
int k = 0; k <
res.vertex.cols(); k++)
281 BOOST_CHECK(
res.vertex(0, k) <=
length &&
res.vertex(0, k) >= 0);
282 BOOST_CHECK(
res.vertex(1, k) <=
length &&
res.vertex(1, k) >= 0);
283 BOOST_CHECK(
res.vertex(2, k) <=
length &&
res.vertex(2, k) >= 0);
285 if (
res.vertex(1, k) > dims / 2 &&
res.vertex(2, k) > dims / 2)
294 using namespace Eigen;
313 BOOST_CHECK(
res.vertex.cols() > 0);
314 BOOST_CHECK(
res.faces.rows() > 0);
337 BOOST_CHECK(
res.vertex.cols() > 0);
338 BOOST_CHECK(
res.faces.rows() > 0);
341 BOOST_AUTO_TEST_SUITE_END()