multibody/model.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2020 CNRS INRIA
3 // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
6 #ifndef __pinocchio_multibody_model_hpp__
7 #define __pinocchio_multibody_model_hpp__
8 
14 
18 
20 
22 
23 #include <iostream>
24 #include <map>
25 #include <iterator>
26 
27 namespace pinocchio
28 {
29 
30  template<typename _Scalar, int _Options, template<typename,int> class JointCollectionTpl>
31  struct ModelTpl
32  : serialization::Serializable< ModelTpl<_Scalar,_Options,JointCollectionTpl> >
33  {
34  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
35 
36  typedef _Scalar Scalar;
37  enum { Options = _Options };
38 
39  typedef JointCollectionTpl<Scalar,Options> JointCollection;
41 
47 
52  typedef std::vector<Index> IndexVector;
53 
56 
57  typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointModel) JointModelVector;
58  typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointData) JointDataVector;
59 
60  typedef PINOCCHIO_ALIGNED_STD_VECTOR(Frame) FrameVector;
61 
62  typedef Eigen::Matrix<Scalar,Eigen::Dynamic,1,Options> VectorXs;
63  typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
64 
67 
69  typedef std::map<std::string, ConfigVectorType> ConfigVectorMap;
70 
74 
76  int nq;
77 
79  int nv;
80 
82  int njoints;
83 
85  int nbodies;
86 
88  int nframes;
89 
92 
94  PINOCCHIO_ALIGNED_STD_VECTOR(SE3) jointPlacements;
95 
97  JointModelVector joints;
98 
100  std::vector<int> idx_qs;
101 
103  std::vector<int> nqs;
104 
106  std::vector<int> idx_vs;
107 
109  std::vector<int> nvs;
110 
112  std::vector<JointIndex> parents;
113 
115  std::vector<std::string> names;
116 
119 
122 
125 
128 
131 
134 
137 
140 
143 
145  FrameVector frames;
146 
152  std::vector<IndexVector> supports;
153 
157  std::vector<IndexVector> subtrees;
158 
161 
163  static const Vector3 gravity981;
164 
166  std::string name;
167 
170  : nq(0)
171  , nv(0)
172  , njoints(1)
173  , nbodies(1)
174  , nframes(0)
175  , inertias(1, Inertia::Zero())
176  , jointPlacements(1, SE3::Identity())
177  , joints(1)
178  , idx_qs(1,0)
179  , nqs(1,0)
180  , idx_vs(1,0)
181  , nvs(1,0)
182  , parents(1, 0)
183  , names(1)
184  , supports(1,IndexVector(1,0))
185  , subtrees(1)
186  , gravity(gravity981,Vector3::Zero())
187  {
188  names[0] = "universe"; // Should be "universe joint (trivial)"
189  // FIXME Should the universe joint be a FIXED_JOINT even if it is
190  // in the list of joints ? See comment in definition of
191  // Model::addJointFrame and Model::addBodyFrame
192  addFrame(Frame("universe", 0, 0, SE3::Identity(), FIXED_JOINT));
193  }
194  ~ModelTpl() {} // std::cout << "Destroy model" << std::endl; }
195 
197  template<typename NewScalar>
199  {
201  ReturnType res;
202  res.nq = nq; res.nv = nv;
203  res.njoints = njoints;
204  res.nbodies = nbodies;
205  res.nframes = nframes;
206  res.parents = parents;
207  res.names = names;
208  res.supports = supports;
209  res.subtrees = subtrees;
210  res.gravity = gravity.template cast<NewScalar>();
211  res.name = name;
212 
213  res.idx_qs = idx_qs;
214  res.nqs = nqs;
215  res.idx_vs = idx_vs;
216  res.nvs = nvs;
217 
218  // Eigen Vectors
219  res.rotorInertia = rotorInertia.template cast<NewScalar>();
220  res.rotorGearRatio = rotorGearRatio.template cast<NewScalar>();
221  res.friction = friction.template cast<NewScalar>();
222  res.damping = damping.template cast<NewScalar>();
223  res.effortLimit = effortLimit.template cast<NewScalar>();
224  res.velocityLimit = velocityLimit.template cast<NewScalar>();
225  res.lowerPositionLimit = lowerPositionLimit.template cast<NewScalar>();
226  res.upperPositionLimit = upperPositionLimit.template cast<NewScalar>();
227 
228  typename ConfigVectorMap::const_iterator it;
229  for (it = referenceConfigurations.begin();
230  it != referenceConfigurations.end(); it++ )
231  {
232  res.referenceConfigurations.insert(std::make_pair(it->first, it->second.template cast<NewScalar>()));
233  }
234 
235  // reserve vectors
236  res.inertias.resize(inertias.size());
237  res.jointPlacements.resize(jointPlacements.size());
238  res.joints.resize(joints.size());
239  res.frames.resize(frames.size());
240 
242  for(size_t k = 0; k < joints.size(); ++k)
243  {
244  res.inertias[k] = inertias[k].template cast<NewScalar>();
245  res.jointPlacements[k] = jointPlacements[k].template cast<NewScalar>();
246  res.joints[k] = joints[k].template cast<NewScalar>();
247  }
248 
249  for(size_t k = 0; k < frames.size(); ++k)
250  {
251  res.frames[k] = frames[k].template cast<NewScalar>();
252  }
253 
254  return res;
255  }
256 
262  bool operator==(const ModelTpl & other) const
263  {
264  bool res =
265  other.nq == nq
266  && other.nv == nv
267  && other.njoints == njoints
268  && other.nbodies == nbodies
269  && other.nframes == nframes
270  && other.parents == parents
271  && other.names == names
272  && other.subtrees == subtrees
273  && other.gravity == gravity
274  && other.name == name;
275 
276  res &=
277  other.idx_qs == idx_qs
278  && other.nqs == nqs
279  && other.idx_vs == idx_vs
280  && other.nvs == nvs;
281 
282  if(other.referenceConfigurations.size() != referenceConfigurations.size())
283  return false;
284 
285  typename ConfigVectorMap::const_iterator it = referenceConfigurations.begin();
286  typename ConfigVectorMap::const_iterator it_other = other.referenceConfigurations.begin();
287  for(long k = 0; k < (long)referenceConfigurations.size(); ++k)
288  {
289  std::advance(it,k); std::advance(it_other,k);
290 
291  if(it->second.size() != it_other->second.size())
292  return false;
293  if(it->second != it_other->second)
294  return false;
295  }
296 
297  if(other.rotorInertia.size() != rotorInertia.size())
298  return false;
299  res &= other.rotorInertia == rotorInertia;
300  if(!res) return res;
301 
302  if(other.friction.size() != friction.size())
303  return false;
304  res &= other.friction == friction;
305  if(!res) return res;
306 
307  if(other.damping.size() != damping.size())
308  return false;
309  res &= other.damping == damping;
310  if(!res) return res;
311 
312  if(other.rotorGearRatio.size() != rotorGearRatio.size())
313  return false;
314  res &= other.rotorGearRatio == rotorGearRatio;
315  if(!res) return res;
316 
317  if(other.effortLimit.size() != effortLimit.size())
318  return false;
319  res &= other.effortLimit == effortLimit;
320  if(!res) return res;
321 
322  if(other.velocityLimit.size() != velocityLimit.size())
323  return false;
324  res &= other.velocityLimit == velocityLimit;
325  if(!res) return res;
326 
327  if(other.lowerPositionLimit.size() != lowerPositionLimit.size())
328  return false;
329  res &= other.lowerPositionLimit == lowerPositionLimit;
330  if(!res) return res;
331 
332  if(other.upperPositionLimit.size() != upperPositionLimit.size())
333  return false;
334  res &= other.upperPositionLimit == upperPositionLimit;
335  if(!res) return res;
336 
337  for(size_t k = 1; k < inertias.size(); ++k)
338  {
339  res &= other.inertias[k] == inertias[k];
340  if(!res) return res;
341  }
342 
343  for(size_t k = 1; k < other.jointPlacements.size(); ++k)
344  {
345  res &= other.jointPlacements[k] == jointPlacements[k];
346  if(!res) return res;
347  }
348 
349  res &=
350  other.joints == joints
351  && other.frames == frames;
352 
353  return res;
354  }
355 
359  bool operator!=(const ModelTpl & other) const
360  { return !(*this == other); }
361 
381  const JointModel & joint_model,
382  const SE3 & joint_placement,
383  const std::string & joint_name);
384 
394  const JointModel & joint_model,
395  const SE3 & joint_placement,
396  const std::string & joint_name,
397  const VectorXs & max_effort,
398  const VectorXs & max_velocity,
399  const VectorXs & min_config,
400  const VectorXs & max_config);
401 
409  const JointModel & joint_model,
410  const SE3 & joint_placement,
411  const std::string & joint_name,
412  const VectorXs & max_effort,
413  const VectorXs & max_velocity,
414  const VectorXs & min_config,
415  const VectorXs & max_config,
416  const VectorXs & friction,
417  const VectorXs & damping);
418 
428  FrameIndex addJointFrame(const JointIndex & joint_index,
429  int previous_frame_index = -1);
430 
440  void appendBodyToJoint(const JointIndex joint_index, const Inertia & Y,
441  const SE3 & body_placement = SE3::Identity());
442 
454  FrameIndex addBodyFrame(const std::string & body_name,
455  const JointIndex & parentJoint,
456  const SE3 & body_placement = SE3::Identity(),
457  int previousFrame = -1);
458 
470  FrameIndex getBodyId(const std::string & name) const;
471 
479  bool existBodyName(const std::string & name) const;
480 
481 
492  JointIndex getJointId(const std::string & name) const;
493 
501  bool existJointName(const std::string & name) const;
502 
516  FrameIndex getFrameId(const std::string & name,
517  const FrameType & type = (FrameType) (JOINT | FIXED_JOINT | BODY | OP_FRAME | SENSOR )) const;
518 
527  bool existFrame(const std::string & name,
528  const FrameType& type = (FrameType) (JOINT | FIXED_JOINT | BODY | OP_FRAME | SENSOR )) const;
529 
539  FrameIndex addFrame(const Frame & frame,
540  const bool append_inertia = true);
541 
552  template<typename D>
553  inline bool check(const AlgorithmCheckerBase<D> & checker = AlgorithmCheckerBase<D>()) const
554  { return checker.checkModel(*this); }
555 
561  std::vector<bool> hasConfigurationLimit();
562 
568  std::vector<bool> hasConfigurationLimitInTangent();
569 
571  inline bool check() const;
572 
580  inline bool check(const Data & data) const;
581 
582  protected:
583 
590  };
591 
592 } // namespace pinocchio
593 
594 /* --- Details -------------------------------------------------------------- */
595 /* --- Details -------------------------------------------------------------- */
596 /* --- Details -------------------------------------------------------------- */
597 #include "pinocchio/multibody/model.hxx"
598 
599 #endif // ifndef __pinocchio_multibody_model_hpp__
pinocchio::FrameIndex
Index FrameIndex
Definition: multibody/fwd.hpp:30
fwd.hpp
pinocchio::ModelTpl::names
std::vector< std::string > names
Name of joint i
Definition: multibody/model.hpp:115
pinocchio::ModelTpl::Motion
MotionTpl< Scalar, Options > Motion
Definition: multibody/model.hpp:43
pinocchio::ModelTpl::Inertia
InertiaTpl< Scalar, Options > Inertia
Definition: multibody/model.hpp:45
pinocchio::ModelTpl::frames
FrameVector frames
Vector of operational frames registered on the model.
Definition: multibody/model.hpp:145
pinocchio::ModelTpl::SE3
SE3Tpl< Scalar, Options > SE3
Definition: multibody/model.hpp:42
pinocchio::DataTpl
Definition: multibody/data.hpp:29
pinocchio::AlgorithmCheckerBase
CRTP class describing the API of the checkers.
Definition: check.hpp:22
pinocchio::ModelTpl::existJointName
bool existJointName(const std::string &name) const
Check if a joint given by its name exists.
pinocchio::ModelTpl::GeomIndex
pinocchio::GeomIndex GeomIndex
Definition: multibody/model.hpp:50
lambdas.parent
parent
Definition: lambdas.py:16
pinocchio::ModelTpl::lowerPositionLimit
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
Definition: multibody/model.hpp:139
pinocchio::ModelTpl::existBodyName
bool existBodyName(const std::string &name) const
Check if a body given by its name exists.
aligned-vector.hpp
pinocchio::ModelTpl::operator==
bool operator==(const ModelTpl &other) const
Equality comparison operator.
Definition: multibody/model.hpp:262
pinocchio::ModelTpl::operator!=
bool operator!=(const ModelTpl &other) const
Definition: multibody/model.hpp:359
pinocchio::ModelTpl::addJointFrame
FrameIndex addJointFrame(const JointIndex &joint_index, int previous_frame_index=-1)
Add a joint to the frame tree.
pinocchio::FrameType
FrameType
Enum on the possible types of frames.
Definition: multibody/frame.hpp:28
pinocchio::SE3Tpl< Scalar, Options >
pinocchio::SENSOR
@ SENSOR
sensor frame: defined in a sensor element
Definition: multibody/frame.hpp:34
pinocchio::ModelTpl::Data
DataTpl< Scalar, Options, JointCollectionTpl > Data
Definition: multibody/model.hpp:40
serializable.hpp
pinocchio::ModelTpl::cast
ModelTpl< NewScalar, Options, JointCollectionTpl > cast() const
Definition: multibody/model.hpp:198
setup.data
data
Definition: cmake/cython/setup.in.py:48
inertia.hpp
pinocchio::ModelTpl::joints
JointModelVector joints
Model of joint i, encapsulated in a JointModelAccessor.
Definition: multibody/model.hpp:97
pinocchio::JointDataTpl
Definition: multibody/joint/fwd.hpp:97
pinocchio::ModelTpl::existFrame
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.
pinocchio::ModelTpl::Options
@ Options
Definition: multibody/model.hpp:37
motion.hpp
pinocchio::ModelTpl::name
std::string name
Model name;.
Definition: multibody/model.hpp:166
pinocchio::ModelTpl::~ModelTpl
~ModelTpl()
Definition: multibody/model.hpp:194
pinocchio::ModelTpl::hasConfigurationLimit
std::vector< bool > hasConfigurationLimit()
Check if joints have configuration limits.
pinocchio::ModelTpl::rotorInertia
TangentVectorType rotorInertia
Vector of rotor inertia parameters.
Definition: multibody/model.hpp:121
pinocchio::ModelTpl::check
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.
Definition: multibody/model.hpp:553
simulation-pendulum.type
type
Definition: simulation-pendulum.py:14
pinocchio::FrameTpl
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
Definition: multibody/frame.hpp:41
pinocchio::ModelTpl::JointIndex
pinocchio::JointIndex JointIndex
Definition: multibody/model.hpp:49
pinocchio::ModelTpl::referenceConfigurations
ConfigVectorMap referenceConfigurations
Map of reference configurations, indexed by user given names.
Definition: multibody/model.hpp:118
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:157
res
res
pinocchio::ModelTpl::JointCollection
JointCollectionTpl< Scalar, Options > JointCollection
Definition: multibody/model.hpp:39
pinocchio::ModelTpl::nqs
std::vector< int > nqs
Dimension of the joint i configuration subspace.
Definition: multibody/model.hpp:103
pinocchio::ModelTpl::PINOCCHIO_ALIGNED_STD_VECTOR
typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointModel) JointModelVector
pinocchio::ModelTpl::nvs
std::vector< int > nvs
Dimension of the joint i tangent subspace.
Definition: multibody/model.hpp:109
pinocchio::ModelTpl::idx_qs
std::vector< int > idx_qs
Starting index of the joint i in the configuration space.
Definition: multibody/model.hpp:100
pinocchio::ModelTpl::TangentVectorType
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....
Definition: multibody/model.hpp:73
pinocchio::ModelTpl::IndexVector
std::vector< Index > IndexVector
Definition: multibody/model.hpp:52
joint-generic.hpp
pinocchio::ModelTpl::getFrameId
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.
se3.hpp
pinocchio::ModelTpl::hasConfigurationLimitInTangent
std::vector< bool > hasConfigurationLimitInTangent()
Check if joints have configuration limits.
pinocchio::JointModelTpl
Definition: multibody/joint/fwd.hpp:93
pinocchio::ForceTpl< Scalar, Options >
pinocchio::ModelTpl::FrameIndex
pinocchio::FrameIndex FrameIndex
Definition: multibody/model.hpp:51
pinocchio::ModelTpl::rotorGearRatio
TangentVectorType rotorGearRatio
Vector of rotor gear ratio parameters.
Definition: multibody/model.hpp:124
pinocchio::Index
std::size_t Index
Definition: multibody/fwd.hpp:25
pinocchio::ModelTpl::Scalar
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
Definition: multibody/model.hpp:36
pinocchio::ModelTpl::JointData
JointDataTpl< Scalar, Options, JointCollectionTpl > JointData
Definition: multibody/model.hpp:55
pinocchio::ModelTpl::addJointIndexToParentSubtrees
void addJointIndexToParentSubtrees(const JointIndex joint_id)
Add the joint_id to its parent subtrees.
pinocchio::ModelTpl::nframes
int nframes
Number of operational frames.
Definition: multibody/model.hpp:88
pinocchio::ModelTpl::addJoint
JointIndex addJoint(const JointIndex parent, const JointModel &joint_model, const SE3 &joint_placement, const std::string &joint_name)
Add a joint to the kinematic tree with infinite bounds.
pinocchio::ModelTpl::velocityLimit
TangentVectorType velocityLimit
Vector of maximal joint velocities.
Definition: multibody/model.hpp:136
pinocchio::ModelTpl::nbodies
int nbodies
Number of bodies.
Definition: multibody/model.hpp:85
pinocchio::ModelTpl::friction
TangentVectorType friction
Vector of joint friction parameters.
Definition: multibody/model.hpp:127
pinocchio::ModelTpl::JointModel
JointModelTpl< Scalar, Options, JointCollectionTpl > JointModel
Definition: multibody/model.hpp:54
pinocchio::ModelTpl::addFrame
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...
pinocchio::ModelTpl::gravity
Motion gravity
Spatial gravity of the model.
Definition: multibody/model.hpp:160
pinocchio::JOINT
@ JOINT
joint frame: attached to the child body of a joint (a.k.a. child frame)
Definition: multibody/frame.hpp:31
pinocchio::ModelTpl::gravity981
static const Vector3 gravity981
Default 3D gravity vector (=(0,0,-9.81)).
Definition: multibody/model.hpp:163
pinocchio::ModelTpl::getJointId
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
collision-with-point-clouds.Y
Y
Definition: collision-with-point-clouds.py:31
pinocchio::ModelTpl::Index
pinocchio::Index Index
Definition: multibody/model.hpp:48
pinocchio::OP_FRAME
@ OP_FRAME
operational frame: user-defined frames that are defined at runtime
Definition: multibody/frame.hpp:30
append-urdf-model-with-another-model.joint_name
string joint_name
Definition: append-urdf-model-with-another-model.py:32
append-urdf-model-with-another-model.joint_placement
joint_placement
Definition: append-urdf-model-with-another-model.py:28
pinocchio::ModelTpl::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Definition: multibody/model.hpp:62
pinocchio::ModelTpl::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: multibody/model.hpp:63
pinocchio::ModelTpl::damping
TangentVectorType damping
Vector of joint damping parameters.
Definition: multibody/model.hpp:130
pinocchio::ModelTpl::nv
int nv
Dimension of the velocity vector space.
Definition: multibody/model.hpp:79
pinocchio::ModelTpl::Force
ForceTpl< Scalar, Options > Force
Definition: multibody/model.hpp:44
pinocchio::ModelTpl::getBodyId
FrameIndex getBodyId(const std::string &name) const
Return the index of a body given by its name.
pinocchio::ModelTpl::ConfigVectorMap
std::map< std::string, ConfigVectorType > ConfigVectorMap
Map between a string (key) and a configuration vector.
Definition: multibody/model.hpp:69
pinocchio::SE3Tpl< Scalar, Options >::Identity
static SE3Tpl Identity()
Definition: spatial/se3-tpl.hpp:106
pinocchio::FIXED_JOINT
@ FIXED_JOINT
fixed joint frame: joint frame but for a fixed joint
Definition: multibody/frame.hpp:32
frame.hpp
pinocchio::ModelTpl::supports
std::vector< IndexVector > supports
Vector of joint supports. supports[j] corresponds to the vector of indices of the joints located on t...
Definition: multibody/model.hpp:152
pinocchio::ModelTpl::check
bool check() const
Run check(fusion::list) with DEFAULT_CHECKERS as argument.
Definition: default-check.hpp:21
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:28
pinocchio::ModelTpl::addBodyFrame
FrameIndex addBodyFrame(const std::string &body_name, const JointIndex &parentJoint, const SE3 &body_placement=SE3::Identity(), int previousFrame=-1)
Add a body to the frame tree.
pinocchio::InertiaTpl< Scalar, Options >
pinocchio::ModelTpl::effortLimit
TangentVectorType effortLimit
Vector of maximal joint torques.
Definition: multibody/model.hpp:133
pinocchio::ModelTpl::parents
std::vector< JointIndex > parents
Joint parent of joint i, denoted li (li==parents[i]).
Definition: multibody/model.hpp:112
pinocchio::ModelTpl::ModelTpl
ModelTpl()
Default constructor. Builds an empty model with no joints.
Definition: multibody/model.hpp:169
append-urdf-model-with-another-model.body_placement
body_placement
Definition: append-urdf-model-with-another-model.py:36
pinocchio::ModelTpl::ConfigVectorType
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
Definition: multibody/model.hpp:66
pinocchio::ModelTpl::Frame
FrameTpl< Scalar, Options > Frame
Definition: multibody/model.hpp:46
pinocchio::ModelTpl::idx_vs
std::vector< int > idx_vs
Starting index of the joint i in the tangent configuration space.
Definition: multibody/model.hpp:106
pinocchio::MotionTpl< Scalar, Options >
append-urdf-model-with-another-model.joint_id
joint_id
Definition: append-urdf-model-with-another-model.py:33
pinocchio::ModelTpl
Definition: multibody/fwd.hpp:23
pinocchio::ModelTpl::upperPositionLimit
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
Definition: multibody/model.hpp:142
force.hpp
pinocchio::BODY
@ BODY
body frame: attached to the collision, inertial or visual properties of a link
Definition: multibody/frame.hpp:33
pinocchio::GeomIndex
Index GeomIndex
Definition: multibody/fwd.hpp:29
fwd.hpp
pinocchio::ModelTpl::nq
int nq
Dimension of the configuration vector representation.
Definition: multibody/model.hpp:76
pinocchio::ModelTpl::appendBodyToJoint
void appendBodyToJoint(const JointIndex joint_index, const Inertia &Y, const SE3 &body_placement=SE3::Identity())
Append a body to a given joint of the kinematic tree.
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:28
pinocchio::ModelTpl::njoints
int njoints
Number of joints.
Definition: multibody/model.hpp:82


pinocchio
Author(s):
autogenerated on Sun Apr 28 2024 02:41:52