sdf.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2021 CNRS INRIA
3 //
4 
5 #include <iostream>
6 #include <fstream>
7 #include <streambuf>
8 
11 
12 #include <boost/test/unit_test.hpp>
13 
14 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
15 
17 {
18  const std::string filename =
20  + std::string("/example-robot-data/robots/cassie_description/robots/cassie.sdf");
21  const std::string dir = PINOCCHIO_MODEL_DIR;
22 
24  const std::string rootLinkName = "pelvis";
27  pinocchio::GeometryModel geomModel;
28  pinocchio::sdf::buildGeom(model, filename, pinocchio::COLLISION, geomModel, rootLinkName, dir);
29 
30  BOOST_CHECK(model.nq == 62);
31 }
32 
33 BOOST_AUTO_TEST_CASE(build_model_with_joint)
34 {
35 
36  const std::string filename =
38  + std::string("/example-robot-data/robots/cassie_description/robots/cassie.sdf");
39  const std::string dir = PINOCCHIO_MODEL_DIR;
40  const std::string rootLinkName = "pelvis";
45  pinocchio::GeometryModel geomModel;
46  pinocchio::sdf::buildGeom(model, filename, pinocchio::COLLISION, geomModel, rootLinkName, dir);
47 
48  BOOST_CHECK(model.nq == 69);
49 }
50 
51 BOOST_AUTO_TEST_CASE(build_model_without_rootLink)
52 {
53 
54  const std::string filename =
56  + std::string("/example-robot-data/robots/cassie_description/robots/cassie.sdf");
57  const std::string dir = PINOCCHIO_MODEL_DIR;
58  const std::string rootLinkName = "";
63  pinocchio::GeometryModel geomModel;
64  pinocchio::sdf::buildGeom(model, filename, pinocchio::COLLISION, geomModel, rootLinkName, dir);
65 
66  BOOST_CHECK(model.nq == 69);
67 }
68 
69 BOOST_AUTO_TEST_CASE(build_model_with_root_joint_name)
70 {
71  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.sdf");
72  const std::string dir = PINOCCHIO_MODEL_DIR;
73  const std::string rootLinkName = "WAIST_LINK0";
78  BOOST_CHECK(model.names[1] == "root_joint");
79 
80  pinocchio::Model model_name;
81  const std::string name_ = "freeFlyer_joint";
84  filename, pinocchio::JointModelFreeFlyer(), name_, model_name, contact_models_name,
85  rootLinkName);
86  BOOST_CHECK(model_name.names[1] == name_);
87 }
88 
89 BOOST_AUTO_TEST_CASE(compare_model_with_urdf)
90 {
91  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.sdf");
92  const std::string dir = PINOCCHIO_MODEL_DIR;
93 
94  pinocchio::Model model_sdf;
95  const std::string rootLinkName = "WAIST_LINK0";
98  filename, pinocchio::JointModelFreeFlyer(), model_sdf, contact_models, rootLinkName);
99  pinocchio::GeometryModel geomModel;
101  model_sdf, filename, pinocchio::COLLISION, geomModel, rootLinkName, dir);
102 
103  const std::string filename_urdf = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.urdf");
104  const std::string dir_urdf = PINOCCHIO_MODEL_DIR;
105  pinocchio::Model model_urdf;
106  pinocchio::urdf::buildModel(filename_urdf, pinocchio::JointModelFreeFlyer(), model_urdf);
107 
108  typedef typename pinocchio::Model::ConfigVectorMap ConfigVectorMap;
109  // Compare models
110  // BOOST_CHECK(model_urdf==model);
111 
112  BOOST_CHECK(model_urdf.nq == model_sdf.nq);
113  BOOST_CHECK(model_urdf.nv == model_sdf.nv);
114  BOOST_CHECK(model_urdf.njoints == model_sdf.njoints);
115  BOOST_CHECK(model_urdf.nbodies == model_sdf.nbodies);
116  BOOST_CHECK(model_urdf.nframes == model_sdf.nframes);
117  BOOST_CHECK(model_urdf.parents == model_sdf.parents);
118  BOOST_CHECK(model_urdf.children == model_sdf.children);
119  BOOST_CHECK(model_urdf.names == model_sdf.names);
120  BOOST_CHECK(model_urdf.subtrees == model_sdf.subtrees);
121  BOOST_CHECK(model_urdf.gravity == model_sdf.gravity);
122  BOOST_CHECK(model_urdf.name == model_sdf.name);
123  BOOST_CHECK(model_urdf.idx_qs == model_sdf.idx_qs);
124  BOOST_CHECK(model_urdf.nqs == model_sdf.nqs);
125  BOOST_CHECK(model_urdf.idx_vs == model_sdf.idx_vs);
126  BOOST_CHECK(model_urdf.nvs == model_sdf.nvs);
127  BOOST_CHECK(
128  model_urdf.referenceConfigurations.size() == model_sdf.referenceConfigurations.size());
129 
130  typename ConfigVectorMap::const_iterator it = model_sdf.referenceConfigurations.begin();
131  typename ConfigVectorMap::const_iterator it_model_urdf =
132  model_urdf.referenceConfigurations.begin();
133  for (long k = 0; k < (long)model_sdf.referenceConfigurations.size(); ++k)
134  {
135  std::advance(it, k);
136  std::advance(it_model_urdf, k);
137  BOOST_CHECK(it->second.size() == it_model_urdf->second.size());
138  BOOST_CHECK(it->second == it_model_urdf->second);
139  }
140  BOOST_CHECK(model_urdf.armature.size() == model_sdf.armature.size());
141 
142  BOOST_CHECK(model_urdf.armature == model_sdf.armature);
143  BOOST_CHECK(model_urdf.friction.size() == model_sdf.friction.size());
144  BOOST_CHECK(model_urdf.friction == model_sdf.friction);
145 
146  BOOST_CHECK(model_urdf.damping.size() == model_sdf.damping.size());
147 
148  BOOST_CHECK(model_urdf.damping == model_sdf.damping);
149 
150  BOOST_CHECK(model_urdf.rotorInertia.size() == model_sdf.rotorInertia.size());
151 
152  BOOST_CHECK(model_urdf.rotorInertia == model_sdf.rotorInertia);
153 
154  BOOST_CHECK(model_urdf.rotorGearRatio.size() == model_sdf.rotorGearRatio.size());
155 
156  BOOST_CHECK(model_urdf.rotorGearRatio == model_sdf.rotorGearRatio);
157 
158  BOOST_CHECK(model_urdf.effortLimit.size() == model_sdf.effortLimit.size());
159  BOOST_CHECK(model_urdf.effortLimit == model_sdf.effortLimit);
160 
161  BOOST_CHECK(model_urdf.velocityLimit.size() == model_sdf.velocityLimit.size());
162 
163  BOOST_CHECK(model_urdf.velocityLimit == model_sdf.velocityLimit);
164  BOOST_CHECK(model_urdf.lowerPositionLimit.size() == model_sdf.lowerPositionLimit.size());
165  BOOST_CHECK(model_urdf.lowerPositionLimit == model_sdf.lowerPositionLimit);
166 
167  BOOST_CHECK(model_urdf.upperPositionLimit.size() == model_sdf.upperPositionLimit.size());
168  BOOST_CHECK(model_urdf.upperPositionLimit == model_sdf.upperPositionLimit);
169 
170  for (size_t k = 1; k < model_sdf.inertias.size(); ++k)
171  {
172  BOOST_CHECK(model_urdf.inertias[k].isApprox(model_sdf.inertias[k]));
173  }
174 
175  for (size_t k = 1; k < model_urdf.jointPlacements.size(); ++k)
176  {
177  BOOST_CHECK(model_urdf.jointPlacements[k] == model_sdf.jointPlacements[k]);
178  }
179 
180  BOOST_CHECK(model_urdf.joints == model_sdf.joints);
181 
182  BOOST_CHECK(model_urdf.frames.size() == model_sdf.frames.size());
183  for (size_t k = 1; k < model_urdf.frames.size(); ++k)
184  {
185  BOOST_CHECK(model_urdf.frames[k] == model_sdf.frames[k]);
186  }
187 }
188 
189 BOOST_AUTO_TEST_CASE(compare_model_in_version_1_6)
190 {
191  // Read file as XML
192  std::string filestr("<sdf version=\"1.6\">"
193  " <model name=\"parallelogram\">"
194  " <link name=\"link_A1\">"
195  " <pose>0 0 0 0 0 0</pose>"
196  " <inertial>"
197  " <pose>0 0 0 0 0 0</pose>"
198  " <mass>10</mass>"
199  " <inertia>"
200  " <ixx>0.008416666667</ixx>"
201  " <iyy>0.841666666667</iyy>"
202  " <izz>0.833416666667</izz>"
203  " <ixy>0.</ixy>"
204  " <ixz>0.</ixz>"
205  " <iyz>0.</iyz>"
206  " </inertia>"
207  " </inertial>"
208  " <visual name=\"link_A1_visual\">"
209  " <geometry>"
210  " <cylinder>"
211  " <length>1.0</length>"
212  " <radius>0.05</radius>"
213  " </cylinder>"
214  " </geometry>"
215  " </visual>"
216  " </link>"
217  " <link name=\"link_B1\">"
218  " <pose>-0.2 0 0 0 0 0</pose>"
219  " <inertial>"
220  " <pose>0 0 0 0 0 0</pose>"
221  " <mass>5</mass>"
222  " <inertia>"
223  " <ixx>0.0042083333333</ixx>"
224  " <iyy>0.1541666666667</iyy>"
225  " <izz>0.1500416666667</izz>"
226  " <ixy>0</ixy>"
227  " <ixz>0</ixz>"
228  " <iyz>0</iyz>"
229  " </inertia>"
230  " </inertial>"
231  " <visual name=\"link_B1_visual\">"
232  " <geometry>"
233  " <cylinder>"
234  " <length>0.6</length>"
235  " <radius>0.05</radius>"
236  " </cylinder>"
237  " </geometry>"
238  " </visual>"
239  " </link>"
240  " <link name=\"link_A2\">"
241  " <pose>0.6 0 0 0 0 0</pose>"
242  " <inertial>"
243  " <pose>0 0 0 0 0 0</pose>"
244  " <mass>10</mass>"
245  " <inertia>"
246  " <ixx>0.008416666667</ixx>"
247  " <iyy>0.841666666667</iyy>"
248  " <izz>0.833416666667</izz>"
249  " <ixy>0.</ixy>"
250  " <ixz>0.</ixz>"
251  " <iyz>0.</iyz>"
252  " </inertia>"
253  " </inertial>"
254  " <visual name=\"link_A2_visual\">"
255  " <geometry>"
256  " <cylinder>"
257  " <length>1.0</length>"
258  " <radius>0.05</radius>"
259  " </cylinder>"
260  " </geometry>"
261  " </visual>"
262  " </link>"
263  " <link name=\"link_B2\">"
264  " <pose>0.8 0 0 0 0 0</pose>"
265  " <inertial>"
266  " <pose>0 0 0 0 0 0</pose>"
267  " <mass>5</mass>"
268  " <inertia>"
269  " <ixx>0.0042083333333</ixx>"
270  " <iyy>0.1541666666667</iyy>"
271  " <izz>0.1500416666667</izz>"
272  " <ixy>0</ixy>"
273  " <ixz>0</ixz>"
274  " <iyz>0</iyz>"
275  " </inertia>"
276  " </inertial>"
277  " <visual name=\"link_B2_visual\">"
278  " <geometry>"
279  " <cylinder>"
280  " <length>0.6</length>"
281  " <radius>0.05</radius>"
282  " </cylinder>"
283  " </geometry>"
284  " </visual>"
285  " </link>"
286  " <joint name=\"joint_B1\" type=\"revolute\">"
287  " <pose>-0.3 0 0 0 0 0</pose>"
288  " <child>link_B1</child>"
289  " <parent>link_A1</parent>"
290  " <axis>"
291  " <xyz>0 1 0</xyz>"
292  " <use_parent_model_frame>1</use_parent_model_frame>"
293  " </axis>"
294  " </joint>"
295  " <joint name=\"joint_A2\" type=\"revolute\">"
296  " <pose>-0.5 0 0 0 0 0</pose>"
297  " <child>link_A2</child>"
298  " <parent>link_B1</parent>"
299  " <axis>"
300  " <xyz>0 1 0</xyz>"
301  " <use_parent_model_frame>1</use_parent_model_frame>"
302  " </axis>"
303  " </joint>"
304  " <joint name=\"joint_B2\" type=\"revolute\">"
305  " <pose>-0.3 0 0 0 0 0</pose>"
306  " <child>link_B2</child>"
307  " <parent>link_A1</parent>"
308  " <axis>"
309  " <xyz>0 1 0</xyz>"
310  " <use_parent_model_frame>1</use_parent_model_frame>"
311  " </axis>"
312  " </joint>"
313  " <joint name=\"joint_B3\" type=\"revolute\">"
314  " <pose>0.5 0 0 0 0 0</pose>"
315  " <child>link_A2</child>"
316  " <parent>link_B2</parent>"
317  " <axis>"
318  " <xyz>0 1 0</xyz>"
319  " <use_parent_model_frame>1</use_parent_model_frame>"
320  " </axis>"
321  " </joint>"
322  " </model>"
323  "</sdf>");
324 
325  double height = 0.1;
326  double width = 0.01;
327 
328  double mass_link_A = 10.;
329  double length_link_A = 1.;
330 
331  double mass_link_B = 5.;
332  double length_link_B = .6;
333 
334  pinocchio::Inertia inertia_link_A_2 =
336 
338  placement_center_link_A.translation() = Eigen::Vector3d::UnitX() * length_link_A / 2.;
339 
340  pinocchio::SE3 placement_center_link_A_minus = pinocchio::SE3::Identity();
341  placement_center_link_A_minus.translation() = -Eigen::Vector3d::UnitX() * length_link_A / 2;
342 
344  placement_shape_A.rotation() = Eigen::Quaterniond::Quaternion::FromTwoVectors(
345  Eigen::Vector3d::UnitZ(), Eigen::Vector3d::UnitX())
346  .matrix();
347 
351  placement_center_link_B.translation() = Eigen::Vector3d::UnitX() * length_link_B / 2.;
353  placement_shape_B.rotation() =
354  Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d::UnitZ(), Eigen::Vector3d::UnitX()).matrix();
355 
358 
360  joint1_placement.translation() = -Eigen::Vector3d::UnitX() * length_link_A / 2;
364 
366  joint2_placement.translation() = Eigen::Vector3d::UnitX() * length_link_B;
368  model.addJoint(joint1_id, pinocchio::JointModelRY(), joint2_placement, "link_A2");
369  model.appendBodyToJoint(joint2_id, inertia_link_A_2, placement_center_link_A);
370 
372  joint3_placement.translation() = Eigen::Vector3d::UnitX() * length_link_A / 2;
376 
377  pinocchio::SE3 joint4_placement = pinocchio::SE3::Identity();
378  joint4_placement.translation() = Eigen::Vector3d::UnitX() * length_link_B;
379  pinocchio::JointIndex joint4_id =
380  model.addJoint(joint3_id, pinocchio::JointModelRY(), joint4_placement, "link_B3");
381  model.appendBodyToJoint(joint4_id, inertia_link_A_2, placement_center_link_A_minus);
382 
383  pinocchio::Model model_sdf;
386 
387  BOOST_CHECK(model.nq == model_sdf.nq);
388  BOOST_CHECK(model.nv == model_sdf.nv);
389  BOOST_CHECK(model.njoints == model_sdf.njoints);
390  BOOST_CHECK(model.nbodies == model_sdf.nbodies);
391 
392  BOOST_CHECK(model.parents == model_sdf.parents);
393 
394  BOOST_CHECK(model.children == model_sdf.children);
395  BOOST_CHECK(model.subtrees == model_sdf.subtrees);
396 
397  BOOST_CHECK(model.gravity == model_sdf.gravity);
398  BOOST_CHECK(model.idx_qs == model_sdf.idx_qs);
399 
400  BOOST_CHECK(model.nqs == model_sdf.nqs);
401  BOOST_CHECK(model.idx_vs == model_sdf.idx_vs);
402  BOOST_CHECK(model.nvs == model_sdf.nvs);
403 
404  for (std::size_t k = 1; k < model.jointPlacements.size(); k++)
405  {
406  BOOST_CHECK(model.jointPlacements[k].isApprox(model_sdf.jointPlacements[k]));
407  }
408 
409  for (std::size_t k = 1; k < model.inertias.size(); k++)
410  {
411  BOOST_CHECK(model.inertias[k].isApprox(model_sdf.inertias[k]));
412  }
413 
414  BOOST_CHECK(contact_models.size() == 1);
415  BOOST_CHECK(contact_models[0].joint1_id == 4);
416  BOOST_CHECK(contact_models[0].joint1_placement == placement_center_link_A_minus);
417  BOOST_CHECK(contact_models[0].joint2_id == 2);
419  BOOST_CHECK(contact_models[0].type == pinocchio::CONTACT_6D);
420  BOOST_CHECK(contact_models[0].reference_frame == pinocchio::LOCAL);
421 }
422 
423 BOOST_AUTO_TEST_SUITE_END()
pinocchio::InertiaTpl< context::Scalar, context::Options >
simulation-closed-kinematic-chains.mass_link_B
float mass_link_B
Definition: simulation-closed-kinematic-chains.py:18
common_symbols.type
type
Definition: common_symbols.py:35
pinocchio::ModelTpl::names
std::vector< std::string > names
Name of the joints.
Definition: multibody/model.hpp:142
pinocchio::ModelTpl::frames
FrameVector frames
Vector of operational frames registered on the model.
Definition: multibody/model.hpp:176
simulation-closed-kinematic-chains.length_link_B
float length_link_B
Definition: simulation-closed-kinematic-chains.py:19
cassie-simulation.joint2_placement
joint2_placement
Definition: cassie-simulation.py:31
simulation-closed-kinematic-chains.length_link_A
float length_link_A
Definition: simulation-closed-kinematic-chains.py:15
pinocchio::ModelTpl::jointPlacements
SE3Vector jointPlacements
Vector of joint placements: placement of a joint i wrt its parent joint frame.
Definition: multibody/model.hpp:116
pinocchio::ModelTpl::lowerPositionLimit
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
Definition: multibody/model.hpp:170
width
FCL_REAL width() const
pinocchio::SE3Tpl
Definition: context/casadi.hpp:29
simulation-closed-kinematic-chains.inertia_link_B
inertia_link_B
Definition: simulation-closed-kinematic-chains.py:30
pinocchio::sdf::buildModelFromXML
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModelFromXML(const std::string &xmlStream, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, ModelTpl< Scalar, Options, JointCollectionTpl > &model, PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) &contact_models, const std::string &rootLinkName="", const std::vector< std::string > &parentGuidance={}, const bool verbose=false)
Build the model from an XML stream with a particular joint as root of the model tree inside the model...
model.hpp
pinocchio::sdf::buildGeom
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geomModel, const std::string &rootLinkName="", const std::vector< std::string > &packageDirs=std::vector< std::string >(), ::hpp::fcl::MeshLoaderPtr meshLoader=::hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a SDF file. Search for meshes in the directories specified by the user f...
simulation-closed-kinematic-chains.placement_center_link_A
placement_center_link_A
Definition: simulation-closed-kinematic-chains.py:23
simulation-closed-kinematic-chains.joint1_placement
joint1_placement
Definition: simulation-closed-kinematic-chains.py:54
pinocchio::ModelTpl::joints
JointModelVector joints
Vector of joint models.
Definition: multibody/model.hpp:119
pinocchio::JointModelFreeFlyerTpl
Definition: multibody/joint/fwd.hpp:110
pinocchio::ModelTpl::name
std::string name
Model name.
Definition: multibody/model.hpp:197
pinocchio::CONTACT_6D
@ CONTACT_6D
Point contact model.
Definition: algorithm/contact-info.hpp:22
pinocchio::sdf::buildModel
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, ModelTpl< Scalar, Options, JointCollectionTpl > &model, PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) &contact_models, const std::string &rootLinkName="", const std::vector< std::string > &parentGuidance={}, const bool verbose=false)
Build the model from a SDF file with a particular joint as root of the model tree inside the model gi...
pinocchio::ModelTpl::rotorInertia
TangentVectorType rotorInertia
Vector of rotor inertia parameters.
Definition: multibody/model.hpp:152
height
FCL_REAL height() const
simulation-closed-kinematic-chains.mass_link_A
float mass_link_A
Definition: simulation-closed-kinematic-chains.py:14
anymal-simulation.model
model
Definition: anymal-simulation.py:8
pinocchio::ModelTpl::inertias
InertiaVector inertias
Vector of spatial inertias supported by each joint.
Definition: multibody/model.hpp:113
pinocchio::SE3Tpl::translation
ConstLinearRef translation() const
Definition: se3-base.hpp:52
pinocchio::ModelTpl::referenceConfigurations
ConfigVectorMap referenceConfigurations
Map of reference configurations, indexed by user given names.
Definition: multibody/model.hpp:145
pinocchio::ModelTpl::subtrees
std::vector< IndexVector > subtrees
Vector of joint subtrees. subtree[j] corresponds to the subtree supported by the joint j....
Definition: multibody/model.hpp:188
sdf.hpp
pinocchio::ModelTpl::nqs
std::vector< int > nqs
Vector of dimension of the joint configuration subspace.
Definition: multibody/model.hpp:125
pinocchio::ModelTpl::nvs
std::vector< int > nvs
Dimension of the *i*th joint tangent subspace.
Definition: multibody/model.hpp:131
pinocchio::RigidConstraintModelTpl
Definition: algorithm/constraints/fwd.hpp:14
pinocchio::ModelTpl::children
std::vector< IndexVector > children
Vector of children index. Chidren of the i*th joint, denoted *mu(i) corresponds to the set (i==parent...
Definition: multibody/model.hpp:139
pinocchio::ModelTpl::idx_qs
std::vector< int > idx_qs
Vector of starting index of the *i*th joint in the configuration space.
Definition: multibody/model.hpp:122
filename
filename
pinocchio::ModelTpl::rotorGearRatio
TangentVectorType rotorGearRatio
Vector of rotor gear ratio parameters.
Definition: multibody/model.hpp:155
pinocchio::ModelTpl::armature
VectorXs armature
Vector of armature values expressed at the joint level This vector may contain the contribution of ro...
Definition: multibody/model.hpp:149
pinocchio::urdf::buildModel
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
pinocchio::ModelTpl::nframes
int nframes
Number of operational frames.
Definition: multibody/model.hpp:110
pinocchio::ModelTpl::velocityLimit
TangentVectorType velocityLimit
Vector of maximal joint velocities.
Definition: multibody/model.hpp:167
simulation-closed-kinematic-chains.placement_shape_B
placement_shape_B
Definition: simulation-closed-kinematic-chains.py:33
pinocchio::ModelTpl::nbodies
int nbodies
Number of bodies.
Definition: multibody/model.hpp:107
pinocchio::ModelTpl::friction
TangentVectorType friction
Vector of joint friction parameters.
Definition: multibody/model.hpp:158
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR
#define PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(T)
Definition: container/aligned-vector.hpp:13
inverse-kinematics-3d.it
int it
Definition: inverse-kinematics-3d.py:17
pinocchio::JointModelRevoluteTpl
Definition: multibody/joint/fwd.hpp:33
pinocchio::ModelTpl::gravity
Motion gravity
Spatial gravity of the model.
Definition: multibody/model.hpp:191
simulation-closed-kinematic-chains.joint1_id
joint1_id
Definition: simulation-closed-kinematic-chains.py:56
simulation-closed-kinematic-chains.placement_shape_A
placement_shape_A
Definition: simulation-closed-kinematic-chains.py:25
simulation-closed-kinematic-chains.joint2_id
joint2_id
Definition: simulation-closed-kinematic-chains.py:66
pinocchio::ModelTpl::damping
TangentVectorType damping
Vector of joint damping parameters.
Definition: multibody/model.hpp:161
pinocchio::ModelTpl::nv
int nv
Dimension of the velocity vector space.
Definition: multibody/model.hpp:101
pinocchio::ModelTpl::ConfigVectorMap
std::map< std::string, ConfigVectorType > ConfigVectorMap
Map between a string (key) and a configuration vector.
Definition: multibody/model.hpp:90
pinocchio::SE3Tpl::Identity
static SE3Tpl Identity()
Definition: spatial/se3-tpl.hpp:136
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
simulation-closed-kinematic-chains.joint3_id
joint3_id
Definition: simulation-closed-kinematic-chains.py:74
pinocchio::ModelTpl::effortLimit
TangentVectorType effortLimit
Vector of maximal joint torques.
Definition: multibody/model.hpp:164
pinocchio::InertiaTpl< context::Scalar, context::Options >::FromBox
static InertiaTpl FromBox(const Scalar mass, const Scalar x, const Scalar y, const Scalar z)
Computes the Inertia of a box defined by its mass and main dimensions (x,y,z).
Definition: spatial/inertia.hpp:423
pinocchio::GeometryModel
Definition: multibody/geometry.hpp:50
pinocchio::ModelTpl::parents
std::vector< JointIndex > parents
Vector of parent joint indexes. The parent of joint i, denoted li, corresponds to li==parents[i].
Definition: multibody/model.hpp:135
contact-cholesky.contact_models
list contact_models
Definition: contact-cholesky.py:22
pinocchio::COLLISION
@ COLLISION
Definition: multibody/geometry-object.hpp:27
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(build_model)
Definition: sdf.cpp:16
simulation-closed-kinematic-chains.joint3_placement
joint3_placement
Definition: simulation-closed-kinematic-chains.py:72
pinocchio::ModelTpl::idx_vs
std::vector< int > idx_vs
Starting index of the *i*th joint in the tangent configuration space.
Definition: multibody/model.hpp:128
simulation-closed-kinematic-chains.placement_center_link_B
placement_center_link_B
Definition: simulation-closed-kinematic-chains.py:31
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::ModelTpl::upperPositionLimit
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
Definition: multibody/model.hpp:173
pinocchio::ModelTpl::nq
int nq
Dimension of the configuration vector representation.
Definition: multibody/model.hpp:98
simulation-closed-kinematic-chains.base_joint_id
int base_joint_id
Definition: simulation-closed-kinematic-chains.py:44
pinocchio::ModelTpl::njoints
int njoints
Number of joints.
Definition: multibody/model.hpp:104
PINOCCHIO_MODEL_DIR
#define PINOCCHIO_MODEL_DIR
Definition: build-reduced-model.cpp:11
pinocchio::LOCAL
@ LOCAL
Definition: multibody/fwd.hpp:50


pinocchio
Author(s):
autogenerated on Sun Dec 22 2024 03:41:12