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("njoints", &Model::njoints, "Number of joints.")
75  .add_property("nbodies", &Model::nbodies, "Number of bodies.")
76  .add_property("nframes", &Model::nframes, "Number of frames.")
77  .add_property(
78  "inertias", &Model::inertias, "Vector of spatial inertias supported by each joint.")
79  .def_readwrite(
80  "jointPlacements", &Model::jointPlacements,
81  "Vector of joint placements: placement of a joint *i* wrt its parent joint frame.")
82  .add_property("joints", &Model::joints, "Vector of joint models.")
83  .add_property(
84  "idx_qs", &Model::idx_qs,
85  "Vector of starting index of the *i*th joint in the configuration space.")
86  .add_property(
87  "nqs", &Model::nqs, "Vector of dimension of the joint configuration subspace.")
88  .add_property(
89  "idx_vs", &Model::idx_vs,
90  "Starting index of the *i*th joint in the tangent configuration space.")
91  .add_property("nvs", &Model::nvs, "Dimension of the *i*th joint tangent subspace.")
92  .add_property(
93  "parents", &Model::parents,
94  "Vector of parent joint indexes. The parent of joint *i*, denoted *li*, "
95  "corresponds to li==parents[i].")
96  .add_property(
97  "children", &Model::children,
98  "Vector of children index. Chidren of the *i*th joint, denoted *mu(i)* "
99  "corresponds to the set (i==parents[k] for k in mu(i)).")
100  .add_property("names", &Model::names, "Name of the joints.")
101  .def_readwrite("name", &Model::name, "Name of the model.")
102  .def_readwrite(
103  "referenceConfigurations", &Model::referenceConfigurations,
104  "Map of reference configurations, indexed by user given names.")
105 
106  .def_readwrite("armature", &Model::armature, "Armature vector.")
107  .def_readwrite(
108  "rotorInertia", &Model::rotorInertia, "Vector of rotor inertia parameters.")
109  .def_readwrite(
110  "rotorGearRatio", &Model::rotorGearRatio, "Vector of rotor gear ratio parameters.")
111  .def_readwrite("friction", &Model::friction, "Vector of joint friction parameters.")
112  .def_readwrite("damping", &Model::damping, "Vector of joint damping parameters.")
113  .def_readwrite("effortLimit", &Model::effortLimit, "Joint max effort.")
114  .def_readwrite("velocityLimit", &Model::velocityLimit, "Joint max velocity.")
115  .def_readwrite(
116  "lowerPositionLimit", &Model::lowerPositionLimit, "Limit for joint lower position.")
117  .def_readwrite(
118  "upperPositionLimit", &Model::upperPositionLimit, "Limit for joint upper position.")
119 
120  .def_readwrite("frames", &Model::frames, "Vector of frames contained in the model.")
121 
122  .def_readwrite(
123  "supports", &Model::supports,
124  "Vector of supports. supports[j] corresponds to the list of joints on the "
125  "path between\n"
126  "the current *j* to the root of the kinematic tree.")
127 
128  .def_readwrite(
129  "subtrees", &Model::subtrees,
130  "Vector of subtrees. subtree[j] corresponds to the subtree supported by the joint j.")
131 
132  .def_readwrite(
133  "gravity", &Model::gravity,
134  "Motion vector corresponding to the gravity field expressed in the world Frame.")
135 
136  // Class Methods
137  .def(
138  "addJoint", &ModelPythonVisitor::addJoint0,
139  bp::args("self", "parent_id", "joint_model", "joint_placement", "joint_name"),
140  "Adds a joint to the kinematic tree. The joint is defined by its placement relative "
141  "to its parent joint and its name.")
142  .def(
143  "addJoint", &ModelPythonVisitor::addJoint1,
144  bp::args(
145  "self", "parent_id", "joint_model", "joint_placement", "joint_name", "max_effort",
146  "max_velocity", "min_config", "max_config"),
147  "Adds a joint to the kinematic tree with given bounds. The joint is defined by its "
148  "placement relative to its parent joint and its name."
149  "This signature also takes as input effort, velocity limits as well as the bounds "
150  "on the joint configuration.")
151  .def(
152  "addJoint", &ModelPythonVisitor::addJoint2,
153  bp::args(
154  "self", "parent_id", "joint_model", "joint_placement", "joint_name", "max_effort",
155  "max_velocity", "min_config", "max_config", "friction", "damping"),
156  "Adds a joint to the kinematic tree with given bounds. The joint is defined by its "
157  "placement relative to its parent joint and its name.\n"
158  "This signature also takes as input effort, velocity limits as well as the bounds "
159  "on the joint configuration.\n"
160  "The user should also provide the friction and damping related to the joint.")
161  .def(
162  "addJointFrame", &Model::addJointFrame,
163  (bp::arg("self"), bp::arg("joint_id"), bp::arg("frame_id") = 0),
164  "Add the joint provided by its joint_id as a frame to the frame tree.\n"
165  "The frame_id may be optionally provided.")
166  .def(
167  "appendBodyToJoint", &Model::appendBodyToJoint,
168  bp::args("self", "joint_id", "body_inertia", "body_placement"),
169  "Appends a body to the joint given by its index. The body is defined by its "
170  "inertia, its relative placement regarding to the joint and its name.")
171 
172  .def(
173  "addBodyFrame", &Model::addBodyFrame,
174  bp::args("self", "body_name", "parentJoint", "body_placement", "previous_frame"),
175  "add a body to the frame tree")
176  .def(
177  "getBodyId", &Model::getBodyId, bp::args("self", "name"),
178  "Return the index of a frame of type BODY given by its name")
179  .def(
180  "existBodyName", &Model::existBodyName, bp::args("self", "name"),
181  "Check if a frame of type BODY exists, given its name")
182  .def(
183  "getJointId", &Model::getJointId, bp::args("self", "name"),
184  "Return the index of a joint given by its name")
185  .def(
186  "existJointName", &Model::existJointName, bp::args("self", "name"),
187  "Check if a joint given by its name exists")
188 
189  .def(
190  "getFrameId", &Model::getFrameId,
191  (bp::arg("self"), bp::arg("name"),
192  bp::arg("type") = (FrameType)(JOINT | FIXED_JOINT | BODY | OP_FRAME | SENSOR)),
193  "Returns the index of the frame given by its name and its type."
194  "If the frame is not in the frames vector, it returns the current size of the "
195  "frames vector.")
196 
197  .def(
198  "existFrame", &Model::existFrame,
199  (bp::arg("self"), bp::arg("name"),
200  bp::arg("type") = (FrameType)(JOINT | FIXED_JOINT | BODY | OP_FRAME | SENSOR)),
201  "Returns true if the frame given by its name exists inside the Model with the given "
202  "type.")
203 
204  .def(
205  "addFrame", &Model::addFrame,
206  (bp::arg("self"), bp::arg("frame"), bp::arg("append_inertia") = true),
207  "Add a frame to the vector of frames. If append_inertia set to True, "
208  "the inertia value contained in frame will be added to the inertia supported by the "
209  "parent joint.")
210 
211  .def(
212  "createData", &ModelPythonVisitor::createData, bp::arg("self"),
213  "Create a Data object for the given model.")
214 
215  .def(
216  "check", (bool(Model::*)(const Data &) const) & Model::check, bp::args("self", "data"),
217  "Check consistency of data wrt model.")
218 
219  .def(
220  "hasConfigurationLimit", &Model::hasConfigurationLimit, bp::args("self"),
221  "Returns list of boolean if joints have configuration limit.")
222  .def(
223  "hasConfigurationLimitInTangent", &Model::hasConfigurationLimitInTangent,
224  bp::args("self"),
225  "Returns list of boolean if joints have configuration limit in tangent space .")
226 
227 #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS
228 
229  .def(bp::self == bp::self)
230  .def(bp::self != bp::self)
231 #endif
232 
233  .PINOCCHIO_ADD_STATIC_PROPERTY_READONLY_BYVALUE(
234  Model, gravity981, "Default gravity field value on the Earth.");
235  }
236 
238  Model & model,
240  const JointModel & jmodel,
241  const SE3 & joint_placement,
242  const std::string & joint_name)
243  {
244  return model.addJoint(parent_id, jmodel, joint_placement, joint_name);
245  }
246 
248  Model & model,
250  const JointModel & jmodel,
251  const SE3 & joint_placement,
252  const std::string & joint_name,
253  const VectorXs & max_effort,
254  const VectorXs & max_velocity,
255  const VectorXs & min_config,
256  const VectorXs & max_config)
257  {
258  return model.addJoint(
259  parent_id, jmodel, joint_placement, joint_name, max_effort, max_velocity, min_config,
260  max_config);
261  }
262 
264  Model & model,
266  const JointModel & jmodel,
267  const SE3 & joint_placement,
268  const std::string & joint_name,
269  const VectorXs & max_effort,
270  const VectorXs & max_velocity,
271  const VectorXs & min_config,
272  const VectorXs & max_config,
273  const VectorXs & friction,
274  const VectorXs & damping)
275  {
276  return model.addJoint(
277  parent_id, jmodel, joint_placement, joint_name, max_effort, max_velocity, min_config,
278  max_config, friction, damping);
279  }
280 
281  static Data createData(const Model & model)
282  {
283  return Data(model);
284  }
285 
296  template<typename T>
297  static Index index(std::vector<T> const & x, typename std::vector<T>::value_type const & v)
298  {
299  Index i = 0;
300  for (typename std::vector<T>::const_iterator it = x.begin(); it != x.end(); ++it, ++i)
301  {
302  if (*it == v)
303  {
304  return i;
305  }
306  }
307  return x.size();
308  }
309 
310  /* --- Expose --------------------------------------------------------- */
311  static void expose()
312  {
313  typedef typename Model::ConfigVectorMap ConfigVectorMap;
314  typedef bp::map_indexing_suite<ConfigVectorMap, false> map_indexing_suite;
316  serialize<std::vector<Index>>();
318  serialize<std::vector<IndexVector>>();
322 
323 #if defined(PINOCCHIO_PYTHON_INTERFACE_MAIN_MODULE)
324  bp::scope().attr("StdVec_Double") = bp::scope().attr("StdVec_Scalar"); // alias
325 #endif
326 
327  serialize<std::vector<std::string>>();
328  serialize<std::vector<bool>>();
329 #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION
330  serialize<std::vector<Scalar>>();
331 #endif
332  bp::class_<typename Model::ConfigVectorMap>("StdMap_String_VectorXd")
333  .def(map_indexing_suite())
336 
337  bp::class_<Model>("Model", "Articulated Rigid Body model", bp::no_init)
338  .def(ModelPythonVisitor())
339  .def(CastVisitor<Model>())
343  .def(CopyableVisitor<Model>())
344 #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION
346 #endif
347  ;
348  }
349  };
350 
351  } // namespace python
352 } // namespace pinocchio
353 
354 #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::names
std::vector< std::string > names
Name of the joints.
Definition: multibody/model.hpp:143
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:247
pinocchio::ModelTpl::frames
FrameVector frames
Vector of operational frames registered on the model.
Definition: multibody/model.hpp:177
model.hpp
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::ModelTpl::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::jointPlacements
SE3Vector jointPlacements
Vector of joint placements: placement of a joint i wrt its parent joint frame.
Definition: multibody/model.hpp:117
eigenpy::StdVectorPythonVisitor
pinocchio::python::ModelPythonVisitor::Force
Model::Force Force
Definition: bindings/python/multibody/model.hpp:55
pinocchio::ModelTpl::lowerPositionLimit
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
Definition: multibody/model.hpp:171
pinocchio::ModelTpl::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:20
model.hpp
pinocchio::python::ExposeConstructorByCastVisitor
Definition: bindings/python/utils/cast.hpp:33
eigen-to-python.hpp
exception.hpp
pinocchio::ModelTpl::joints
JointModelVector joints
Vector of joint models.
Definition: multibody/model.hpp:120
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::name
std::string name
Model name.
Definition: multibody/model.hpp:198
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:281
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:153
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::inertias
InertiaVector inertias
Vector of spatial inertias supported by each joint.
Definition: multibody/model.hpp:114
pinocchio::ModelTpl::JointIndex
pinocchio::JointIndex JointIndex
Definition: multibody/model.hpp:68
pinocchio::ModelTpl::referenceConfigurations
ConfigVectorMap referenceConfigurations
Map of reference configurations, indexed by user given names.
Definition: multibody/model.hpp:146
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:189
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::nqs
std::vector< int > nqs
Vector of dimension of the joint configuration subspace.
Definition: multibody/model.hpp:126
pinocchio::python::PrintableVisitor
Set the Python method str and repr to use the overloading operator<<.
Definition: printable.hpp:21
pinocchio::ModelTpl::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::nvs
std::vector< int > nvs
Dimension of the *i*th joint tangent subspace.
Definition: multibody/model.hpp:132
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::python::ModelPythonVisitor::JointModel
Model::JointModel JointModel
Definition: bindings/python/multibody/model.hpp:48
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:140
serializable.hpp
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:123
pinocchio::ModelTpl::IndexVector
std::vector< Index > IndexVector
Definition: multibody/model.hpp:71
pinocchio::python::ModelPythonVisitor::visit
void visit(PyClass &cl) const
Definition: bindings/python/multibody/model.hpp:66
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.
python
pinocchio::ModelTpl::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
Definition: multibody/joint/fwd.hpp:155
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:237
pinocchio::python::ModelPythonVisitor::VectorXs
Model::VectorXs VectorXs
Definition: bindings/python/multibody/model.hpp:61
pinocchio::ForceTpl< Scalar, Options >
pinocchio::ModelTpl::FrameIndex
pinocchio::FrameIndex FrameIndex
Definition: multibody/model.hpp:70
pinocchio::python::ModelPythonVisitor::JointModelVariant
JointModel::JointModelVariant JointModelVariant
Definition: bindings/python/multibody/model.hpp:49
pinocchio::ModelTpl::rotorGearRatio
TangentVectorType rotorGearRatio
Vector of rotor gear ratio parameters.
Definition: multibody/model.hpp:156
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:150
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
x
x
pinocchio::ModelTpl::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Definition: multibody/model.hpp:81
pinocchio::ModelTpl::Scalar
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
Definition: multibody/model.hpp:52
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::nframes
int nframes
Number of operational frames.
Definition: multibody/model.hpp:111
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:297
pinocchio::python::ModelPythonVisitor::Inertia
Model::Inertia Inertia
Definition: bindings/python/multibody/model.hpp:57
pinocchio::ModelTpl::velocityLimit
TangentVectorType velocityLimit
Vector of maximal joint velocities.
Definition: multibody/model.hpp:168
pinocchio::ModelTpl::nbodies
int nbodies
Number of bodies.
Definition: multibody/model.hpp:108
pinocchio::ModelTpl::friction
TangentVectorType friction
Vector of joint friction parameters.
Definition: multibody/model.hpp:159
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::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
pinocchio::ModelTpl::gravity
Motion gravity
Spatial gravity of the model.
Definition: multibody/model.hpp:192
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::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::Index
pinocchio::Index Index
Definition: multibody/model.hpp:67
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::damping
TangentVectorType damping
Vector of joint damping parameters.
Definition: multibody/model.hpp:162
pinocchio::ModelTpl::nv
int nv
Dimension of the velocity vector space.
Definition: multibody/model.hpp:102
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:91
pinocchio::JointModelTpl::JointModelVariant
JointCollection::JointModelVariant JointModelVariant
Definition: joint-generic.hpp:273
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:263
pinocchio::FIXED_JOINT
@ FIXED_JOINT
fixed joint frame: joint frame but for a fixed joint
Definition: multibody/frame.hpp:35
cl
cl
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:184
pinocchio::ModelTpl::check
bool check() const
Run check(fusion::list) with DEFAULT_CHECKERS as argument.
Definition: default-check.hpp:23
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...
memory.hpp
pinocchio::ModelTpl::effortLimit
TangentVectorType effortLimit
Vector of maximal joint torques.
Definition: multibody/model.hpp:165
printable.hpp
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:136
std-vector.hpp
pickle-map.hpp
pinocchio::python::ModelPythonVisitor::expose
static void expose()
Definition: bindings/python/multibody/model.hpp:311
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:129
pinocchio::MotionTpl< Scalar, Options >
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::python::ModelPythonVisitor::JointIndex
Model::JointIndex JointIndex
Definition: bindings/python/multibody/model.hpp:47
pinocchio::ModelTpl::upperPositionLimit
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
Definition: multibody/model.hpp:174
pinocchio::BODY
@ BODY
body frame: attached to the collision, inertial or visual properties of a link
Definition: multibody/frame.hpp:36
pinocchio::ModelTpl::nq
int nq
Dimension of the configuration vector representation.
Definition: multibody/model.hpp:99
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:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::ModelTpl::njoints
int njoints
Number of joints.
Definition: multibody/model.hpp:105


pinocchio
Author(s):
autogenerated on Sat Jun 1 2024 02:40:37