unittest/model.cpp
Go to the documentation of this file.
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 #include "pinocchio/algorithm/kinematics.hpp"
11 #include "pinocchio/algorithm/frames.hpp"
12 #include "pinocchio/algorithm/joint-configuration.hpp"
13 #include "pinocchio/algorithm/geometry.hpp"
14 
15 #include "pinocchio/parsers/sample-models.hpp"
16 
17 #include <boost/test/unit_test.hpp>
18 #include <boost/utility/binary.hpp>
19 
20 using namespace pinocchio;
21 
22 BOOST_AUTO_TEST_SUITE ( BOOST_TEST_MODULE )
23 
24  BOOST_AUTO_TEST_CASE(test_model_subtree)
25  {
26  Model model;
28 
29  Model::JointIndex idx_larm1 = model.getJointId("larm1_joint");
30  BOOST_CHECK(idx_larm1<(Model::JointIndex)model.njoints);
31  Model::IndexVector subtree = model.subtrees[idx_larm1];
32  BOOST_CHECK(subtree.size()==6);
33 
34  for(size_t i=1; i<subtree.size();++i)
35  {
36  BOOST_CHECK(model.parents[subtree[i]]==subtree[i-1]);
37  }
38 
39  // Check that i starts subtree[i]
41  {
42  BOOST_CHECK(model.subtrees[joint_id][0] == joint_id);
43  }
44 
45  // Check that subtree[0] contains all joint ids
47  {
48  BOOST_CHECK(model.subtrees[0][joint_id-1] == joint_id);
49  }
50  }
51 
52  BOOST_AUTO_TEST_CASE(test_model_get_frame_id)
53  {
54  Model model;
56 
57  for(FrameIndex i=0; i<static_cast<FrameIndex>(model.nframes); i++)
58  {
59  BOOST_CHECK_EQUAL(i, model.getFrameId(model.frames[i].name));
60  }
61  BOOST_CHECK_EQUAL(model.nframes, model.getFrameId("NOT_A_FRAME"));
62  }
63 
64  BOOST_AUTO_TEST_CASE(test_model_support)
65  {
66  Model model;
68  const Model::IndexVector support0_ref(1,0);
69  BOOST_CHECK(model.supports[0] == support0_ref);
70 
71  // Check that i ends supports[i]
73  {
74  BOOST_CHECK(model.supports[joint_id].back() == joint_id);
75  Model::IndexVector & support = model.supports[joint_id];
76 
77  size_t current_id = support.size()-2;
78  for(JointIndex parent_id = model.parents[joint_id];
79  parent_id > 0;
80  parent_id = model.parents[parent_id],
81  current_id--)
82  {
83  BOOST_CHECK(parent_id == support[current_id]);
84  }
85  }
86  }
87 
88  BOOST_AUTO_TEST_CASE(test_model_subspace_dimensions)
89  {
90  Model model;
92 
93  // Check that i ends supports[i]
95  {
96  const Model::JointModel & jmodel = model.joints[joint_id];
97 
98  BOOST_CHECK(model.nqs[joint_id] == jmodel.nq());
99  BOOST_CHECK(model.idx_qs[joint_id] == jmodel.idx_q());
100 
101  BOOST_CHECK(model.nvs[joint_id] == jmodel.nv());
102  BOOST_CHECK(model.idx_vs[joint_id] == jmodel.idx_v());
103  }
104  }
105 
107  {
108  Model model;
110 
111  BOOST_CHECK(model == model);
112  }
113 
115  {
116  Model model;
118 
119  BOOST_CHECK(model.cast<double>() == model.cast<double>());
120  BOOST_CHECK(model.cast<double>().cast<long double>() == model.cast<long double>());
121  }
122 
123  BOOST_AUTO_TEST_CASE(test_std_vector_of_Model)
124  {
125  Model model;
126  buildModels::humanoid(model);
127 
129  for(size_t k = 0; k < 20; ++k)
130  {
131  models.push_back(Model());
132  buildModels::humanoid(models.back());
133 
134  BOOST_CHECK(model == models.back());
135  }
136  }
137 
138 #ifdef PINOCCHIO_WITH_HPP_FCL
139  struct AddPrefix {
140  std::string p;
141  std::string operator() (const std::string& n) { return p + n; }
142  Frame operator() (const Frame& _f) { Frame f (_f); f.name = p + f.name; return f; }
143  AddPrefix (const char* _p) : p(_p) {}
144  };
145 
147  {
149  GeometryModel geomManipulator, geomHumanoid;
150 
151  buildModels::manipulator(manipulator);
152  buildModels::manipulatorGeometries(manipulator, geomManipulator);
153  geomManipulator.addAllCollisionPairs();
154  // Add prefix to joint and frame names
155  AddPrefix addManipulatorPrefix ("manipulator/");
156  std::transform (++manipulator.names.begin(), manipulator.names.end(),
157  ++manipulator.names.begin(), addManipulatorPrefix);
158  std::transform (++manipulator.frames.begin(), manipulator.frames.end(),
159  ++manipulator.frames.begin(), addManipulatorPrefix);
160 
161  BOOST_TEST_MESSAGE(manipulator);
162 
163  buildModels::humanoid(humanoid);
164  buildModels::humanoidGeometries(humanoid, geomHumanoid);
165  geomHumanoid.addAllCollisionPairs();
166  // Add prefix to joint and frame names
167  AddPrefix addHumanoidPrefix ("humanoid/");
168  std::transform (++humanoid.names.begin(), humanoid.names.end(),
169  ++humanoid.names.begin(), addHumanoidPrefix);
170  std::transform (++humanoid.frames.begin(), humanoid.frames.end(),
171  ++humanoid.frames.begin(), addHumanoidPrefix);
172 
173  BOOST_TEST_MESSAGE(humanoid);
174 
175  //TODO fix inertia of the base
176  manipulator.inertias[0].setRandom();
177  SE3 aMb = SE3::Random();
178 
179  // First append a model to the universe frame.
180  Model model1;
181  GeometryModel geomModel1;
182  FrameIndex fid = 0;
183  appendModel (humanoid, manipulator, geomHumanoid, geomManipulator, fid,
184  SE3::Identity(), model1, geomModel1);
185 
186  {
187  Model model2 = appendModel(humanoid, manipulator, fid, SE3::Identity());
188  Model model3;
189  appendModel(humanoid, manipulator, fid, SE3::Identity(), model3);
190  BOOST_CHECK(model1 == model2);
191  BOOST_CHECK(model1 == model3);
192  BOOST_CHECK(model2 == model3);
193  }
194 
195  Data data1 (model1);
196  BOOST_CHECK(model1.check(data1));
197 
198  BOOST_TEST_MESSAGE(model1);
199 
200  // Second, append a model to a moving frame.
201  Model model;
202 
203  GeometryModel geomModel;
204  fid = humanoid.addFrame (Frame ("humanoid/add_manipulator",
205  humanoid.getJointId("humanoid/chest2_joint"),
206  humanoid.getFrameId("humanoid/chest2_joint"), aMb,
207  OP_FRAME));
208 
209  appendModel (humanoid, manipulator, geomHumanoid, geomManipulator, fid,
210  SE3::Identity(), model, geomModel);
211 
212  {
213  Model model2 = appendModel(humanoid, manipulator, fid, SE3::Identity());
214  Model model3;
215  appendModel(humanoid, manipulator, fid, SE3::Identity(), model3);
216  BOOST_CHECK(model == model2);
217  BOOST_CHECK(model == model3);
218  BOOST_CHECK(model2 == model3);
219  }
220 
221  BOOST_TEST_MESSAGE(model);
222 
223  Data data (model);
224  BOOST_CHECK(model.check(data));
225 
226  // Check the model
227  BOOST_CHECK_EQUAL(model.getJointId("humanoid/chest2_joint"),
228  model.parents[model.getJointId("manipulator/shoulder1_joint")]);
229 
230  // check the joint order and the inertias
231  JointIndex chest2 = model.getJointId("humanoid/chest2_joint");
232  for (JointIndex jid = 1; jid < chest2; ++jid) {
233  BOOST_TEST_MESSAGE("Checking joint " << jid << " " << model.names[jid]);
234  BOOST_CHECK_EQUAL(model.names[jid], humanoid.names[jid]);
235  BOOST_CHECK_EQUAL(model.inertias[jid], humanoid.inertias[jid]);
236  BOOST_CHECK_EQUAL(model.jointPlacements[jid], humanoid.jointPlacements[jid]);
237  }
238  BOOST_TEST_MESSAGE("Checking joint " << chest2 << " " << model.names[chest2]);
239  BOOST_CHECK_EQUAL(model.names[chest2], humanoid.names[chest2]);
240  BOOST_CHECK_MESSAGE(model.inertias[chest2].isApprox(manipulator.inertias[0].se3Action(aMb) + humanoid.inertias[chest2]),
241  model.inertias[chest2] << " != " << manipulator.inertias[0].se3Action(aMb) + humanoid.inertias[chest2]);
242  BOOST_CHECK_EQUAL(model.jointPlacements[chest2], humanoid.jointPlacements[chest2]);
243 
244  for (JointIndex jid = 1; jid < manipulator.joints.size(); ++jid) {
245  BOOST_TEST_MESSAGE("Checking joint " << chest2+jid << " " << model.names[chest2+jid]);
246  BOOST_CHECK_EQUAL(model.names[chest2+jid], manipulator.names[jid]);
247  BOOST_CHECK_EQUAL(model.inertias[chest2+jid], manipulator.inertias[jid]);
248  if (jid==1)
249  BOOST_CHECK_EQUAL(model.jointPlacements[chest2+jid], aMb*manipulator.jointPlacements[jid]);
250  else
251  BOOST_CHECK_EQUAL(model.jointPlacements[chest2+jid], manipulator.jointPlacements[jid]);
252  }
253  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  BOOST_CHECK_EQUAL(model.names[jid+manipulator.joints.size()-1], humanoid.names[jid]);
256  BOOST_CHECK_EQUAL(model.inertias[jid+manipulator.joints.size()-1], humanoid.inertias[jid]);
257  BOOST_CHECK_EQUAL(model.jointPlacements[jid+manipulator.joints.size()-1], humanoid.jointPlacements[jid]);
258  }
259 
260  // Check the frames
261  for (FrameIndex fid = 1; fid < humanoid.frames.size(); ++fid) {
262  const Frame& frame = humanoid.frames[fid],
263  parent = humanoid.frames[frame.previousFrame];
264  BOOST_CHECK(model.existFrame (frame.name, frame.type));
265  const Frame& nframe = model.frames[model.getFrameId(frame.name, frame.type)],
266  nparent = model.frames[nframe.previousFrame];
267  BOOST_CHECK_EQUAL(parent.name, nparent.name);
268  BOOST_CHECK_EQUAL(frame.placement, nframe.placement);
269  }
270  for (FrameIndex fid = 1; fid < manipulator.frames.size(); ++fid) {
271  const Frame& frame = manipulator.frames[fid],
272  parent = manipulator.frames[frame.previousFrame];
273  BOOST_CHECK(model.existFrame (frame.name, frame.type));
274  const Frame& nframe = model.frames[model.getFrameId(frame.name, frame.type)],
275  nparent = model.frames[nframe.previousFrame];
276  if (frame.previousFrame > 0) {
277  BOOST_CHECK_EQUAL(parent.name, nparent.name);
278  BOOST_CHECK_EQUAL(frame.placement, nframe.placement);
279  }
280  }
281  }
282 #endif
283 
284 BOOST_AUTO_TEST_CASE(test_buildReducedModel_empty)
285 {
286  Model humanoid_model;
287  buildModels::humanoid(humanoid_model);
288 
289  static const std::vector<JointIndex> empty_index_vector;
290 
291  humanoid_model.lowerPositionLimit.head<3>().fill(-1.);
292  humanoid_model.upperPositionLimit.head<3>().fill( 1.);
293 
294  humanoid_model.referenceConfigurations.insert(std::pair<std::string,Eigen::VectorXd>("neutral",neutral(humanoid_model)));
295  Eigen::VectorXd reference_config_humanoid = randomConfiguration(humanoid_model);
296  Model humanoid_copy_model = buildReducedModel(humanoid_model,empty_index_vector,reference_config_humanoid);
297 
298  BOOST_CHECK(humanoid_copy_model.names == humanoid_model.names);
299  BOOST_CHECK(humanoid_copy_model.joints == humanoid_model.joints);
300  BOOST_CHECK(humanoid_copy_model == humanoid_model);
301  BOOST_CHECK(humanoid_copy_model.referenceConfigurations["neutral"].isApprox(neutral(humanoid_copy_model)));
302 
303  const std::vector<JointIndex> empty_joints_to_lock;
304 
305  const Model reduced_humanoid_model = buildReducedModel(humanoid_model,empty_joints_to_lock,reference_config_humanoid);
306  BOOST_CHECK(reduced_humanoid_model.njoints == humanoid_model.njoints);
307  BOOST_CHECK(reduced_humanoid_model.frames == humanoid_model.frames);
308  BOOST_CHECK(reduced_humanoid_model.jointPlacements == humanoid_model.jointPlacements);
309  BOOST_CHECK(reduced_humanoid_model.joints == humanoid_model.joints);
310 
311  for(JointIndex joint_id = 1; joint_id < (JointIndex)reduced_humanoid_model.njoints; ++joint_id)
312  {
313  BOOST_CHECK(reduced_humanoid_model.inertias[joint_id].isApprox(humanoid_model.inertias[joint_id]));
314  }
315 }
316 
317 BOOST_AUTO_TEST_CASE(test_buildReducedModel)
318 {
319  Model humanoid_model;
320  buildModels::humanoid(humanoid_model);
321 
322  static const std::vector<JointIndex> empty_index_vector;
323 
324  humanoid_model.lowerPositionLimit.head<3>().fill(-1.);
325  humanoid_model.upperPositionLimit.head<3>().fill( 1.);
326 
327  humanoid_model.referenceConfigurations.insert(std::pair<std::string,Eigen::VectorXd>("neutral",neutral(humanoid_model)));
328  Eigen::VectorXd reference_config_humanoid = randomConfiguration(humanoid_model);
329  Model humanoid_copy_model = buildReducedModel(humanoid_model,empty_index_vector,reference_config_humanoid);
330 
331  BOOST_CHECK(humanoid_copy_model.names == humanoid_model.names);
332  BOOST_CHECK(humanoid_copy_model.joints == humanoid_model.joints);
333  BOOST_CHECK(humanoid_copy_model == humanoid_model);
334  BOOST_CHECK(humanoid_copy_model.referenceConfigurations["neutral"].isApprox(neutral(humanoid_copy_model)));
335 
336  std::vector<JointIndex> joints_to_lock;
337  const std::string joint1_to_lock = "rarm_shoulder2_joint";
338  joints_to_lock.push_back(humanoid_model.getJointId(joint1_to_lock));
339  const std::string joint2_to_lock = "larm_shoulder2_joint";
340  joints_to_lock.push_back(humanoid_model.getJointId(joint2_to_lock));
341 
342  Model reduced_humanoid_model = buildReducedModel(humanoid_model,joints_to_lock,reference_config_humanoid);
343  BOOST_CHECK(reduced_humanoid_model.njoints == humanoid_model.njoints-(int)joints_to_lock.size());
344 
345  BOOST_CHECK(reduced_humanoid_model != humanoid_model);
346 
347  Model reduced_humanoid_model_other_signature;
348  buildReducedModel(humanoid_model,joints_to_lock,reference_config_humanoid,reduced_humanoid_model_other_signature);
349  BOOST_CHECK(reduced_humanoid_model == reduced_humanoid_model_other_signature);
350 
351  // Check that forward kinematics give same results
352  Data data(humanoid_model), reduced_data(reduced_humanoid_model);
353  Eigen::VectorXd q = reference_config_humanoid;
354  Eigen::VectorXd reduced_q(reduced_humanoid_model.nq);
355 
356  for(JointIndex joint_id = 1; joint_id < (JointIndex)reduced_humanoid_model.njoints; ++joint_id)
357  {
358  const JointIndex reference_joint_id = humanoid_model.getJointId(reduced_humanoid_model.names[joint_id]);
359 
360  reduced_humanoid_model.joints[joint_id].jointConfigSelector(reduced_q) =
361  humanoid_model.joints[reference_joint_id].jointConfigSelector(q);
362  }
363 
364  BOOST_CHECK(reduced_humanoid_model.referenceConfigurations["neutral"].isApprox(neutral(reduced_humanoid_model)));
365 
366  framesForwardKinematics(humanoid_model,data,q);
367  framesForwardKinematics(reduced_humanoid_model,reduced_data,reduced_q);
368 
369  for(size_t frame_id = 0; frame_id < reduced_humanoid_model.frames.size(); ++frame_id)
370  {
371  const Frame & reduced_frame = reduced_humanoid_model.frames[frame_id];
372  switch(reduced_frame.type)
373  {
374  case JOINT:
375  case FIXED_JOINT:
376  {
377  // May not be present in the original model
378  if(humanoid_model.existJointName(reduced_frame.name))
379  {
380  const JointIndex joint_id = humanoid_model.getJointId(reduced_frame.name);
381  BOOST_CHECK(data.oMi[joint_id].isApprox(reduced_data.oMf[frame_id]));
382  }
383  else if(humanoid_model.existFrame(reduced_frame.name))
384  {
385  const FrameIndex humanoid_frame_id = humanoid_model.getFrameId(reduced_frame.name);
386  BOOST_CHECK(data.oMf[humanoid_frame_id].isApprox(reduced_data.oMf[frame_id]));
387  }
388  else
389  {
390  BOOST_CHECK_MESSAGE(false, "The frame " << reduced_frame.name << " is not presend in the humanoid_model");
391  }
392  break;
393  }
394  default:
395  {
396  BOOST_CHECK(humanoid_model.existFrame(reduced_frame.name));
397  const FrameIndex humanoid_frame_id = humanoid_model.getFrameId(reduced_frame.name);
398  BOOST_CHECK(data.oMf[humanoid_frame_id].isApprox(reduced_data.oMf[frame_id]));
399  break;
400  }
401 
402  }
403  }
404 }
405 
406 BOOST_AUTO_TEST_CASE(test_aligned_vector_of_model)
407 {
408  typedef PINOCCHIO_ALIGNED_STD_VECTOR(Model) VectorOfModels;
409 
410  VectorOfModels models;
411  for(size_t k = 0; k < 100; ++k)
412  {
413  models.push_back(Model());
414  buildModels::humanoidRandom(models[k]);
415  }
416 }
417 
418 #ifdef PINOCCHIO_WITH_HPP_FCL
419 BOOST_AUTO_TEST_CASE(test_buildReducedModel_with_geom)
420 {
421  Model humanoid_model;
422  buildModels::humanoid(humanoid_model);
423 
424  humanoid_model.lowerPositionLimit.head<3>().fill(-1.);
425  humanoid_model.upperPositionLimit.head<3>().fill( 1.);
426  const Eigen::VectorXd reference_config_humanoid = randomConfiguration(humanoid_model);
427 
428  GeometryModel humanoid_geometry;
429  buildModels::humanoidGeometries(humanoid_model, humanoid_geometry);
430 
431  static const std::vector<JointIndex> empty_index_vector;
432 
433  Model humanoid_copy_model; GeometryModel humanoid_copy_geometry;
434  buildReducedModel(humanoid_model,humanoid_geometry,empty_index_vector,
435  reference_config_humanoid,humanoid_copy_model,humanoid_copy_geometry);
436 
437  BOOST_CHECK(humanoid_copy_model == humanoid_model);
438  BOOST_CHECK(humanoid_copy_geometry == humanoid_geometry);
439 
440  std::vector<JointIndex> joints_to_lock;
441  const std::string joint1_to_lock = "rarm_shoulder2_joint";
442  joints_to_lock.push_back(humanoid_model.getJointId(joint1_to_lock));
443  const std::string joint2_to_lock = "larm_shoulder2_joint";
444  joints_to_lock.push_back(humanoid_model.getJointId(joint2_to_lock));
445 
446  Model reduced_humanoid_model; GeometryModel reduced_humanoid_geometry;
447  buildReducedModel(humanoid_model,humanoid_geometry,joints_to_lock,
448  reference_config_humanoid,reduced_humanoid_model,reduced_humanoid_geometry);
449 
450  BOOST_CHECK(reduced_humanoid_geometry.ngeoms == humanoid_geometry.ngeoms);
451  BOOST_CHECK(reduced_humanoid_geometry.collisionPairs == humanoid_geometry.collisionPairs);
452  BOOST_CHECK(reduced_humanoid_geometry.geometryObjects.size() == humanoid_geometry.geometryObjects.size());
453 
454  for(Index i = 0; i < humanoid_geometry.geometryObjects.size(); ++i)
455  {
456  const GeometryObject & go1 = humanoid_geometry.geometryObjects[i];
457  const GeometryObject & go2 = reduced_humanoid_geometry.geometryObjects[i];
458  BOOST_CHECK_EQUAL(go1.name, go2.name);
459  BOOST_CHECK_EQUAL(go1.geometry, go2.geometry);
460  BOOST_CHECK_EQUAL(go1.meshPath, go2.meshPath);
461  BOOST_CHECK_EQUAL(go1.meshScale, go2.meshScale);
462  BOOST_CHECK_EQUAL(go1.overrideMaterial, go2.overrideMaterial);
463  BOOST_CHECK_EQUAL(go1.meshColor, go2.meshColor);
464  BOOST_CHECK_EQUAL(go1.meshTexturePath, go2.meshTexturePath);
465  BOOST_CHECK_EQUAL(humanoid_model.frames[go1.parentFrame].name,
466  reduced_humanoid_model.frames[go2.parentFrame].name);
467  }
468 
469  Data data(humanoid_model), reduced_data(reduced_humanoid_model);
470  const Eigen::VectorXd q = reference_config_humanoid;
471  Eigen::VectorXd reduced_q(reduced_humanoid_model.nq);
472 
473  for(JointIndex joint_id = 1; joint_id < (JointIndex)reduced_humanoid_model.njoints; ++joint_id)
474  {
475  const JointIndex reference_joint_id = humanoid_model.getJointId(reduced_humanoid_model.names[joint_id]);
476 
477  reduced_humanoid_model.joints[joint_id].jointConfigSelector(reduced_q) =
478  humanoid_model.joints[reference_joint_id].jointConfigSelector(q);
479  }
480 
481  framesForwardKinematics(humanoid_model,data,q);
482  framesForwardKinematics(reduced_humanoid_model,reduced_data,reduced_q);
483 
484  for(size_t frame_id = 0; frame_id < reduced_humanoid_model.frames.size(); ++frame_id)
485  {
486  const Frame & reduced_frame = reduced_humanoid_model.frames[frame_id];
487  switch(reduced_frame.type)
488  {
489  case JOINT:
490  case FIXED_JOINT:
491  {
492  // May not be present in the original model
493  if(humanoid_model.existJointName(reduced_frame.name))
494  {
495  const JointIndex joint_id = humanoid_model.getJointId(reduced_frame.name);
496  BOOST_CHECK(data.oMi[joint_id].isApprox(reduced_data.oMf[frame_id]));
497  }
498  else if(humanoid_model.existFrame(reduced_frame.name))
499  {
500  const FrameIndex humanoid_frame_id = humanoid_model.getFrameId(reduced_frame.name);
501  BOOST_CHECK(data.oMf[humanoid_frame_id].isApprox(reduced_data.oMf[frame_id]));
502  }
503  else
504  {
505  BOOST_CHECK_MESSAGE(false, "The frame " << reduced_frame.name << " is not presend in the humanoid_model");
506  }
507  break;
508  }
509  default:
510  {
511  BOOST_CHECK(humanoid_model.existFrame(reduced_frame.name));
512  const FrameIndex humanoid_frame_id = humanoid_model.getFrameId(reduced_frame.name);
513  BOOST_CHECK(data.oMf[humanoid_frame_id].isApprox(reduced_data.oMf[frame_id]));
514  break;
515  }
516 
517  }
518  }
519 
520  // Test GeometryObject placements
521  GeometryData geom_data(humanoid_geometry), reduded_geom_data(reduced_humanoid_geometry);
522  updateGeometryPlacements(humanoid_model,data,humanoid_geometry,geom_data);
523  updateGeometryPlacements(reduced_humanoid_model,reduced_data,reduced_humanoid_geometry,reduded_geom_data);
524 
525  BOOST_CHECK(geom_data.oMg.size() == reduded_geom_data.oMg.size());
526  for(FrameIndex i = 0; i < geom_data.oMg.size(); ++i)
527  {
528  BOOST_CHECK(geom_data.oMg[i].isApprox(reduded_geom_data.oMg[i]));
529  }
530 
531  // Test other signature
532  std::vector<GeometryModel> full_geometry_models;
533  full_geometry_models.push_back(humanoid_geometry);
534  full_geometry_models.push_back(humanoid_geometry);
535  full_geometry_models.push_back(humanoid_geometry);
536 
537  std::vector<GeometryModel> reduced_geometry_models;
538 
539  Model reduced_humanoid_model_other_sig;
540  buildReducedModel(humanoid_model,full_geometry_models,joints_to_lock,
541  reference_config_humanoid,reduced_humanoid_model_other_sig,reduced_geometry_models);
542 
543  BOOST_CHECK(reduced_geometry_models[0] == reduced_humanoid_geometry);
544  BOOST_CHECK(reduced_geometry_models[1] == reduced_humanoid_geometry);
545  BOOST_CHECK(reduced_geometry_models[2] == reduced_humanoid_geometry);
546 }
547 #endif // PINOCCHIO_WITH_HPP_FCL
548 
549 BOOST_AUTO_TEST_SUITE_END()
result_of::push_front< V const, T >::type append(T const &t, V const &v)
Append the element T at the front of boost fusion vector V.
Definition: fusion.hpp:24
typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointData) JointDataVector
JointModelVector joints
Model of joint i, encapsulated in a JointModelAccessor.
parent
Definition: lambdas.py:16
ModelTpl< double > Model
void appendModel(const ModelTpl< Scalar, Options, JointCollectionTpl > &modelA, const ModelTpl< Scalar, Options, JointCollectionTpl > &modelB, const FrameIndex frameInModelA, const SE3Tpl< Scalar, Options > &aMb, ModelTpl< Scalar, Options, JointCollectionTpl > &model)
Append a child model into a parent model, after a specific frame given by its index.
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
int njoints
Number of joints.
CollisionPairVector collisionPairs
Vector of collision pairs.
bool check(const AlgorithmCheckerBase< D > &checker=AlgorithmCheckerBase< D >()) const
Check the validity of the attributes of Model with respect to the specification of some algorithms...
std::vector< std::string > names
Name of joint i
NewScalar cast(const Scalar &value)
Definition: cast.hpp:13
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
BOOST_AUTO_TEST_CASE(test_model_subtree)
FrameVector frames
Vector of operational frames registered on the model.
std::vector< int > nvs
Dimension of the joint i tangent subspace.
void randomConfiguration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &lowerLimits, const Eigen::MatrixBase< ConfigVectorIn2 > &upperLimits, const Eigen::MatrixBase< ReturnType > &qout)
Generate a configuration vector uniformly sampled among provided limits.
data
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
void humanoid(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a 28-DOF kinematic chain of a floating humanoid robot.
std::vector< IndexVector > subtrees
Vector of joint subtrees. subtree[j] corresponds to the subtree supported by the joint j...
ConfigVectorMap referenceConfigurations
Map of reference configurations, indexed by user given names.
FrameType type
Type of the frame.
int nframes
Number of operational frames.
bool existJointName(const std::string &name) const
Check if a joint given by its name exists.
std::vector< int > nqs
Dimension of the joint i configuration subspace.
GeometryObjectVector geometryObjects
Vector of GeometryObjects used for collision computations.
std::vector< int > idx_qs
Starting index of the joint i in the configuration space.
std::vector< Index > IndexVector
pinocchio::JointIndex JointIndex
FrameIndex getFrameId(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
Returns the index of a frame given by its name.
bool existFrame(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
Checks if a frame given by its name exists.
Index ngeoms
The number of GeometryObjects.
void addAllCollisionPairs()
Add all possible collision pairs.
FrameIndex addFrame(const Frame &frame, const bool append_inertia=true)
Adds a frame to the kinematic tree. The inertia stored within the frame will be happened to the inert...
SE3 placement
Placement of the frame wrt the parent joint.
Main pinocchio namespace.
Definition: timings.cpp:30
std::vector< int > idx_vs
Starting index of the joint i in the tangent configuration space.
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
Return the neutral configuration element related to the model configuration space.
std::vector< JointIndex > parents
Joint parent of joint i, denoted li (li==parents[i]).
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
std::size_t Index
std::string name
Name of the frame.
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
void updateGeometryPlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data, const Eigen::MatrixBase< ConfigVectorType > &q)
Apply a forward kinematics and update the placement of the geometry objects.
std::vector< IndexVector > supports
Vector of joint supports. supports[j] corresponds to the collection of all joints located on the path...
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
Definition: conversions.cpp:14
JointCollectionTpl & model
FrameIndex previousFrame
Index of the previous frame.
int nq
Dimension of the configuration vector representation.
void framesForwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
First calls the forwardKinematics on the model, then computes the placement of each frame...
void manipulator(ModelTpl< Scalar, Options, JointCollectionTpl > &model)
Create a 6-DOF kinematic chain shoulder-elbow-wrist.
void buildReducedModel(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, std::vector< JointIndex > list_of_joints_to_lock, const Eigen::MatrixBase< ConfigVectorType > &reference_configuration, ModelTpl< Scalar, Options, JointCollectionTpl > &reduced_model)
Build a reduced model from a given input model and a list of joint to lock.
ModelTpl< NewScalar, Options, JointCollectionTpl > cast() const
void fill(Eigen::Ref< MatType > mat, const typename MatType::Scalar &value)


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:04