27 #include <boost/test/unit_test.hpp>
28 #include <boost/utility/binary.hpp>
30 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
32 template<
typename T1,
typename T2 = T1>
35 static bool run(
const T1 & v1,
const T2 & v2)
48 #ifdef PINOCCHIO_WITH_EIGEN_TENSOR_MODULE
49 template<
typename Scalar,
int NumIndices,
int Options,
typename IndexType>
54 static bool run(
const T & v1,
const T & v2)
56 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> VectorXd;
57 Eigen::Map<const VectorXd> map1(v1.data(), v1.size(), 1);
58 Eigen::Map<const VectorXd> map2(v2.data(), v2.size(), 1);
89 void generic_test(
const T &
object,
const std::string & filename,
const std::string & tag_name)
94 const std::string txt_filename =
filename +
".txt";
98 T & object_loaded = *empty_contructor<T>();
104 delete &object_loaded;
108 std::stringstream ss_out;
112 T & object_loaded = *empty_contructor<T>();
113 std::istringstream is(ss_out.str());
119 delete &object_loaded;
126 T & object_loaded = *empty_contructor<T>();
127 std::string str_in(str_out);
133 delete &object_loaded;
137 const std::string xml_filename =
filename +
".xml";
138 saveToXML(
object, xml_filename, tag_name);
141 T & object_loaded = *empty_contructor<T>();
142 loadFromXML(object_loaded, xml_filename, tag_name);
147 delete &object_loaded;
151 const std::string bin_filename =
filename +
".bin";
155 T & object_loaded = *empty_contructor<T>();
161 delete &object_loaded;
165 boost::asio::streambuf buffer;
169 T & object_loaded = *empty_contructor<T>();
175 delete &object_loaded;
183 T & object_loaded = *empty_contructor<T>();
189 delete &object_loaded;
196 const size_t size = 10000000;
198 BOOST_CHECK(
size == static_buffer.
size());
200 const size_t new_size = 2 *
size;
201 static_buffer.
resize(new_size);
202 BOOST_CHECK(new_size == static_buffer.
size());
204 BOOST_CHECK(static_buffer.
data() != NULL);
205 BOOST_CHECK(
reinterpret_cast<const StaticBuffer &
>(static_buffer).
data() != NULL);
206 BOOST_CHECK(
reinterpret_cast<const StaticBuffer &
>(static_buffer).
data() == static_buffer.
data());
213 const Eigen::DenseIndex num_cols = 10;
214 const Eigen::DenseIndex num_rows = 20;
216 const Eigen::DenseIndex array_size = 3;
218 Eigen::MatrixXd Mat = Eigen::MatrixXd::Random(num_rows, num_cols);
219 generic_test(Mat, TEST_SERIALIZATION_FOLDER
"/eigen_matrix",
"matrix");
221 Eigen::VectorXd Vec = Eigen::VectorXd::Random(num_rows * num_cols);
222 generic_test(Vec, TEST_SERIALIZATION_FOLDER
"/eigen_vector",
"vector");
225 generic_test(array, TEST_SERIALIZATION_FOLDER
"/eigen_array",
"array");
227 const Eigen::DenseIndex tensor_size = 3;
228 const Eigen::DenseIndex
x_dim = 10,
y_dim = 20, z_dim = 30;
233 Eigen::Map<Eigen::VectorXd>(tensor.data(), tensor.size(), 1).setRandom();
235 generic_test(tensor, TEST_SERIALIZATION_FOLDER
"/eigen_tensor",
"tensor");
246 generic_test(
m, TEST_SERIALIZATION_FOLDER
"/Motion",
"Motion");
249 generic_test(
f, TEST_SERIALIZATION_FOLDER
"/Force",
"Force");
252 generic_test(
S, TEST_SERIALIZATION_FOLDER
"/Symmetric3",
"Symmetric3");
255 generic_test(I, TEST_SERIALIZATION_FOLDER
"/Inertia",
"Inertia");
266 template<
typename Jo
intModel_>
269 template<
typename Jo
intModel_>
275 jmodel.setIndexes(0, 0, 0);
280 template<
typename Scalar,
int Options>
288 JointModel jmodel(Vector3::Random().normalized());
295 template<
typename Scalar,
int Options>
303 JointModel jmodel(Vector3::Random().normalized());
310 template<
typename Scalar,
int Options>
318 JointModel jmodel(Vector3::Random().normalized());
325 template<
typename Scalar,
int Options>
333 JointModel jmodel(Vector3::Random().normalized());
340 template<
typename Scalar,
int Options,
int axis>
354 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollection>
369 template<
typename Scalar,
int Options>
383 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollection>
395 jmodel.setIndexes(0, 0, 0);
400 template<
typename Jo
intModel_>
417 template<
typename Jo
intModel>
424 template<
typename Jo
intType>
425 static void test(JointType & jmodel)
427 generic_test(jmodel, TEST_SERIALIZATION_FOLDER
"/Joint",
"jmodel");
439 template<
typename Jo
intModel>
442 typedef typename JointModel::JointDerived JointDerived;
455 Eigen::VectorXd lb(Eigen::VectorXd::Constant(jmodel.nq(), -1.));
456 Eigen::VectorXd ub(Eigen::VectorXd::Constant(jmodel.nq(), 1.));
458 Eigen::VectorXd q_random = lg.randomConfiguration(lb, ub);
460 jmodel.
calc(jdata, q_random);
461 Transform &
m = jdata_base.
M();
464 Constraint &
S = jdata_base.
S();
468 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
474 template<
typename Jo
intModel>
478 typedef typename JointModelMimic::JointDerived JointDerived;
492 Eigen::VectorXd lb(Eigen::VectorXd::Constant(jmodel.nq(), -1.));
493 Eigen::VectorXd ub(Eigen::VectorXd::Constant(jmodel.nq(), 1.));
495 Eigen::VectorXd q_random = lg.randomConfiguration(lb, ub);
497 jmodel_mimic.
calc(jdata_mimic, q_random);
498 Transform &
m = jdata_mimic_base.
M();
501 Constraint &
S = jdata_mimic_base.
S();
505 template<
typename Transform>
508 generic_test(
m, TEST_SERIALIZATION_FOLDER
"/JointTransform",
"transform");
520 template<
typename Jo
intModel>
523 typedef typename JointModel::JointDerived JointDerived;
536 Eigen::VectorXd lb(Eigen::VectorXd::Constant(jmodel.nq(), -1.));
537 Eigen::VectorXd ub(Eigen::VectorXd::Constant(jmodel.nq(), 1.));
539 Eigen::VectorXd q_random = lg.randomConfiguration(lb, ub);
540 Eigen::VectorXd v_random = Eigen::VectorXd::Random(jmodel.nv());
542 jmodel.
calc(jdata, q_random, v_random);
547 Bias &
b = jdata_base.
c();
551 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
557 template<
typename Jo
intModel>
561 typedef typename JointModelMimic::JointDerived JointDerived;
575 Eigen::VectorXd lb(Eigen::VectorXd::Constant(jmodel.nq(), -1.));
576 Eigen::VectorXd ub(Eigen::VectorXd::Constant(jmodel.nq(), 1.));
578 Eigen::VectorXd q_random = lg.randomConfiguration(lb, ub);
579 Eigen::VectorXd v_random = Eigen::VectorXd::Random(jmodel.nv());
581 jmodel_mimic.
calc(jdata_mimic, q_random, v_random);
586 Bias &
b = jdata_mimic_base.
c();
590 template<
typename Motion>
593 generic_test(
m, TEST_SERIALIZATION_FOLDER
"/JointMotion",
"motion");
605 template<
typename Jo
intModel>
608 typedef typename JointModel::JointDerived JointDerived;
617 Eigen::VectorXd lb(Eigen::VectorXd::Constant(jmodel.nq(), -1.));
618 Eigen::VectorXd ub(Eigen::VectorXd::Constant(jmodel.nq(), 1.));
620 Eigen::VectorXd q_random = lg.randomConfiguration(lb, ub);
621 Eigen::VectorXd v_random = Eigen::VectorXd::Random(jmodel.nv());
623 jmodel.
calc(jdata, q_random, v_random);
624 pinocchio::Inertia::Matrix6 I(pinocchio::Inertia::Matrix6::Identity());
625 jmodel.
calc_aba(jdata, Eigen::VectorXd::Zero(jmodel.nv()), I,
false);
629 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
633 typedef typename JointModel::JointDerived JointDerived;
640 model.lowerPositionLimit.fill(-1.);
641 model.upperPositionLimit.fill(1.);
645 Eigen::VectorXd v_random = Eigen::VectorXd::Random(
model.nv);
650 jmodel.
calc(jdata, q_random, v_random);
651 pinocchio::Inertia::Matrix6 I(pinocchio::Inertia::Matrix6::Identity());
652 jmodel.
calc_aba(jdata, Eigen::VectorXd::Zero(jmodel.nv()), I,
false);
657 template<
typename Jo
intModel>
661 typedef typename JointModelMimic::JointDerived JointDerived;
671 Eigen::VectorXd lb(Eigen::VectorXd::Constant(jmodel.nq(), -1.));
672 Eigen::VectorXd ub(Eigen::VectorXd::Constant(jmodel.nq(), 1.));
674 Eigen::VectorXd q_random = lg.randomConfiguration(lb, ub);
675 Eigen::VectorXd v_random = Eigen::VectorXd::Random(jmodel.nv());
677 jmodel_mimic.
calc(jdata_mimic, q_random, v_random);
678 pinocchio::Inertia::Matrix6 I(pinocchio::Inertia::Matrix6::Identity());
679 jmodel_mimic.
calc_aba(jdata_mimic, Eigen::VectorXd::Zero(jmodel.nv()), I,
false);
683 template<
typename Jo
intData>
686 generic_test(joint_data, TEST_SERIALIZATION_FOLDER
"/JointData",
"data");
693 boost::mpl::for_each<JointModelVariant::types>(
TestJointData());
713 const std::string & fake_filename =
"this_is_a_fake_filename";
716 const std::string complete_filename = fake_filename +
".txt";
717 BOOST_REQUIRE_THROW(
loadFromText(
model, complete_filename), std::invalid_argument);
721 saveToXML(
model, TEST_SERIALIZATION_FOLDER
"/model.xml",
"model");
725 const std::string complete_filename = fake_filename +
".txte";
727 BOOST_REQUIRE_THROW(
loadFromText(
model, complete_filename), std::invalid_argument);
731 const std::string complete_filename = fake_filename +
".xmle";
732 BOOST_REQUIRE_THROW(
loadFromXML(
model, complete_filename,
"model"), std::invalid_argument);
736 const std::string complete_filename = fake_filename +
".bine";
766 GeometryObject_ModelItem model_item(
"pinocchio", 1, 2,
SE3::Random());
767 generic_test(model_item, TEST_SERIALIZATION_FOLDER
"/ModelItem",
"ModelItem");
776 generic_test(geometry_object, TEST_SERIALIZATION_FOLDER
"/GeometryObject",
"GeometryObject");
779 #ifdef PINOCCHIO_WITH_HPP_FCL
785 #if HPP_FCL_VERSION_AT_LEAST(3, 0, 0)
788 CollisionGeometryPtr box_ptr = CollisionGeometryPtr(
new hpp::fcl::Box(1., 2., 3.));
790 generic_test(geometry_object, TEST_SERIALIZATION_FOLDER
"/GeometryObject",
"GeometryObject");
792 #endif // hpp-fcl >= 3.0.0
813 #ifdef PINOCCHIO_WITH_HPP_FCL
814 #if HPP_FCL_VERSION_AT_LEAST(3, 0, 0)
830 const double min_altitude = -1.;
832 const Eigen::DenseIndex
nx = 100,
ny = 200;
833 const Eigen::MatrixXd
heights = Eigen::MatrixXd::Random(
ny,
nx);
851 #endif // hpp-fcl >= 3.0.0
852 #endif // PINOCCHIO_WITH_HPP_FCL
855 BOOST_AUTO_TEST_SUITE_END()