model.cpp 21.2 KB
Newer Older
1
//
2
// Copyright (c) 2016-2019 CNRS INRIA
3
4
//

5
#include "pinocchio/multibody/data.hpp"
6
#include "pinocchio/multibody/model.hpp"
7

8
#include "pinocchio/algorithm/check.hpp"
9
#include "pinocchio/algorithm/model.hpp"
10
11
12
#include "pinocchio/algorithm/kinematics.hpp"
#include "pinocchio/algorithm/frames.hpp"
#include "pinocchio/algorithm/joint-configuration.hpp"
13
#include "pinocchio/algorithm/geometry.hpp"
14

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

jcarpent's avatar
jcarpent committed
17
18
19
#include <boost/test/unit_test.hpp>
#include <boost/utility/binary.hpp>

20
using namespace pinocchio;
21

22
BOOST_AUTO_TEST_SUITE ( BOOST_TEST_MODULE )
23

24
25
26
  BOOST_AUTO_TEST_CASE(test_model_subtree)
  {
    Model model;
27
    buildModels::humanoidRandom(model);
28
29
30
31
32
33
34
    
    Model::JointIndex idx_larm1 = model.getJointId("larm1_joint");
    BOOST_CHECK(idx_larm1<(Model::JointIndex)model.njoints);
    Model::IndexVector subtree = model.subtrees[idx_larm1];
    BOOST_CHECK(subtree.size()==6);
    
    for(size_t i=1; i<subtree.size();++i)
35
    {
36
      BOOST_CHECK(model.parents[subtree[i]]==subtree[i-1]);
37
38
39
40
41
42
43
44
45
46
47
48
49
    }
      
    // Check that i starts subtree[i]
    for(JointIndex joint_id = 1; joint_id < (JointIndex)model.njoints; ++joint_id)
    {
      BOOST_CHECK(model.subtrees[joint_id][0] == joint_id);
    }
    
    // Check that subtree[0] contains all joint ids
    for(JointIndex joint_id = 1; joint_id < (JointIndex)model.njoints; ++joint_id)
    {
      BOOST_CHECK(model.subtrees[0][joint_id-1] == joint_id);
    }
50
51
  }

52
53
54
55
56
57
58
59
60
61
62
63
  BOOST_AUTO_TEST_CASE(test_model_get_frame_id)
  {
    Model model;
    buildModels::humanoidRandom(model);
    
    for(FrameIndex i=0; i<static_cast<FrameIndex>(model.nframes); i++)
    {
      BOOST_CHECK_EQUAL(i, model.getFrameId(model.frames[i].name));
    }
    BOOST_CHECK_EQUAL(model.nframes, model.getFrameId("NOT_A_FRAME"));
  }

64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
  BOOST_AUTO_TEST_CASE(test_model_support)
  {
    Model model;
    buildModels::humanoidRandom(model);
    const Model::IndexVector support0_ref(1,0);
    BOOST_CHECK(model.supports[0] == support0_ref);

    // Check that i ends supports[i]
    for(JointIndex joint_id = 1; joint_id < (JointIndex)model.njoints; ++joint_id)
    {
      BOOST_CHECK(model.supports[joint_id].back() == joint_id);
      Model::IndexVector & support = model.supports[joint_id];
      
      size_t current_id = support.size()-2;
      for(JointIndex parent_id = model.parents[joint_id];
          parent_id > 0;
          parent_id = model.parents[parent_id],
          current_id--)
      {
        BOOST_CHECK(parent_id == support[current_id]);
      }
    }
  }

88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
  BOOST_AUTO_TEST_CASE(test_model_subspace_dimensions)
  {
    Model model;
    buildModels::humanoidRandom(model);

    // Check that i ends supports[i]
    for(JointIndex joint_id = 1; joint_id < (JointIndex)model.njoints; ++joint_id)
    {
      const Model::JointModel & jmodel = model.joints[joint_id];
      
      BOOST_CHECK(model.nqs[joint_id] == jmodel.nq());
      BOOST_CHECK(model.idx_qs[joint_id] == jmodel.idx_q());
      
      BOOST_CHECK(model.nvs[joint_id] == jmodel.nv());
      BOOST_CHECK(model.idx_vs[joint_id] == jmodel.idx_v());
    }
  }

106
107
108
  BOOST_AUTO_TEST_CASE(comparison)
  {
    Model model;
109
    buildModels::humanoidRandom(model);
110
111
112
    
    BOOST_CHECK(model == model);
  }
113
  
114
115
116
  BOOST_AUTO_TEST_CASE(cast)
  {
    Model model;
117
    buildModels::humanoidRandom(model);
118
    
Justin Carpentier's avatar
Justin Carpentier committed
119
120
    BOOST_CHECK(model.cast<double>() == model.cast<double>());
    BOOST_CHECK(model.cast<double>().cast<long double>() == model.cast<long double>());
121
  }
122

123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
  BOOST_AUTO_TEST_CASE(test_std_vector_of_Model)
  {
    Model model;
    buildModels::humanoid(model);
    
    PINOCCHIO_ALIGNED_STD_VECTOR(Model) models;
    for(size_t k = 0; k < 20; ++k)
    {
      models.push_back(Model());
      buildModels::humanoid(models.back());
      
      BOOST_CHECK(model == models.back());
    }
  }

138
139
140
141
142
143
144
145
146
147
#ifdef PINOCCHIO_WITH_HPP_FCL
  struct AddPrefix {
    std::string p;
    std::string operator() (const std::string& n) { return p + n; }
    Frame operator() (const Frame& _f) { Frame f (_f); f.name = p + f.name; return f; }
    AddPrefix (const char* _p) : p(_p) {}
  };

  BOOST_AUTO_TEST_CASE(append)
  {
Joseph Mirabel's avatar
Joseph Mirabel committed
148
149
    Model manipulator, humanoid;
    GeometryModel geomManipulator, geomHumanoid;
150
151
152

    buildModels::manipulator(manipulator);
    buildModels::manipulatorGeometries(manipulator, geomManipulator);
153
    geomManipulator.addAllCollisionPairs();
154
155
156
157
158
159
160
    // Add prefix to joint and frame names
    AddPrefix addManipulatorPrefix ("manipulator/");
    std::transform (++manipulator.names.begin(), manipulator.names.end(),
        ++manipulator.names.begin(), addManipulatorPrefix);
    std::transform (++manipulator.frames.begin(), manipulator.frames.end(),
        ++manipulator.frames.begin(), addManipulatorPrefix);

161
    BOOST_TEST_MESSAGE(manipulator);
162
163
164

    buildModels::humanoid(humanoid);
    buildModels::humanoidGeometries(humanoid, geomHumanoid);
165
    geomHumanoid.addAllCollisionPairs();
166
167
168
169
170
171
172
    // Add prefix to joint and frame names
    AddPrefix addHumanoidPrefix ("humanoid/");
    std::transform (++humanoid.names.begin(), humanoid.names.end(),
        ++humanoid.names.begin(), addHumanoidPrefix);
    std::transform (++humanoid.frames.begin(), humanoid.frames.end(),
        ++humanoid.frames.begin(), addHumanoidPrefix);

173
    BOOST_TEST_MESSAGE(humanoid);
174
175
176
177
    
    //TODO fix inertia of the base
    manipulator.inertias[0].setRandom();
    SE3 aMb = SE3::Random();
Joseph Mirabel's avatar
Joseph Mirabel committed
178
179
180
181

    // First append a model to the universe frame.
    Model model1;
    GeometryModel geomModel1;
182
183
    FrameIndex fid = 0;
    appendModel (humanoid, manipulator, geomHumanoid, geomManipulator, fid,
Joseph Mirabel's avatar
Joseph Mirabel committed
184
        SE3::Identity(), model1, geomModel1);
185
186
187
188
189
190
191
192
193
    
    {
      Model model2 = appendModel(humanoid, manipulator, fid, SE3::Identity());
      Model model3;
      appendModel(humanoid, manipulator, fid, SE3::Identity(), model3);
      BOOST_CHECK(model1 == model2);
      BOOST_CHECK(model1 == model3);
      BOOST_CHECK(model2 == model3);
    }
Joseph Mirabel's avatar
Joseph Mirabel committed
194

195
196
197
    Data data1 (model1);
    BOOST_CHECK(model1.check(data1));

Joseph Mirabel's avatar
Joseph Mirabel committed
198
199
200
201
    BOOST_TEST_MESSAGE(model1);

    // Second, append a model to a moving frame.
    Model model;
202
    
Joseph Mirabel's avatar
Joseph Mirabel committed
203
204
    GeometryModel geomModel;
    fid = humanoid.addFrame (Frame ("humanoid/add_manipulator", 
205
206
207
208
          humanoid.getJointId("humanoid/chest2_joint"),
          humanoid.getFrameId("humanoid/chest2_joint"), aMb,
          OP_FRAME));

209
    appendModel (humanoid, manipulator, geomHumanoid, geomManipulator, fid,
210
        SE3::Identity(), model, geomModel);
211
212
213
214
215
    
    {
      Model model2 = appendModel(humanoid, manipulator, fid, SE3::Identity());
      Model model3;
      appendModel(humanoid, manipulator, fid, SE3::Identity(), model3);
Justin Carpentier's avatar
Justin Carpentier committed
216
217
      BOOST_CHECK(model == model2);
      BOOST_CHECK(model == model3);
218
219
      BOOST_CHECK(model2 == model3);
    }
220

221
    BOOST_TEST_MESSAGE(model);
222

223
224
225
    Data data (model);
    BOOST_CHECK(model.check(data));

226
227
228
229
230
231
232
    // Check the model
    BOOST_CHECK_EQUAL(model.getJointId("humanoid/chest2_joint"),
        model.parents[model.getJointId("manipulator/shoulder1_joint")]);

    // check the joint order and the inertias
    JointIndex chest2 = model.getJointId("humanoid/chest2_joint");
    for (JointIndex jid = 1; jid < chest2; ++jid) {
233
      BOOST_TEST_MESSAGE("Checking joint " << jid << " " << model.names[jid]);
234
235
236
237
      BOOST_CHECK_EQUAL(model.names[jid], humanoid.names[jid]);
      BOOST_CHECK_EQUAL(model.inertias[jid], humanoid.inertias[jid]);
      BOOST_CHECK_EQUAL(model.jointPlacements[jid], humanoid.jointPlacements[jid]);
    }
238
    BOOST_TEST_MESSAGE("Checking joint " << chest2 << " " << model.names[chest2]);
239
240
241
242
243
244
    BOOST_CHECK_EQUAL(model.names[chest2], humanoid.names[chest2]);
    BOOST_CHECK_MESSAGE(model.inertias[chest2].isApprox(manipulator.inertias[0].se3Action(aMb) + humanoid.inertias[chest2]),
        model.inertias[chest2] << " != " << manipulator.inertias[0].se3Action(aMb) + humanoid.inertias[chest2]);
    BOOST_CHECK_EQUAL(model.jointPlacements[chest2], humanoid.jointPlacements[chest2]);

    for (JointIndex jid = 1; jid < manipulator.joints.size(); ++jid) {
245
      BOOST_TEST_MESSAGE("Checking joint " << chest2+jid << " " << model.names[chest2+jid]);
246
247
248
249
250
251
252
253
      BOOST_CHECK_EQUAL(model.names[chest2+jid], manipulator.names[jid]);
      BOOST_CHECK_EQUAL(model.inertias[chest2+jid], manipulator.inertias[jid]);
      if (jid==1)
        BOOST_CHECK_EQUAL(model.jointPlacements[chest2+jid], aMb*manipulator.jointPlacements[jid]);
      else
        BOOST_CHECK_EQUAL(model.jointPlacements[chest2+jid], manipulator.jointPlacements[jid]);
    }
    for (JointIndex jid = chest2+1; jid < humanoid.joints.size(); ++jid) {
254
      BOOST_TEST_MESSAGE("Checking joint " << jid+manipulator.joints.size()-1 << " " << model.names[jid+manipulator.joints.size()-1]);
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
      BOOST_CHECK_EQUAL(model.names[jid+manipulator.joints.size()-1], humanoid.names[jid]);
      BOOST_CHECK_EQUAL(model.inertias[jid+manipulator.joints.size()-1], humanoid.inertias[jid]);
      BOOST_CHECK_EQUAL(model.jointPlacements[jid+manipulator.joints.size()-1], humanoid.jointPlacements[jid]);
    }

    // Check the frames
    for (FrameIndex fid = 1; fid < humanoid.frames.size(); ++fid) {
      const Frame& frame  = humanoid.frames[fid],
                   parent = humanoid.frames[frame.previousFrame];
      BOOST_CHECK(model.existFrame (frame.name, frame.type));
      const Frame& nframe  = model.frames[model.getFrameId(frame.name, frame.type)],
                   nparent = model.frames[nframe.previousFrame];
      BOOST_CHECK_EQUAL(parent.name, nparent.name);
      BOOST_CHECK_EQUAL(frame.placement, nframe.placement);
    }
    for (FrameIndex fid = 1; fid < manipulator.frames.size(); ++fid) {
      const Frame& frame  = manipulator.frames[fid],
                   parent = manipulator.frames[frame.previousFrame];
      BOOST_CHECK(model.existFrame (frame.name, frame.type));
      const Frame& nframe  = model.frames[model.getFrameId(frame.name, frame.type)],
                   nparent = model.frames[nframe.previousFrame];
      if (frame.previousFrame > 0) {
        BOOST_CHECK_EQUAL(parent.name, nparent.name);
        BOOST_CHECK_EQUAL(frame.placement, nframe.placement);
      }
    }
  }
#endif

284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
BOOST_AUTO_TEST_CASE(test_buildReducedModel_empty)
{
  Model humanoid_model;
  buildModels::humanoid(humanoid_model);
  
  static const std::vector<JointIndex> empty_index_vector;
  
  humanoid_model.lowerPositionLimit.head<3>().fill(-1.);
  humanoid_model.upperPositionLimit.head<3>().fill( 1.);
  
  humanoid_model.referenceConfigurations.insert(std::pair<std::string,Eigen::VectorXd>("neutral",neutral(humanoid_model)));
  Eigen::VectorXd reference_config_humanoid = randomConfiguration(humanoid_model);
  Model humanoid_copy_model = buildReducedModel(humanoid_model,empty_index_vector,reference_config_humanoid);
  
  BOOST_CHECK(humanoid_copy_model.names == humanoid_model.names);
  BOOST_CHECK(humanoid_copy_model.joints == humanoid_model.joints);
  BOOST_CHECK(humanoid_copy_model == humanoid_model);
  BOOST_CHECK(humanoid_copy_model.referenceConfigurations["neutral"].isApprox(neutral(humanoid_copy_model)));
  
  const std::vector<JointIndex> empty_joints_to_lock;
  
  const Model reduced_humanoid_model = buildReducedModel(humanoid_model,empty_joints_to_lock,reference_config_humanoid);
  BOOST_CHECK(reduced_humanoid_model.njoints == humanoid_model.njoints);
  BOOST_CHECK(reduced_humanoid_model.frames == humanoid_model.frames);
  BOOST_CHECK(reduced_humanoid_model.jointPlacements == humanoid_model.jointPlacements);
  BOOST_CHECK(reduced_humanoid_model.joints == humanoid_model.joints);
  
  for(JointIndex joint_id = 1; joint_id < (JointIndex)reduced_humanoid_model.njoints; ++joint_id)
  {
    BOOST_CHECK(reduced_humanoid_model.inertias[joint_id].isApprox(humanoid_model.inertias[joint_id]));
  }
}

317
318
319
320
321
322
323
324
325
326
BOOST_AUTO_TEST_CASE(test_buildReducedModel)
{
  Model humanoid_model;
  buildModels::humanoid(humanoid_model);
  
  static const std::vector<JointIndex> empty_index_vector;
  
  humanoid_model.lowerPositionLimit.head<3>().fill(-1.);
  humanoid_model.upperPositionLimit.head<3>().fill( 1.);
  
327
  humanoid_model.referenceConfigurations.insert(std::pair<std::string,Eigen::VectorXd>("neutral",neutral(humanoid_model)));
328
329
330
331
332
333
  Eigen::VectorXd reference_config_humanoid = randomConfiguration(humanoid_model);
  Model humanoid_copy_model = buildReducedModel(humanoid_model,empty_index_vector,reference_config_humanoid);
  
  BOOST_CHECK(humanoid_copy_model.names == humanoid_model.names);
  BOOST_CHECK(humanoid_copy_model.joints == humanoid_model.joints);
  BOOST_CHECK(humanoid_copy_model == humanoid_model);
334
  BOOST_CHECK(humanoid_copy_model.referenceConfigurations["neutral"].isApprox(neutral(humanoid_copy_model)));
335
336
337
338
339
340
341
342
343
  
  std::vector<JointIndex> joints_to_lock;
  const std::string joint1_to_lock = "rarm_shoulder2_joint";
  joints_to_lock.push_back(humanoid_model.getJointId(joint1_to_lock));
  const std::string joint2_to_lock = "larm_shoulder2_joint";
  joints_to_lock.push_back(humanoid_model.getJointId(joint2_to_lock));

  Model reduced_humanoid_model = buildReducedModel(humanoid_model,joints_to_lock,reference_config_humanoid);
  BOOST_CHECK(reduced_humanoid_model.njoints == humanoid_model.njoints-(int)joints_to_lock.size());
344
  
345
346
  BOOST_CHECK(reduced_humanoid_model != humanoid_model);
  
347
348
349
350
  Model reduced_humanoid_model_other_signature;
  buildReducedModel(humanoid_model,joints_to_lock,reference_config_humanoid,reduced_humanoid_model_other_signature);
  BOOST_CHECK(reduced_humanoid_model == reduced_humanoid_model_other_signature);
  
351
352
353
354
355
356
357
358
359
360
361
362
363
  // Check that forward kinematics give same results
  Data data(humanoid_model), reduced_data(reduced_humanoid_model);
  Eigen::VectorXd q = reference_config_humanoid;
  Eigen::VectorXd reduced_q(reduced_humanoid_model.nq);
  
  for(JointIndex joint_id = 1; joint_id < (JointIndex)reduced_humanoid_model.njoints; ++joint_id)
  {
    const JointIndex reference_joint_id = humanoid_model.getJointId(reduced_humanoid_model.names[joint_id]);
    
    reduced_humanoid_model.joints[joint_id].jointConfigSelector(reduced_q) =
    humanoid_model.joints[reference_joint_id].jointConfigSelector(q);
  }
  
364
365
  BOOST_CHECK(reduced_humanoid_model.referenceConfigurations["neutral"].isApprox(neutral(reduced_humanoid_model)));
  
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
  framesForwardKinematics(humanoid_model,data,q);
  framesForwardKinematics(reduced_humanoid_model,reduced_data,reduced_q);
  
  for(size_t frame_id = 0; frame_id < reduced_humanoid_model.frames.size(); ++frame_id)
  {
    const Frame & reduced_frame = reduced_humanoid_model.frames[frame_id];
    switch(reduced_frame.type)
    {
      case JOINT:
      case FIXED_JOINT:
      {
        // May not be present in the original model
        if(humanoid_model.existJointName(reduced_frame.name))
        {
          const JointIndex joint_id = humanoid_model.getJointId(reduced_frame.name);
          BOOST_CHECK(data.oMi[joint_id].isApprox(reduced_data.oMf[frame_id]));
        }
        else if(humanoid_model.existFrame(reduced_frame.name))
        {
          const FrameIndex humanoid_frame_id = humanoid_model.getFrameId(reduced_frame.name);
          BOOST_CHECK(data.oMf[humanoid_frame_id].isApprox(reduced_data.oMf[frame_id]));
        }
        else
        {
          BOOST_CHECK_MESSAGE(false, "The frame " << reduced_frame.name << " is not presend in the humanoid_model");
        }
        break;
      }
      default:
      {
        BOOST_CHECK(humanoid_model.existFrame(reduced_frame.name));
        const FrameIndex humanoid_frame_id = humanoid_model.getFrameId(reduced_frame.name);
        BOOST_CHECK(data.oMf[humanoid_frame_id].isApprox(reduced_data.oMf[frame_id]));
        break;
      }
        
    }
  }
}

406
407
408
409
410
411
412
413
414
415
416
417
BOOST_AUTO_TEST_CASE(test_aligned_vector_of_model)
{
  typedef PINOCCHIO_ALIGNED_STD_VECTOR(Model) VectorOfModels;
  
  VectorOfModels models;
  for(size_t k = 0; k < 100; ++k)
  {
    models.push_back(Model());
    buildModels::humanoidRandom(models[k]);
  }
}

418
#ifdef PINOCCHIO_WITH_HPP_FCL
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
BOOST_AUTO_TEST_CASE(test_buildReducedModel_with_geom)
{
  Model humanoid_model;
  buildModels::humanoid(humanoid_model);
  
  humanoid_model.lowerPositionLimit.head<3>().fill(-1.);
  humanoid_model.upperPositionLimit.head<3>().fill( 1.);
  const Eigen::VectorXd reference_config_humanoid = randomConfiguration(humanoid_model);
  
  GeometryModel humanoid_geometry;
  buildModels::humanoidGeometries(humanoid_model, humanoid_geometry);
  
  static const std::vector<JointIndex> empty_index_vector;
  
  Model humanoid_copy_model; GeometryModel humanoid_copy_geometry;
  buildReducedModel(humanoid_model,humanoid_geometry,empty_index_vector,
                    reference_config_humanoid,humanoid_copy_model,humanoid_copy_geometry);

  BOOST_CHECK(humanoid_copy_model == humanoid_model);
  BOOST_CHECK(humanoid_copy_geometry == humanoid_geometry);
  
  std::vector<JointIndex> joints_to_lock;
  const std::string joint1_to_lock = "rarm_shoulder2_joint";
  joints_to_lock.push_back(humanoid_model.getJointId(joint1_to_lock));
  const std::string joint2_to_lock = "larm_shoulder2_joint";
  joints_to_lock.push_back(humanoid_model.getJointId(joint2_to_lock));
  
  Model reduced_humanoid_model; GeometryModel reduced_humanoid_geometry;
  buildReducedModel(humanoid_model,humanoid_geometry,joints_to_lock,
                    reference_config_humanoid,reduced_humanoid_model,reduced_humanoid_geometry);
  
  BOOST_CHECK(reduced_humanoid_geometry.ngeoms == humanoid_geometry.ngeoms);
  BOOST_CHECK(reduced_humanoid_geometry.collisionPairs == humanoid_geometry.collisionPairs);
  BOOST_CHECK(reduced_humanoid_geometry.geometryObjects.size() == humanoid_geometry.geometryObjects.size());
  
  for(Index i = 0; i < humanoid_geometry.geometryObjects.size(); ++i)
  {
    const GeometryObject & go1 = humanoid_geometry.geometryObjects[i];
    const GeometryObject & go2 = reduced_humanoid_geometry.geometryObjects[i];
Joseph Mirabel's avatar
Joseph Mirabel committed
458
459
460
461
462
463
464
465
466
    BOOST_CHECK_EQUAL(go1.name, go2.name);
    BOOST_CHECK_EQUAL(go1.geometry, go2.geometry);
    BOOST_CHECK_EQUAL(go1.meshPath, go2.meshPath);
    BOOST_CHECK_EQUAL(go1.meshScale, go2.meshScale);
    BOOST_CHECK_EQUAL(go1.overrideMaterial, go2.overrideMaterial);
    BOOST_CHECK_EQUAL(go1.meshColor, go2.meshColor);
    BOOST_CHECK_EQUAL(go1.meshTexturePath, go2.meshTexturePath);
    BOOST_CHECK_EQUAL(humanoid_model.frames[go1.parentFrame].name,
                      reduced_humanoid_model.frames[go2.parentFrame].name);
467
468
469
470
471
472
473
474
475
476
477
478
479
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
522
523
524
525
526
527
528
529
  }
  
  Data data(humanoid_model), reduced_data(reduced_humanoid_model);
  const Eigen::VectorXd q = reference_config_humanoid;
  Eigen::VectorXd reduced_q(reduced_humanoid_model.nq);
  
  for(JointIndex joint_id = 1; joint_id < (JointIndex)reduced_humanoid_model.njoints; ++joint_id)
  {
    const JointIndex reference_joint_id = humanoid_model.getJointId(reduced_humanoid_model.names[joint_id]);
    
    reduced_humanoid_model.joints[joint_id].jointConfigSelector(reduced_q) =
    humanoid_model.joints[reference_joint_id].jointConfigSelector(q);
  }
  
  framesForwardKinematics(humanoid_model,data,q);
  framesForwardKinematics(reduced_humanoid_model,reduced_data,reduced_q);
  
  for(size_t frame_id = 0; frame_id < reduced_humanoid_model.frames.size(); ++frame_id)
  {
    const Frame & reduced_frame = reduced_humanoid_model.frames[frame_id];
    switch(reduced_frame.type)
    {
      case JOINT:
      case FIXED_JOINT:
      {
        // May not be present in the original model
        if(humanoid_model.existJointName(reduced_frame.name))
        {
          const JointIndex joint_id = humanoid_model.getJointId(reduced_frame.name);
          BOOST_CHECK(data.oMi[joint_id].isApprox(reduced_data.oMf[frame_id]));
        }
        else if(humanoid_model.existFrame(reduced_frame.name))
        {
          const FrameIndex humanoid_frame_id = humanoid_model.getFrameId(reduced_frame.name);
          BOOST_CHECK(data.oMf[humanoid_frame_id].isApprox(reduced_data.oMf[frame_id]));
        }
        else
        {
          BOOST_CHECK_MESSAGE(false, "The frame " << reduced_frame.name << " is not presend in the humanoid_model");
        }
        break;
      }
      default:
      {
        BOOST_CHECK(humanoid_model.existFrame(reduced_frame.name));
        const FrameIndex humanoid_frame_id = humanoid_model.getFrameId(reduced_frame.name);
        BOOST_CHECK(data.oMf[humanoid_frame_id].isApprox(reduced_data.oMf[frame_id]));
        break;
      }
        
    }
  }
  
  // Test GeometryObject placements
  GeometryData geom_data(humanoid_geometry), reduded_geom_data(reduced_humanoid_geometry);
  updateGeometryPlacements(humanoid_model,data,humanoid_geometry,geom_data);
  updateGeometryPlacements(reduced_humanoid_model,reduced_data,reduced_humanoid_geometry,reduded_geom_data);
  
  BOOST_CHECK(geom_data.oMg.size() == reduded_geom_data.oMg.size());
  for(FrameIndex i = 0; i < geom_data.oMg.size(); ++i)
  {
    BOOST_CHECK(geom_data.oMg[i].isApprox(reduded_geom_data.oMg[i]));
  }
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
  
  // Test other signature
  std::vector<GeometryModel> full_geometry_models;
  full_geometry_models.push_back(humanoid_geometry);
  full_geometry_models.push_back(humanoid_geometry);
  full_geometry_models.push_back(humanoid_geometry);
  
  std::vector<GeometryModel> reduced_geometry_models;
  
  Model reduced_humanoid_model_other_sig;
  buildReducedModel(humanoid_model,full_geometry_models,joints_to_lock,
                    reference_config_humanoid,reduced_humanoid_model_other_sig,reduced_geometry_models);
  
  BOOST_CHECK(reduced_geometry_models[0] == reduced_humanoid_geometry);
  BOOST_CHECK(reduced_geometry_models[1] == reduced_humanoid_geometry);
  BOOST_CHECK(reduced_geometry_models[2] == reduced_humanoid_geometry);
546
}
547
#endif // PINOCCHIO_WITH_HPP_FCL
548

549
BOOST_AUTO_TEST_SUITE_END()