bindings/python/multibody/model.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2023 CNRS INRIA
3 // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
6 #ifndef __pinocchio_python_multibody_model_hpp__
7 #define __pinocchio_python_multibody_model_hpp__
8 
10 
13 
14 #include <boost/python/overloads.hpp>
15 #include <eigenpy/memory.hpp>
16 #include <eigenpy/exception.hpp>
17 
19 
29 
30 #if EIGENPY_VERSION_AT_MOST(2, 8, 1)
32 #endif
33 
34 namespace pinocchio
35 {
36  namespace python
37  {
38  namespace bp = boost::python;
39 
40  template<typename Model>
41  struct ModelPythonVisitor : public bp::def_visitor<ModelPythonVisitor<Model>>
42  {
43  public:
44  typedef typename Model::Scalar Scalar;
45 
46  typedef typename Model::Index Index;
47  typedef typename Model::JointIndex JointIndex;
48  typedef typename Model::JointModel JointModel;
50  typedef typename Model::FrameIndex FrameIndex;
51  typedef typename Model::IndexVector IndexVector;
52 
53  typedef typename Model::SE3 SE3;
54  typedef typename Model::Motion Motion;
55  typedef typename Model::Force Force;
56  typedef typename Model::Frame Frame;
57  typedef typename Model::Inertia Inertia;
58 
59  typedef typename Model::Data Data;
60 
61  typedef typename Model::VectorXs VectorXs;
62 
63  public:
64  /* --- Exposing C++ API to python through the handler ----------------- */
65  template<class PyClass>
66  void visit(PyClass & cl) const
67  {
68  cl.def(bp::init<>(bp::arg("self"), "Default constructor. Constructs an empty model."))
69  .def(bp::init<const Model &>((bp::arg("self"), bp::arg("clone")), "Copy constructor"))
70 
71  // Class Members
72  .add_property("nq", &Model::nq, "Dimension of the configuration vector representation.")
73  .add_property("nv", &Model::nv, "Dimension of the velocity vector space.")
74  .add_property("nvExtended", &Model::nvExtended, "Dimension of the jacobian matrix space.")
75  .add_property("njoints", &Model::njoints, "Number of joints.")
76  .add_property("nbodies", &Model::nbodies, "Number of bodies.")
77  .add_property("nframes", &Model::nframes, "Number of frames.")
78  .add_property(
79  "inertias", &Model::inertias, "Vector of spatial inertias supported by each joint.")
80  .def_readwrite(
81  "jointPlacements", &Model::jointPlacements,
82  "Vector of joint placements: placement of a joint *i* wrt its parent joint frame.")
83  .add_property("joints", &Model::joints, "Vector of joint models.")
84  .add_property(
85  "idx_qs", &Model::idx_qs,
86  "Vector of starting index of the *i*th joint in the configuration space.")
87  .add_property(
88  "nqs", &Model::nqs, "Vector of dimension of the joint configuration subspace.")
89  .add_property(
90  "idx_vs", &Model::idx_vs,
91  "Starting index of the *i*th joint in the tangent configuration space.")
92  .add_property("nvs", &Model::nvs, "Dimension of the *i*th joint tangent subspace.")
93  .add_property(
94  "idx_vExtendeds", &Model::idx_vExtendeds,
95  "Starting index of the *i*th joint in the jacobian space.")
96  .add_property(
97  "nvExtendeds", &Model::nvExtendeds, "Dimension of the *i*th joint jacobian subspace.")
98  .add_property(
99  "parents", &Model::parents,
100  "Vector of parent joint indexes. The parent of joint *i*, denoted *li*, "
101  "corresponds to li==parents[i].")
102  .add_property(
103  "children", &Model::children,
104  "Vector of children index. Chidren of the *i*th joint, denoted *mu(i)* "
105  "corresponds to the set (i==parents[k] for k in mu(i)).")
106  .add_property("names", &Model::names, "Name of the joints.")
107  .def_readwrite("name", &Model::name, "Name of the model.")
108  .def_readwrite(
109  "referenceConfigurations", &Model::referenceConfigurations,
110  "Map of reference configurations, indexed by user given names.")
111 
112  .def_readwrite("armature", &Model::armature, "Armature vector.")
113  .def_readwrite(
114  "rotorInertia", &Model::rotorInertia, "Vector of rotor inertia parameters.")
115  .def_readwrite(
116  "rotorGearRatio", &Model::rotorGearRatio, "Vector of rotor gear ratio parameters.")
117  .def_readwrite("friction", &Model::friction, "Vector of joint friction parameters.")
118  .def_readwrite("damping", &Model::damping, "Vector of joint damping parameters.")
119  .def_readwrite("effortLimit", &Model::effortLimit, "Joint max effort.")
120  .def_readwrite("velocityLimit", &Model::velocityLimit, "Joint max velocity.")
121  .def_readwrite(
122  "lowerPositionLimit", &Model::lowerPositionLimit, "Limit for joint lower position.")
123  .def_readwrite(
124  "upperPositionLimit", &Model::upperPositionLimit, "Limit for joint upper position.")
125 
126  .def_readwrite("frames", &Model::frames, "Vector of frames contained in the model.")
127 
128  .def_readwrite(
129  "supports", &Model::supports,
130  "Vector of supports. supports[j] corresponds to the list of joints on the "
131  "path between\n"
132  "the current *j* to the root of the kinematic tree.")
133 
134  .def_readwrite(
135  "mimic_joint_supports", &Model::mimic_joint_supports,
136  "Vector of mimic supports joints. "
137  "mimic_joint_supports[j] corresponds to the vector of mimic joints indices located on "
138  "the path "
139  "between joint *j* and \"universe\". The first element of mimic_joint_supports[j] is "
140  "\"universe\". "
141  "If *j* is a mimic, the last element is the index of joint *j* itself")
142 
143  .def_readwrite(
144  "subtrees", &Model::subtrees,
145  "Vector of subtrees. subtree[j] corresponds to the subtree supported by the joint j.")
146 
147  .def_readwrite(
148  "mimicking_joints", &Model::mimicking_joints,
149  "Vector of mimicking joints in the tree (with type MimicTpl)")
150 
151  .def_readwrite(
152  "mimicked_joints", &Model::mimicked_joints,
153  "Vector of mimicked joints in the tree (can be any joint type)")
154 
155  .def_readwrite(
156  "gravity", &Model::gravity,
157  "Motion vector corresponding to the gravity field expressed in the world Frame.")
158 
159  // Class Methods
160  .def(
161  "addJoint", &ModelPythonVisitor::addJoint0,
162  bp::args("self", "parent_id", "joint_model", "joint_placement", "joint_name"),
163  "Adds a joint to the kinematic tree. The joint is defined by its placement relative "
164  "to its parent joint and its name.")
165  .def(
166  "addJoint", &ModelPythonVisitor::addJoint1,
167  bp::args(
168  "self", "parent_id", "joint_model", "joint_placement", "joint_name", "max_effort",
169  "max_velocity", "min_config", "max_config"),
170  "Adds a joint to the kinematic tree with given bounds. The joint is defined by its "
171  "placement relative to its parent joint and its name."
172  "This signature also takes as input effort, velocity limits as well as the bounds "
173  "on the joint configuration.")
174  .def(
175  "addJoint", &ModelPythonVisitor::addJoint2,
176  bp::args(
177  "self", "parent_id", "joint_model", "joint_placement", "joint_name", "max_effort",
178  "max_velocity", "min_config", "max_config", "friction", "damping"),
179  "Adds a joint to the kinematic tree with given bounds. The joint is defined by its "
180  "placement relative to its parent joint and its name.\n"
181  "This signature also takes as input effort, velocity limits as well as the bounds "
182  "on the joint configuration.\n"
183  "The user should also provide the friction and damping related to the joint.")
184  .def(
185  "addJointFrame", &Model::addJointFrame,
186  (bp::arg("self"), bp::arg("joint_id"), bp::arg("frame_id") = 0),
187  "Add the joint provided by its joint_id as a frame to the frame tree.\n"
188  "The frame_id may be optionally provided.")
189  .def(
190  "appendBodyToJoint", &Model::appendBodyToJoint,
191  bp::args("self", "joint_id", "body_inertia", "body_placement"),
192  "Appends a body to the joint given by its index. The body is defined by its "
193  "inertia, its relative placement regarding to the joint and its name.")
194 
195  .def(
196  "addBodyFrame", &Model::addBodyFrame,
197  bp::args("self", "body_name", "parentJoint", "body_placement", "previous_frame"),
198  "add a body to the frame tree")
199  .def(
200  "getBodyId", &Model::getBodyId, bp::args("self", "name"),
201  "Return the index of a frame of type BODY given by its name")
202  .def(
203  "existBodyName", &Model::existBodyName, bp::args("self", "name"),
204  "Check if a frame of type BODY exists, given its name")
205  .def(
206  "getJointId", &Model::getJointId, bp::args("self", "name"),
207  "Return the index of a joint given by its name")
208  .def(
209  "existJointName", &Model::existJointName, bp::args("self", "name"),
210  "Check if a joint given by its name exists")
211 
212  .def(
213  "getFrameId", &Model::getFrameId,
214  (bp::arg("self"), bp::arg("name"),
215  bp::arg("type") = (FrameType)(JOINT | FIXED_JOINT | BODY | OP_FRAME | SENSOR)),
216  "Returns the index of the frame given by its name and its type."
217  "If the frame is not in the frames vector, it returns the current size of the "
218  "frames vector.")
219 
220  .def(
221  "existFrame", &Model::existFrame,
222  (bp::arg("self"), bp::arg("name"),
223  bp::arg("type") = (FrameType)(JOINT | FIXED_JOINT | BODY | OP_FRAME | SENSOR)),
224  "Returns true if the frame given by its name exists inside the Model with the given "
225  "type.")
226 
227  .def(
228  "addFrame", &Model::addFrame,
229  (bp::arg("self"), bp::arg("frame"), bp::arg("append_inertia") = true),
230  "Add a frame to the vector of frames. If append_inertia set to True, "
231  "the inertia value contained in frame will be added to the inertia supported by the "
232  "parent joint.")
233 
234  .def(
235  "createData", &ModelPythonVisitor::createData, bp::arg("self"),
236  "Create a Data object for the given model.")
237 
238  .def(
239  "check", (bool(Model::*)(const Data &) const) & Model::check, bp::args("self", "data"),
240  "Check consistency of data wrt model.")
241 
242  .def(
243  "hasConfigurationLimit", &Model::hasConfigurationLimit, bp::args("self"),
244  "Returns list of boolean if joints have configuration limit.")
245  .def(
246  "hasConfigurationLimitInTangent", &Model::hasConfigurationLimitInTangent,
247  bp::args("self"),
248  "Returns list of boolean if joints have configuration limit in tangent space .")
249 
250 #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS
251 
252  .def(bp::self == bp::self)
253  .def(bp::self != bp::self)
254 #endif
255 
256  .PINOCCHIO_ADD_STATIC_PROPERTY_READONLY_BYVALUE(
257  Model, gravity981, "Default gravity field value on the Earth.");
258 
259  bp::register_ptr_to_python<std::shared_ptr<Model>>();
260  }
261 
263  Model & model,
265  const JointModel & jmodel,
266  const SE3 & joint_placement,
267  const std::string & joint_name)
268  {
269  return model.addJoint(parent_id, jmodel, joint_placement, joint_name);
270  }
271 
273  Model & model,
275  const JointModel & jmodel,
276  const SE3 & joint_placement,
277  const std::string & joint_name,
278  const VectorXs & max_effort,
279  const VectorXs & max_velocity,
280  const VectorXs & min_config,
281  const VectorXs & max_config)
282  {
283  return model.addJoint(
284  parent_id, jmodel, joint_placement, joint_name, max_effort, max_velocity, min_config,
285  max_config);
286  }
287 
289  Model & model,
291  const JointModel & jmodel,
292  const SE3 & joint_placement,
293  const std::string & joint_name,
294  const VectorXs & max_effort,
295  const VectorXs & max_velocity,
296  const VectorXs & min_config,
297  const VectorXs & max_config,
298  const VectorXs & friction,
299  const VectorXs & damping)
300  {
301  return model.addJoint(
302  parent_id, jmodel, joint_placement, joint_name, max_effort, max_velocity, min_config,
303  max_config, friction, damping);
304  }
305 
306  static Data createData(const Model & model)
307  {
308  return Data(model);
309  }
310 
321  template<typename T>
322  static Index index(std::vector<T> const & x, typename std::vector<T>::value_type const & v)
323  {
324  Index i = 0;
325  for (typename std::vector<T>::const_iterator it = x.begin(); it != x.end(); ++it, ++i)
326  {
327  if (*it == v)
328  {
329  return i;
330  }
331  }
332  return x.size();
333  }
334 
335  /* --- Expose --------------------------------------------------------- */
336  static void expose()
337  {
338  typedef typename Model::ConfigVectorMap ConfigVectorMap;
339  typedef bp::map_indexing_suite<ConfigVectorMap, false> map_indexing_suite;
341  serialize<std::vector<Index>>();
343  serialize<std::vector<IndexVector>>();
347 
348 #if defined(PINOCCHIO_PYTHON_INTERFACE_MAIN_MODULE)
349  bp::scope().attr("StdVec_Double") = bp::scope().attr("StdVec_Scalar"); // alias
350 #endif
351 
352  serialize<std::vector<std::string>>();
353  serialize<std::vector<bool>>();
354 #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION
355  serialize<std::vector<Scalar>>();
356 #endif
357  bp::class_<typename Model::ConfigVectorMap>("StdMap_String_VectorXd")
358  .def(map_indexing_suite())
361 
362  bp::class_<Model>("Model", "Articulated Rigid Body model", bp::no_init)
363  .def(ModelPythonVisitor())
364  .def(CastVisitor<Model>())
368  .def(CopyableVisitor<Model>())
369 #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION
371 #endif
372  ;
373  }
374  };
375 
376  } // namespace python
377 } // namespace pinocchio
378 
379 #endif // ifndef __pinocchio_python_multibody_model_hpp__
pinocchio::InertiaTpl< Scalar, Options >
pinocchio::python::ModelPythonVisitor::Data
Model::Data Data
Definition: bindings/python/multibody/model.hpp:59
pinocchio::ModelTpl< context::Scalar, context::Options >::names
std::vector< std::string > names
Name of the joints.
Definition: multibody/model.hpp:159
boost::python
pinocchio::python::ModelPythonVisitor::Index
Model::Index Index
Definition: bindings/python/multibody/model.hpp:46
pinocchio::python::ModelPythonVisitor::addJoint1
static JointIndex addJoint1(Model &model, JointIndex parent_id, const JointModel &jmodel, const SE3 &joint_placement, const std::string &joint_name, const VectorXs &max_effort, const VectorXs &max_velocity, const VectorXs &min_config, const VectorXs &max_config)
Definition: bindings/python/multibody/model.hpp:272
pinocchio::ModelTpl< context::Scalar, context::Options >::frames
FrameVector frames
Vector of operational frames registered on the model.
Definition: multibody/model.hpp:193
model.hpp
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::ModelTpl< context::Scalar, context::Options >::existJointName
bool existJointName(const std::string &name) const
Check if a joint given by its name exists.
pinocchio::python::PickleFromStringSerialization
Definition: pickle.hpp:17
pinocchio::ModelTpl< context::Scalar, context::Options >::jointPlacements
SE3Vector jointPlacements
Vector of joint placements: placement of a joint i wrt its parent joint frame.
Definition: multibody/model.hpp:119
eigenpy::StdVectorPythonVisitor
pinocchio::python::ModelPythonVisitor::Force
Model::Force Force
Definition: bindings/python/multibody/model.hpp:55
pinocchio::ModelTpl< context::Scalar, context::Options >::lowerPositionLimit
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
Definition: multibody/model.hpp:187
pinocchio::ModelTpl< context::Scalar, context::Options >::existBodyName
bool existBodyName(const std::string &name) const
Check if a body given by its name exists.
pinocchio::FrameType
FrameType
Enum on the possible types of frames.
Definition: multibody/frame.hpp:31
pinocchio::SE3Tpl< Scalar, Options >
pinocchio::SENSOR
@ SENSOR
sensor frame: defined in a sensor element
Definition: multibody/frame.hpp:38
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:17
model.hpp
pinocchio::python::ExposeConstructorByCastVisitor
Definition: bindings/python/utils/cast.hpp:33
eigen-to-python.hpp
exception.hpp
pinocchio::ModelTpl< context::Scalar, context::Options >::joints
JointModelVector joints
Vector of joint models.
Definition: multibody/model.hpp:122
pinocchio::ModelTpl< context::Scalar, context::Options >::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< context::Scalar, context::Options >::mimic_joint_supports
std::vector< IndexVector > mimic_joint_supports
Vector of mimic supports joints. mimic_joint_supports[j] corresponds to the vector of mimic joints in...
Definition: multibody/model.hpp:206
pinocchio::ModelTpl< context::Scalar, context::Options >::name
std::string name
Model name.
Definition: multibody/model.hpp:220
pinocchio::python::details::overload_base_get_item_for_std_map
Definition: std-map.hpp:17
pinocchio::python::ModelPythonVisitor::createData
static Data createData(const Model &model)
Definition: bindings/python/multibody/model.hpp:306
pinocchio::ModelTpl< context::Scalar, context::Options >::hasConfigurationLimit
std::vector< bool > hasConfigurationLimit()
Check if joints have configuration limits.
pinocchio::ModelTpl< context::Scalar, context::Options >::rotorInertia
TangentVectorType rotorInertia
Vector of rotor inertia parameters.
Definition: multibody/model.hpp:169
pinocchio::FrameTpl
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
Definition: multibody/frame.hpp:55
pinocchio::python::ModelPythonVisitor::Frame
Model::Frame Frame
Definition: bindings/python/multibody/model.hpp:56
pinocchio::ModelTpl< context::Scalar, context::Options >::inertias
InertiaVector inertias
Vector of spatial inertias supported by each joint.
Definition: multibody/model.hpp:116
pinocchio::ModelTpl< context::Scalar, context::Options >::JointIndex
pinocchio::JointIndex JointIndex
Definition: multibody/model.hpp:67
pinocchio::ModelTpl< context::Scalar, context::Options >::referenceConfigurations
ConfigVectorMap referenceConfigurations
Map of reference configurations, indexed by user given names.
Definition: multibody/model.hpp:162
pinocchio::ModelTpl< context::Scalar, context::Options >::subtrees
std::vector< IndexVector > subtrees
Vector of joint subtrees. subtree[j] corresponds to the subtree supported by the joint j....
Definition: multibody/model.hpp:211
append-urdf-model-with-another-model.parent_id
int parent_id
Definition: append-urdf-model-with-another-model.py:28
pickle.hpp
cast.hpp
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION
#define EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(...)
pinocchio::python::ModelPythonVisitor::SE3
Model::SE3 SE3
Definition: bindings/python/multibody/model.hpp:53
pinocchio::ModelTpl< context::Scalar, context::Options >::nqs
std::vector< int > nqs
Vector of dimension of the joint configuration subspace.
Definition: multibody/model.hpp:128
pinocchio::python::PrintableVisitor
Set the Python method str and repr to use the overloading operator<<.
Definition: printable.hpp:21
pinocchio::ModelTpl< context::Scalar, context::Options >::addBodyFrame
FrameIndex addBodyFrame(const std::string &body_name, const JointIndex &parentJoint, const SE3 &body_placement=SE3::Identity(), int parentFrame=-1)
Add a body to the frame tree.
pinocchio::ModelTpl< context::Scalar, context::Options >::nvs
std::vector< int > nvs
Dimension of the *i*th joint tangent subspace.
Definition: multibody/model.hpp:134
pinocchio::ModelTpl< context::Scalar, context::Options >::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::ModelTpl< context::Scalar, context::Options >::mimicking_joints
std::vector< JointIndex > mimicking_joints
Vector of mimicking joints in the tree (with type MimicTpl)
Definition: multibody/model.hpp:151
pinocchio::python::ModelPythonVisitor::JointModel
Model::JointModel JointModel
Definition: bindings/python/multibody/model.hpp:48
pinocchio::ModelTpl< context::Scalar, context::Options >::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:148
serializable.hpp
pinocchio::ModelTpl< context::Scalar, context::Options >::idx_qs
std::vector< int > idx_qs
Vector of starting index of the *i*th joint in the configuration space.
Definition: multibody/model.hpp:125
pinocchio::ModelTpl< context::Scalar, context::Options >::IndexVector
std::vector< Index > IndexVector
Definition: multibody/model.hpp:70
pinocchio::python::ModelPythonVisitor::visit
void visit(PyClass &cl) const
Definition: bindings/python/multibody/model.hpp:66
pinocchio::ModelTpl< context::Scalar, context::Options >::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.
python
pinocchio::ModelTpl< context::Scalar, context::Options >::hasConfigurationLimitInTangent
std::vector< bool > hasConfigurationLimitInTangent()
Check if joints have configuration limits.
pinocchio::python::v
const Vector3Like & v
Definition: bindings/python/spatial/explog.hpp:66
pinocchio::JointModelTpl< Scalar, Options, JointCollectionTpl >
pinocchio::ModelTpl< context::Scalar, context::Options >::nvExtended
int nvExtended
Dimension of the jacobian space.
Definition: multibody/model.hpp:104
pinocchio::python::ModelPythonVisitor::addJoint0
static JointIndex addJoint0(Model &model, JointIndex parent_id, const JointModel &jmodel, const SE3 &joint_placement, const std::string &joint_name)
Definition: bindings/python/multibody/model.hpp:262
pinocchio::python::ModelPythonVisitor::VectorXs
Model::VectorXs VectorXs
Definition: bindings/python/multibody/model.hpp:61
pinocchio::ForceTpl< Scalar, Options >
pinocchio::ModelTpl< context::Scalar, context::Options >::FrameIndex
pinocchio::FrameIndex FrameIndex
Definition: multibody/model.hpp:69
pinocchio::python::ModelPythonVisitor::JointModelVariant
JointModel::JointModelVariant JointModelVariant
Definition: bindings/python/multibody/model.hpp:49
pinocchio::ModelTpl< context::Scalar, context::Options >::rotorGearRatio
TangentVectorType rotorGearRatio
Vector of rotor gear ratio parameters.
Definition: multibody/model.hpp:172
pinocchio::ModelTpl< context::Scalar, context::Options >::armature
VectorXs armature
Vector of armature values expressed at the joint level This vector may contain the contribution of ro...
Definition: multibody/model.hpp:166
pinocchio::python::CopyableVisitor
Add the Python method copy to allow a copy of this by calling the copy constructor.
Definition: copyable.hpp:21
pinocchio::python::ModelPythonVisitor::Motion
Model::Motion Motion
Definition: bindings/python/multibody/model.hpp:54
pinocchio::ModelTpl< context::Scalar, context::Options >::mimicked_joints
std::vector< JointIndex > mimicked_joints
Vector of mimicked joints in the tree (can be any joint type) The i-th element of this vector corresp...
Definition: multibody/model.hpp:156
x
x
pinocchio::ModelTpl< context::Scalar, context::Options >::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Definition: multibody/model.hpp:80
pinocchio::ModelTpl< context::Scalar, context::Options >::Scalar
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef context::Scalar Scalar
Definition: multibody/model.hpp:51
pinocchio::python::ModelPythonVisitor::IndexVector
Model::IndexVector IndexVector
Definition: bindings/python/multibody/model.hpp:51
pinocchio::python::ModelPythonVisitor::FrameIndex
Model::FrameIndex FrameIndex
Definition: bindings/python/multibody/model.hpp:50
pinocchio::ModelTpl< context::Scalar, context::Options >::nframes
int nframes
Number of operational frames.
Definition: multibody/model.hpp:113
pinocchio::python::ModelPythonVisitor::index
static Index index(std::vector< T > const &x, typename std::vector< T >::value_type const &v)
Provide equivalent to python list index function for vectors.
Definition: bindings/python/multibody/model.hpp:322
pinocchio::python::ModelPythonVisitor::Inertia
Model::Inertia Inertia
Definition: bindings/python/multibody/model.hpp:57
pinocchio::ModelTpl< context::Scalar, context::Options >::velocityLimit
TangentVectorType velocityLimit
Vector of maximal joint velocities.
Definition: multibody/model.hpp:184
pinocchio::ModelTpl< context::Scalar, context::Options >::nbodies
int nbodies
Number of bodies.
Definition: multibody/model.hpp:110
pinocchio::ModelTpl< context::Scalar, context::Options >::friction
TangentVectorType friction
Vector of joint friction parameters.
Definition: multibody/model.hpp:175
pinocchio::python::ModelPythonVisitor::Scalar
Model::Scalar Scalar
Definition: bindings/python/multibody/model.hpp:44
pinocchio::python::CastVisitor
Add the Python method cast.
Definition: bindings/python/utils/cast.hpp:23
pinocchio::ModelTpl< context::Scalar, context::Options >::addJointFrame
FrameIndex addJointFrame(const JointIndex &joint_index, int previous_frame_index=-1)
Add a joint to the frame tree.
pinocchio::python::ModelPythonVisitor
Definition: bindings/python/multibody/model.hpp:41
copyable.hpp
inverse-kinematics-3d.it
int it
Definition: inverse-kinematics-3d.py:17
pinocchio::ModelTpl< context::Scalar, context::Options >::gravity
Motion gravity
Spatial gravity of the model.
Definition: multibody/model.hpp:214
pinocchio::JOINT
@ JOINT
joint frame: attached to the child body of a joint (a.k.a. child frame)
Definition: multibody/frame.hpp:34
pinocchio::ModelTpl< context::Scalar, context::Options >::getJointId
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
value_type
Scalar value_type
Definition: eigen_plugin.hpp:2
pinocchio::python::SerializableVisitor
Definition: bindings/python/serialization/serializable.hpp:19
macros.hpp
check.hpp
pinocchio::ModelTpl< context::Scalar, context::Options >::Index
pinocchio::Index Index
Definition: multibody/model.hpp:66
pinocchio::OP_FRAME
@ OP_FRAME
operational frame: user-defined frames that are defined at runtime
Definition: multibody/frame.hpp:33
append-urdf-model-with-another-model.joint_name
string joint_name
Definition: append-urdf-model-with-another-model.py:33
append-urdf-model-with-another-model.joint_placement
joint_placement
Definition: append-urdf-model-with-another-model.py:29
std-map.hpp
pinocchio::ModelTpl< context::Scalar, context::Options >::damping
TangentVectorType damping
Vector of joint damping parameters.
Definition: multibody/model.hpp:178
pinocchio::ModelTpl< context::Scalar, context::Options >::nv
int nv
Dimension of the velocity vector space.
Definition: multibody/model.hpp:101
pinocchio::ModelTpl< context::Scalar, context::Options >::nvExtendeds
std::vector< int > nvExtendeds
Dimension of the *i*th joint jacobian subspace.
Definition: multibody/model.hpp:140
pinocchio::ModelTpl< context::Scalar, context::Options >::getBodyId
FrameIndex getBodyId(const std::string &name) const
Return the index of a body given by its name.
pinocchio::ModelTpl< context::Scalar, context::Options >::ConfigVectorMap
std::map< std::string, ConfigVectorType > ConfigVectorMap
Map between a string (key) and a configuration vector.
Definition: multibody/model.hpp:90
pinocchio::JointModelTpl< Scalar, Options, JointCollectionTpl >::JointModelVariant
JointCollection::JointModelVariant JointModelVariant
Definition: joint-generic.hpp:275
pinocchio::python::ModelPythonVisitor::addJoint2
static JointIndex addJoint2(Model &model, JointIndex parent_id, const JointModel &jmodel, const SE3 &joint_placement, const std::string &joint_name, const VectorXs &max_effort, const VectorXs &max_velocity, const VectorXs &min_config, const VectorXs &max_config, const VectorXs &friction, const VectorXs &damping)
Definition: bindings/python/multibody/model.hpp:288
pinocchio::FIXED_JOINT
@ FIXED_JOINT
fixed joint frame: joint frame but for a fixed joint
Definition: multibody/frame.hpp:35
cl
cl
pinocchio::ModelTpl< context::Scalar, context::Options >::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:200
pinocchio::ModelTpl< context::Scalar, context::Options >::check
bool check() const
Run check(fusion::list) with DEFAULT_CHECKERS as argument.
Definition: default-check.hpp:23
pinocchio::ModelTpl< context::Scalar, context::Options >::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...
memory.hpp
pinocchio::ModelTpl< context::Scalar, context::Options >::effortLimit
TangentVectorType effortLimit
Vector of maximal joint torques.
Definition: multibody/model.hpp:181
printable.hpp
pinocchio::ModelTpl< context::Scalar, context::Options >::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:144
std-vector.hpp
pickle-map.hpp
pinocchio::python::ModelPythonVisitor::expose
static void expose()
Definition: bindings/python/multibody/model.hpp:336
pinocchio::ModelTpl< context::Scalar, context::Options >::idx_vs
std::vector< int > idx_vs
Starting index of the *i*th joint in the tangent configuration space.
Definition: multibody/model.hpp:131
pinocchio::MotionTpl< Scalar, Options >
pinocchio::ModelTpl< context::Scalar, context::Options >
pinocchio::python::ModelPythonVisitor::JointIndex
Model::JointIndex JointIndex
Definition: bindings/python/multibody/model.hpp:47
pinocchio::ModelTpl< context::Scalar, context::Options >::upperPositionLimit
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
Definition: multibody/model.hpp:190
pinocchio::BODY
@ BODY
body frame: attached to the collision, inertial or visual properties of a link
Definition: multibody/frame.hpp:36
pinocchio::ModelTpl< context::Scalar, context::Options >::idx_vExtendeds
std::vector< int > idx_vExtendeds
Starting index of the *i*th joint in the jacobian space.
Definition: multibody/model.hpp:137
pinocchio::ModelTpl< context::Scalar, context::Options >::nq
int nq
Dimension of the configuration vector representation.
Definition: multibody/model.hpp:98
pinocchio::python::PickleMap
Create a pickle interface for the std::map and aligned map.
Definition: pickle-map.hpp:24
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:33
pinocchio::ModelTpl< context::Scalar, context::Options >::njoints
int njoints
Number of joints.
Definition: multibody/model.hpp:107


pinocchio
Author(s):
autogenerated on Thu Apr 10 2025 02:42:21