serialization.cpp 14.8 KB
Newer Older
1
2
3
4
//
// Copyright (c) 2019 INRIA
//

5
6
#include "pinocchio/algorithm/joint-configuration.hpp"

7
#include "pinocchio/serialization/archive.hpp"
8
9

#include "pinocchio/serialization/eigen.hpp"
10
11
12
13
#include "pinocchio/serialization/spatial.hpp"

#include "pinocchio/serialization/frame.hpp"

14
#include "pinocchio/serialization/joints.hpp"
15
16
17
18
#include "pinocchio/serialization/model.hpp"

#include "pinocchio/parsers/sample-models.hpp"

19
20
21
22
23
24
25
#include <iostream>

#include <boost/test/unit_test.hpp>
#include <boost/utility/binary.hpp>

BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)

26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
template<typename T1, typename T2 = T1>
struct call_equality_op
{
  static bool run(const T1 & v1, const T2 & v2)
  {
    return v1 == v2;
  }
};

template<typename T>
bool run_call_equality_op(const T & v1, const T & v2)
{
  return call_equality_op<T,T>::run(v1,v2);
}

// Bug fix in Eigen::Tensor
#ifdef PINOCCHIO_WITH_EIGEN_TENSOR_MODULE
template<typename Scalar, int NumIndices, int Options, typename IndexType>
struct call_equality_op< pinocchio::Tensor<Scalar,NumIndices,Options,IndexType> >
{
  typedef pinocchio::Tensor<Scalar,NumIndices,Options,IndexType> T;
  
  static bool run(const T & v1, const T & v2)
  {
    typedef Eigen::Matrix<Scalar,Eigen::Dynamic,1,Options> VectorXd;
    Eigen::Map<const VectorXd> map1(v1.data(),v1.size(),1);
    Eigen::Map<const VectorXd> map2(v2.data(),v2.size(),1);
    return map1 == map2;
  }
};
#endif

58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
template<typename T>
void generic_test(const T & object,
                  const std::string & filename,
                  const std::string & tag_name)
{
  using namespace pinocchio::serialization;
  
  // Load and save as TXT
  const std::string txt_filename = filename + ".txt";
  saveToText(object,txt_filename);
  
  {
    T object_loaded;
    loadFromText(object_loaded,txt_filename);
    
    // Check
74
    BOOST_CHECK(run_call_equality_op(object_loaded,object));
75
76
  }
  
77
78
79
80
81
82
83
84
85
86
  // Load and save as string stream
  std::stringstream ss_out;
  saveToStringStream(object,ss_out);
  
  {
    T object_loaded;
    std::istringstream is(ss_out.str());
    loadFromStringStream(object_loaded,is);
    
    // Check
87
    BOOST_CHECK(run_call_equality_op(object_loaded,object));
88
89
  }
  
90
  // Load and save as string
91
  std::string str_out = saveToString(object);
92
93
94
95
96
97
98
  
  {
    T object_loaded;
    std::string str_in(str_out);
    loadFromString(object_loaded,str_in);
    
    // Check
99
    BOOST_CHECK(run_call_equality_op(object_loaded,object));
100
101
  }
  
102
103
104
105
106
107
108
109
110
  // Load and save as XML
  const std::string xml_filename = filename + ".xml";
  saveToXML(object,xml_filename,tag_name);
  
  {
    T object_loaded;
    loadFromXML(object_loaded,xml_filename,tag_name);
    
    // Check
111
    BOOST_CHECK(run_call_equality_op(object_loaded,object));
112
113
114
115
  }
  
  // Load and save as binary
  const std::string bin_filename = filename + ".bin";
116
  saveToBinary(object,bin_filename);
117
118
119
  
  {
    T object_loaded;
120
    loadFromBinary(object_loaded,bin_filename);
121
122
    
    // Check
123
    BOOST_CHECK(run_call_equality_op(object_loaded,object));
124
125
126
  }
}

127
128
129
130
131
132
133
134
135
136
137
138
139
140
BOOST_AUTO_TEST_CASE(test_eigen_serialization)
{
  using namespace pinocchio;
  
  const Eigen::DenseIndex num_cols = 10;
  const Eigen::DenseIndex num_rows = 20;
  
  const Eigen::DenseIndex array_size = 3;
  
  Eigen::MatrixXd Mat = Eigen::MatrixXd::Random(num_rows,num_cols);
  generic_test(Mat,TEST_SERIALIZATION_FOLDER"/eigen_matrix","matrix");
  
  Eigen::VectorXd Vec = Eigen::VectorXd::Random(num_rows*num_cols);
  generic_test(Vec,TEST_SERIALIZATION_FOLDER"/eigen_vector","vector");
141
142
  
  Eigen::array<Eigen::DenseIndex,array_size> array = { 1, 2, 3 };
143
144
145
146
147
148
149
150
151
152
153
  generic_test(array,TEST_SERIALIZATION_FOLDER"/eigen_array","array");
  
  const Eigen::DenseIndex tensor_size = 3;
  const Eigen::DenseIndex x_dim = 10, y_dim = 20, z_dim = 30;
  
  typedef pinocchio::Tensor<double,tensor_size> Tensor3x;
  Tensor3x tensor(x_dim,y_dim,z_dim);
  
  Eigen::Map<Eigen::VectorXd>(tensor.data(),tensor.size(),1).setRandom();
  
  generic_test(tensor,TEST_SERIALIZATION_FOLDER"/eigen_tensor","tensor");
154
155
}

156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
BOOST_AUTO_TEST_CASE(test_spatial_serialization)
{
  using namespace pinocchio;
  
  SE3 M(SE3::Random());
  generic_test(M,TEST_SERIALIZATION_FOLDER"/SE3","SE3");
  
  Motion m(Motion::Random());
  generic_test(m,TEST_SERIALIZATION_FOLDER"/Motion","Motion");
  
  Force f(Force::Random());
  generic_test(f,TEST_SERIALIZATION_FOLDER"/Force","Force");
  
  Symmetric3 S(Symmetric3::Random());
  generic_test(S,TEST_SERIALIZATION_FOLDER"/Symmetric3","Symmetric3");
  
  Inertia I(Inertia::Random());
  generic_test(I,TEST_SERIALIZATION_FOLDER"/Inertia","Inertia");
}

BOOST_AUTO_TEST_CASE(test_multibody_serialization)
{
  using namespace pinocchio;
  
  Frame frame("frame",0,0,SE3::Random(),SENSOR);
  generic_test(frame,TEST_SERIALIZATION_FOLDER"/Frame","Frame");
}

184
185
186
187
template<typename JointModel_> struct init;

template<typename JointModel_>
struct init
188
{
189
  static JointModel_ run()
190
  {
191
    JointModel_ jmodel;
192
    jmodel.setIndexes(0,0,0);
193
    return jmodel;
194
  }
195
196
197
198
199
200
};

template<typename Scalar, int Options>
struct init<pinocchio::JointModelRevoluteUnalignedTpl<Scalar,Options> >
{
  typedef pinocchio::JointModelRevoluteUnalignedTpl<Scalar,Options> JointModel;
201
  
202
  static JointModel run()
203
  {
204
205
    typedef typename JointModel::Vector3 Vector3;
    JointModel jmodel(Vector3::Random().normalized());
206
    
207
208
    jmodel.setIndexes(0,0,0);
    return jmodel;
209
  }
210
211
};

212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
template<typename Scalar, int Options>
struct init<pinocchio::JointModelRevoluteUnboundedUnalignedTpl<Scalar,Options> >
{
  typedef pinocchio::JointModelRevoluteUnboundedUnalignedTpl<Scalar,Options> JointModel;
  
  static JointModel run()
  {
    typedef typename JointModel::Vector3 Vector3;
    JointModel jmodel(Vector3::Random().normalized());
    
    jmodel.setIndexes(0,0,0);
    return jmodel;
  }
};

227
228
229
230
template<typename Scalar, int Options>
struct init<pinocchio::JointModelPrismaticUnalignedTpl<Scalar,Options> >
{
  typedef pinocchio::JointModelPrismaticUnalignedTpl<Scalar,Options> JointModel;
231
  
232
  static JointModel run()
233
  {
234
235
236
    typedef typename JointModel::Vector3 Vector3;
    JointModel jmodel(Vector3::Random().normalized());
    
237
    jmodel.setIndexes(0,0,0);
238
239
240
    return jmodel;
  }
};
241

242
243
244
245
246
247
248
249
250
251
252
253
template<typename Scalar, int Options, template<typename,int> class JointCollection>
struct init<pinocchio::JointModelTpl<Scalar,Options,JointCollection> >
{
  typedef pinocchio::JointModelTpl<Scalar,Options,JointCollection> JointModel;
  
  static JointModel run()
  {
    typedef pinocchio::JointModelRevoluteTpl<Scalar,Options,0> JointModelRX;
    JointModel jmodel((JointModelRX()));
    
    jmodel.setIndexes(0,0,0);
    return jmodel;
254
  }
255
256
257
258
259
260
};

template<typename Scalar, int Options, template<typename,int> class JointCollection>
struct init<pinocchio::JointModelCompositeTpl<Scalar,Options,JointCollection> >
{
  typedef pinocchio::JointModelCompositeTpl<Scalar,Options,JointCollection> JointModel;
261
  
262
  static JointModel run()
263
  {
264
265
266
267
268
    typedef pinocchio::JointModelRevoluteTpl<Scalar,Options,0> JointModelRX;
    typedef pinocchio::JointModelRevoluteTpl<Scalar,Options,1> JointModelRY;
    JointModel jmodel((JointModelRX()));
    jmodel.addJoint(JointModelRY());
    
269
    jmodel.setIndexes(0,0,0);
270
271
272
    return jmodel;
  }
};
273

274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
template<typename JointModel_>
struct init<pinocchio::JointModelMimic<JointModel_> >
{
  typedef pinocchio::JointModelMimic<JointModel_> JointModel;
  
  static JointModel run()
  {
    JointModel_ jmodel_ref = init<JointModel_>::run();
    
    JointModel jmodel(jmodel_ref,1.,0.);
    
    return jmodel;
  }
};

Justin Carpentier's avatar
Justin Carpentier committed
289
struct TestJointModel
290
291
292
293
294
{
  template <typename JointModel>
  void operator()(const pinocchio::JointModelBase<JointModel> &) const
  {
    JointModel jmodel = init<JointModel>::run();
295
296
297
298
299
300
    test(jmodel);
  }
  
  template<typename JointType>
  static void test(JointType & jmodel)
  {
301
    generic_test(jmodel,TEST_SERIALIZATION_FOLDER"/Joint","jmodel");
302
303
304
305
  }
  
};

Justin Carpentier's avatar
Justin Carpentier committed
306
BOOST_AUTO_TEST_CASE(test_multibody_joints_model_serialization)
307
308
{
  using namespace pinocchio;
Justin Carpentier's avatar
Justin Carpentier committed
309
  boost::mpl::for_each<JointModelVariant::types>(TestJointModel());
310
311
}

312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
struct TestJointTransform
{
  template <typename JointModel>
  void operator()(const pinocchio::JointModelBase<JointModel> &) const
  {
    typedef typename JointModel::JointDerived JointDerived;
    typedef typename pinocchio::traits<JointDerived>::Transformation_t Transform;
    typedef typename pinocchio::traits<JointDerived>::JointDataDerived JointData;
    typedef pinocchio::JointDataBase<JointData> JointDataBase;
    JointModel jmodel = init<JointModel>::run();
    
    JointData jdata = jmodel.createData();
    JointDataBase & jdata_base = static_cast<JointDataBase &>(jdata);
    
    typedef typename pinocchio::LieGroup<JointModel>::type LieGroupType;
    LieGroupType lg;
   
    Eigen::VectorXd lb(Eigen::VectorXd::Constant(jmodel.nq(),-1.));
    Eigen::VectorXd ub(Eigen::VectorXd::Constant(jmodel.nq(), 1.));
    
    Eigen::VectorXd q_random = lg.randomConfiguration(lb,ub);
    
    jmodel.calc(jdata,q_random);
    Transform & m = jdata_base.M();
    test(m);
  }
  
  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
  void operator()(const pinocchio::JointModelCompositeTpl<Scalar,Options,JointCollectionTpl> &)
  {
    // Do nothing
  }
    
  template<typename JointModel>
  void operator()(const pinocchio::JointModelMimic<JointModel> &)
  {
    typedef pinocchio::JointModelMimic<JointModel> JointModelMimic;
    typedef typename JointModelMimic::JointDerived JointDerived;
    typedef typename pinocchio::traits<JointDerived>::Transformation_t Transform;
    typedef typename pinocchio::traits<JointDerived>::JointDataDerived JointDataMimic;
    typedef pinocchio::JointDataBase<JointDataMimic> JointDataBase;
    JointModelMimic jmodel_mimic = init<JointModelMimic>::run();
    JointModel jmodel = init<JointModel>::run();
    
    JointDataMimic jdata_mimic = jmodel_mimic.createData();
    JointDataBase & jdata_mimic_base = static_cast<JointDataBase &>(jdata_mimic);
    
    typedef typename pinocchio::LieGroup<JointModel>::type LieGroupType;
    LieGroupType lg;
    
    Eigen::VectorXd lb(Eigen::VectorXd::Constant(jmodel.nq(),-1.));
    Eigen::VectorXd ub(Eigen::VectorXd::Constant(jmodel.nq(), 1.));
    
    Eigen::VectorXd q_random = lg.randomConfiguration(lb,ub);
    
    jmodel_mimic.calc(jdata_mimic,q_random);
    Transform & m = jdata_mimic_base.M();
    test(m);
  }
  
  template<typename Transform>
  static void test(Transform & m)
  {
    generic_test(m,TEST_SERIALIZATION_FOLDER"/JointTransform","transform");
  }
  
};

BOOST_AUTO_TEST_CASE(test_multibody_joints_transform_serialization)
{
  using namespace pinocchio;
  boost::mpl::for_each<JointModelVariant::types>(TestJointTransform());
}

386
387
388
389
390
391
392
struct TestJointMotion
{
  template <typename JointModel>
  void operator()(const pinocchio::JointModelBase<JointModel> &) const
  {
    typedef typename JointModel::JointDerived JointDerived;
    typedef typename pinocchio::traits<JointDerived>::Motion_t Motion;
393
    typedef typename pinocchio::traits<JointDerived>::Bias_t Bias;
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
    typedef typename pinocchio::traits<JointDerived>::JointDataDerived JointData;
    typedef pinocchio::JointDataBase<JointData> JointDataBase;
    JointModel jmodel = init<JointModel>::run();
    
    JointData jdata = jmodel.createData();
    JointDataBase & jdata_base = static_cast<JointDataBase &>(jdata);
    
    typedef typename pinocchio::LieGroup<JointModel>::type LieGroupType;
    LieGroupType lg;
   
    Eigen::VectorXd lb(Eigen::VectorXd::Constant(jmodel.nq(),-1.));
    Eigen::VectorXd ub(Eigen::VectorXd::Constant(jmodel.nq(), 1.));
    
    Eigen::VectorXd q_random = lg.randomConfiguration(lb,ub);
    Eigen::VectorXd v_random = Eigen::VectorXd::Random(jmodel.nv());
    
    jmodel.calc(jdata,q_random,v_random);
    Motion & m = jdata_base.v();
    
    test(m);
414
415
416
    
    Bias & b = jdata_base.c();
    test(b);
417
418
419
420
421
422
423
424
425
426
427
428
429
430
  }
  
  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
  void operator()(const pinocchio::JointModelCompositeTpl<Scalar,Options,JointCollectionTpl> &)
  {
    // Do nothing
  }
    
  template<typename JointModel>
  void operator()(const pinocchio::JointModelMimic<JointModel> &)
  {
    typedef pinocchio::JointModelMimic<JointModel> JointModelMimic;
    typedef typename JointModelMimic::JointDerived JointDerived;
    typedef typename pinocchio::traits<JointDerived>::Motion_t Motion;
431
    typedef typename pinocchio::traits<JointDerived>::Bias_t Bias;
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
    typedef typename pinocchio::traits<JointDerived>::JointDataDerived JointDataMimic;
    typedef pinocchio::JointDataBase<JointDataMimic> JointDataBase;
    JointModelMimic jmodel_mimic = init<JointModelMimic>::run();
    JointModel jmodel = init<JointModel>::run();
    
    JointDataMimic jdata_mimic = jmodel_mimic.createData();
    JointDataBase & jdata_mimic_base = static_cast<JointDataBase &>(jdata_mimic);
    
    typedef typename pinocchio::LieGroup<JointModel>::type LieGroupType;
    LieGroupType lg;
    
    Eigen::VectorXd lb(Eigen::VectorXd::Constant(jmodel.nq(),-1.));
    Eigen::VectorXd ub(Eigen::VectorXd::Constant(jmodel.nq(), 1.));
    
    Eigen::VectorXd q_random = lg.randomConfiguration(lb,ub);
    Eigen::VectorXd v_random = Eigen::VectorXd::Random(jmodel.nv());
    
    jmodel_mimic.calc(jdata_mimic,q_random,v_random);
    Motion & m = jdata_mimic_base.v();
    
    test(m);
453
454
455
    
    Bias & b = jdata_mimic_base.c();
    test(b);
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
  }
  
  template<typename Motion>
  static void test(Motion & m)
  {
    generic_test(m,TEST_SERIALIZATION_FOLDER"/JointMotion","motion");
  }
  
};

BOOST_AUTO_TEST_CASE(test_multibody_joints_motion_serialization)
{
  using namespace pinocchio;
  boost::mpl::for_each<JointModelVariant::types>(TestJointMotion());
}

472
473
474
475
BOOST_AUTO_TEST_CASE(test_model_serialization)
{
  using namespace pinocchio;

476
477
478
479
  Model model;
  buildModels::humanoidRandom(model);
  
  generic_test(model,TEST_SERIALIZATION_FOLDER"/Model","Model");
480
481
}

482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
BOOST_AUTO_TEST_CASE(test_throw_extension)
{
  using namespace pinocchio;
  
  Model model;
  buildModels::humanoidRandom(model);
  
  const std::string & fake_filename = "this_is_a_fake_filename";
  
  {
    const std::string complete_filename = fake_filename + ".txt";
    BOOST_REQUIRE_THROW(loadFromText(model,complete_filename),
                        std::invalid_argument);
  }
  
  saveToText(model,TEST_SERIALIZATION_FOLDER"/model.txt");
  saveToXML(model,TEST_SERIALIZATION_FOLDER"/model.xml","model");
  saveToBinary(model,TEST_SERIALIZATION_FOLDER"/model.bin");
  
  {
    const std::string complete_filename = fake_filename + ".txte";
  
    BOOST_REQUIRE_THROW(loadFromText(model,complete_filename),
                        std::invalid_argument);
  }
  
  {
    const std::string complete_filename = fake_filename + ".xmle";
    BOOST_REQUIRE_THROW(loadFromXML(model,complete_filename,"model"),
                        std::invalid_argument);
  }
  
  {
    const std::string complete_filename = fake_filename + ".bine";
    BOOST_REQUIRE_THROW(loadFromBinary(model,complete_filename),
                        std::invalid_argument);
  }
  
}

522
BOOST_AUTO_TEST_SUITE_END()