bindings/python/spatial/inertia.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2024 CNRS INRIA
3 // Copyright (c) 2016 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
6 #ifndef __pinocchio_python_spatial_inertia_hpp__
7 #define __pinocchio_python_spatial_inertia_hpp__
8 
9 #include <eigenpy/exception.hpp>
10 #include <eigenpy/eigenpy.hpp>
11 #include <eigenpy/memory.hpp>
12 #include <boost/python/tuple.hpp>
13 
15 
19 
20 #if EIGENPY_VERSION_AT_MOST(2, 8, 1)
24 #endif
25 
26 namespace pinocchio
27 {
28  namespace python
29  {
30  namespace bp = boost::python;
31 
32  template<typename Inertia>
33  struct InertiaPythonVisitor : public boost::python::def_visitor<InertiaPythonVisitor<Inertia>>
34  {
35  enum
36  {
38  };
39  typedef typename Inertia::Scalar Scalar;
40  typedef typename Inertia::Vector3 Vector3;
41  typedef typename Inertia::Matrix3 Matrix3;
42  typedef typename Inertia::Vector6 Vector6;
43  typedef typename Inertia::Matrix6 Matrix6;
44 
45  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> VectorXs;
48 
49  public:
50  template<class PyClass>
51  void visit(PyClass & cl) const
52  {
53  static const Scalar dummy_precision = Eigen::NumTraits<Scalar>::dummy_precision();
54  cl.def(
55  "__init__",
56  bp::make_constructor(
57  &InertiaPythonVisitor::makeFromMCI, bp::default_call_policies(),
58  bp::args("mass", "lever", "inertia")),
59  "Initialize from mass, lever and 3d inertia.")
60 
61  .def(bp::init<>(bp::arg("self"), "Default constructor."))
62  .def(bp::init<const Inertia &>((bp::arg("self"), bp::arg("clone")), "Copy constructor"))
63 
64  .add_property(
66  "Mass of the Spatial Inertia.")
67  .add_property(
68  "lever",
69  bp::make_function(
70  (typename Inertia::Vector3 & (Inertia::*)()) & Inertia::lever,
71  bp::return_internal_reference<>()),
73  "Center of mass location of the Spatial Inertia. It corresponds to the location of the "
74  "center of mass regarding to the frame where the Spatial Inertia is expressed.")
75  .add_property(
77  "Rotational part of the Spatial Inertia, i.e. a symmetric matrix "
78  "representing the rotational inertia around the center of mass.")
79 
80  .def("matrix", (Matrix6(Inertia::*)() const)&Inertia::matrix, bp::arg("self"))
81  .def("inverse", (Matrix6(Inertia::*)() const)&Inertia::inverse, bp::arg("self"))
82  .def(
83  "se3Action", &Inertia::template se3Action<Scalar, Options>, bp::args("self", "M"),
84  "Returns the result of the action of M on *this.")
85  .def(
86  "se3ActionInverse", &Inertia::template se3ActionInverse<Scalar, Options>,
87  bp::args("self", "M"), "Returns the result of the action of the inverse of M on *this.")
88 
89  .def(
90  "setIdentity", &Inertia::setIdentity, bp::arg("self"),
91  "Set *this to be the Identity inertia.")
92  .def(
93  "setZero", &Inertia::setZero, bp::arg("self"),
94  "Set all the components of *this to zero.")
95  .def(
96  "setRandom", &Inertia::setRandom, bp::arg("self"),
97  "Set all the components of *this to random values.")
98 
99  .def(bp::self + bp::self)
100  .def(bp::self += bp::self)
101  .def(bp::self - bp::self)
102  .def(bp::self -= bp::self)
103  .def(bp::self * bp::other<Motion>())
104 
105  .add_property("np", (Matrix6(Inertia::*)() const)&Inertia::matrix)
106  .def(
107  "vxiv", &Inertia::template vxiv<Motion>, bp::args("self", "v"),
108  "Returns the result of v x Iv.")
109  .def(
110  "vtiv", &Inertia::template vtiv<Motion>, bp::args("self", "v"),
111  "Returns the result of v.T * Iv.")
112  .def(
113  "vxi",
114  (Matrix6(Inertia::*)(const MotionDense<Motion> &) const)&Inertia::template vxi<Motion>,
115  bp::args("self", "v"), "Returns the result of v x* I, a 6x6 matrix.")
116  .def(
117  "ivx",
118  (Matrix6(Inertia::*)(const MotionDense<Motion> &) const)&Inertia::template ivx<Motion>,
119  bp::args("self", "v"), "Returns the result of I vx, a 6x6 matrix.")
120  .def(
121  "variation",
122  (Matrix6(Inertia::*)(const MotionDense<Motion> &)
123  const)&Inertia::template variation<Motion>,
124  bp::args("self", "v"), "Returns the time derivative of the inertia.")
125 
126 #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS
127  .def(bp::self == bp::self)
128  .def(bp::self != bp::self)
129 #endif
130 
131 #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS
132  .def(
133  "isApprox", &Inertia::isApprox,
134  (bp::arg("self"), bp::arg("other"), bp::arg("prec") = dummy_precision),
135  "Returns true if *this is approximately equal to other, within the precision given "
136  "by prec.")
137 
138  .def(
139  "isZero", &Inertia::isZero, (bp::arg("self"), bp::arg("prec") = dummy_precision),
140  "Returns true if *this is approximately equal to the zero Inertia, within the "
141  "precision given by prec.")
142 #endif
143 
144  .def("Identity", &Inertia::Identity, "Returns the identity Inertia.")
145  .staticmethod("Identity")
146  .def("Zero", &Inertia::Zero, "Returns the zero Inertia.")
147  .staticmethod("Zero")
148  .def("Random", &Inertia::Random, "Returns a random Inertia.")
149  .staticmethod("Random")
150 
151  .def(
152  "toDynamicParameters", &InertiaPythonVisitor::toDynamicParameters_proxy,
153  bp::arg("self"),
154  "Returns the representation of the matrix as a vector of dynamic parameters."
155  "\nThe parameters are given as v = [m, mc_x, mc_y, mc_z, I_{xx}, I_{xy}, I_{yy}, "
156  "I_{xz}, I_{yz}, I_{zz}]^T "
157  "where I = I_C + mS^T(c)S(c) and I_C has its origin at the barycenter")
158  .def(
159  "FromDynamicParameters", &InertiaPythonVisitor::fromDynamicParameters_proxy,
160  bp::args("dynamic_parameters"),
161  "Builds and inertia matrix from a vector of dynamic parameters."
162  "\nThe parameters are given as dynamic_parameters = [m, mc_x, mc_y, mc_z, I_{xx}, "
163  "I_{xy}, I_{yy}, I_{xz}, I_{yz}, I_{zz}]^T "
164  "where I = I_C + mS^T(c)S(c) and I_C has its origin at the barycenter.")
165  .staticmethod("FromDynamicParameters")
166 
167  .def(
168  "FromSphere", &Inertia::FromSphere, bp::args("mass", "radius"),
169  "Returns the Inertia of a sphere defined by a given mass and radius.")
170  .staticmethod("FromSphere")
171  .def(
172  "FromEllipsoid", &Inertia::FromEllipsoid,
173  bp::args("mass", "length_x", "length_y", "length_z"),
174  "Returns the Inertia of an ellipsoid shape defined by a mass and given dimensions "
175  "the semi-axis of values length_{x,y,z}.")
176  .staticmethod("FromEllipsoid")
177  .def(
178  "FromCylinder", &Inertia::FromCylinder, bp::args("mass", "radius", "length"),
179  "Returns the Inertia of a cylinder defined by its mass, radius and length along the "
180  "Z axis.")
181  .staticmethod("FromCylinder")
182  .def(
183  "FromBox", &Inertia::FromBox, bp::args("mass", "length_x", "length_y", "length_z"),
184  "Returns the Inertia of a box shape with a mass and of dimension the semi axis of "
185  "length_{x,y,z}.")
186  .staticmethod("FromBox")
187  .def(
188  "FromCapsule", &Inertia::FromCapsule, bp::args("mass", "radius", "height"),
189  "Computes the Inertia of a capsule defined by its mass, radius and length along the "
190  "Z axis. Assumes a uniform density.")
191  .staticmethod("FromCapsule")
192 
193  .def(
194  "FromPseudoInertia", &Inertia::FromPseudoInertia, bp::args("pseudo_inertia"),
195  "Returns the Inertia created from a pseudo inertia object.")
196  .staticmethod("FromPseudoInertia")
197 
198  .def(
199  "toPseudoInertia", &Inertia::toPseudoInertia, bp::arg("self"),
200  "Returns the pseudo inertia representation of the inertia.")
201 
202  .def(
203  "FromLogCholeskyParameters", &Inertia::FromLogCholeskyParameters,
204  bp::args("log_cholesky_parameters"),
205  "Returns the Inertia created from log Cholesky parameters.")
206  .staticmethod("FromLogCholeskyParameters")
207 
208  .def("__array__", (Matrix6(Inertia::*)() const)&Inertia::matrix)
209  .def(
210  "__array__", &__array__,
211  (bp::arg("self"), bp::arg("dtype") = bp::object(), bp::arg("copy") = bp::object()))
212 #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION
213  .def_pickle(Pickle())
214 #endif
215  ;
216  }
217 
218  static Scalar getMass(const Inertia & self)
219  {
220  return self.mass();
221  }
222  static void setMass(Inertia & self, Scalar mass)
223  {
224  self.mass() = mass;
225  }
226 
227  static void setLever(Inertia & self, const Vector3 & lever)
228  {
229  self.lever() = lever;
230  }
231 
232  static Matrix3 getInertia(const Inertia & self)
233  {
234  return self.inertia().matrix();
235  }
236  // static void setInertia(Inertia & self, const Vector6 & minimal_inertia) {
237  // self.inertia().data() = minimal_inertia; }
238  static void setInertia(Inertia & self, const Matrix3 & symmetric_inertia)
239  {
240  if (!check_expression_if_real<Scalar>(
241  isZero(symmetric_inertia - symmetric_inertia.transpose())))
242  throw eigenpy::Exception("The 3d inertia should be symmetric.");
243  self.inertia().data() << symmetric_inertia(0, 0), symmetric_inertia(1, 0),
244  symmetric_inertia(1, 1), symmetric_inertia(0, 2), symmetric_inertia(1, 2),
245  symmetric_inertia(2, 2);
246  }
247 
249  {
250  return self.toDynamicParameters();
251  }
252 
254  {
255  if (params.rows() != 10 || params.cols() != 1)
256  {
257  std::ostringstream shape;
258  shape << "(" << params.rows() << ", " << params.cols() << ")";
259  throw std::invalid_argument(
260  "Wrong size: params" + shape.str() + " but should have the following shape (10, 1)");
261  }
262  return Inertia::FromDynamicParameters(params);
263  }
264 
265  static Inertia *
266  makeFromMCI(const Scalar & mass, const Vector3 & lever, const Matrix3 & inertia)
267  {
268 #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS
269  if (!inertia.isApprox(inertia.transpose()))
270  throw eigenpy::Exception("The 3d inertia should be symmetric.");
271  if (
272  (Vector3::UnitX().transpose() * inertia * Vector3::UnitX() < 0)
273  || (Vector3::UnitY().transpose() * inertia * Vector3::UnitY() < 0)
274  || (Vector3::UnitZ().transpose() * inertia * Vector3::UnitZ() < 0))
275  throw eigenpy::Exception("The 3d inertia should be positive.");
276 #endif
277  return new Inertia(mass, lever, inertia);
278  }
279 
280  static void expose()
281  {
282 #if PY_MAJOR_VERSION == 3 && PY_MINOR_VERSION == 6 && EIGENPY_VERSION_AT_LEAST(2, 9, 0)
283  typedef PINOCCHIO_SHARED_PTR_HOLDER_TYPE(Inertia) HolderType;
284 #else
285  typedef ::boost::python::detail::not_specified HolderType;
286 #endif
287  bp::class_<Inertia, HolderType>(
288  "Inertia",
289  "This class represenses a sparse version of a Spatial Inertia and its is defined by its "
290  "mass, its center of mass location and the rotational inertia expressed around this "
291  "center of mass.\n\n"
292  "Supported operations ...",
293  bp::no_init)
295  .def(CastVisitor<Inertia>())
299  }
300 
301  private:
302  static Matrix6 __array__(const Inertia & self, bp::object, bp::object)
303  {
304  return self.matrix();
305  }
306 
307  struct Pickle : bp::pickle_suite
308  {
309  static boost::python::tuple getinitargs(const Inertia & I)
310  {
311  return bp::make_tuple(I.mass(), (Vector3)I.lever(), I.inertia().matrix());
312  }
313 
314  static bool getstate_manages_dict()
315  {
316  return true;
317  }
318  };
319 
320  }; // struct InertiaPythonVisitor
321 
322  template<typename PseudoInertia>
324  : public boost::python::def_visitor<PseudoInertiaPythonVisitor<PseudoInertia>>
325  {
326  enum
327  {
329  };
330  typedef typename PseudoInertia::Scalar Scalar;
331  typedef typename PseudoInertia::Vector3 Vector3;
332  typedef typename PseudoInertia::Matrix3 Matrix3;
334  typedef typename PseudoInertia::Matrix4 Matrix4;
335  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> VectorXs;
336 
337  public:
338  template<class PyClass>
339  void visit(PyClass & cl) const
340  {
341  cl.def(bp::init<const Scalar &, const Vector3 &, const Matrix3 &>(
342  (bp::arg("self"), bp::arg("mass"), bp::arg("h"), bp::arg("sigma")),
343  "Initialize from mass, vector part of the pseudo inertia and matrix part of the "
344  "pseudo inertia."))
345  .def(bp::init<const PseudoInertia &>(
346  (bp::arg("self"), bp::arg("clone")), "Copy constructor"))
347  .add_property(
349  "Mass of the Pseudo Inertia.")
350  .add_property(
352  "Vector part of the Pseudo Inertia.")
353  .add_property(
355  "Matrix part of the Pseudo Inertia.")
356 
357  .def(
358  "toMatrix", &PseudoInertia::toMatrix, bp::arg("self"),
359  "Returns the pseudo inertia as a 4x4 matrix.")
360  .def(
362  bp::arg("self"), "Returns the dynamic parameters representation.")
363  .def(
364  "toInertia", &PseudoInertia::toInertia, bp::arg("self"),
365  "Returns the inertia representation.")
366  .def(
368  bp::args("dynamic_parameters"),
369  "Builds a pseudo inertia matrix from a vector of dynamic parameters."
370  "\nThe parameters are given as dynamic_parameters = [m, h_x, h_y, h_z, I_{xx}, "
371  "I_{xy}, I_{yy}, I_{xz}, I_{yz}, I_{zz}]^T.")
372  .staticmethod("FromDynamicParameters")
373 
374  .def(
375  "FromMatrix", &PseudoInertia::FromMatrix, bp::args("pseudo_inertia_matrix"),
376  "Returns the Pseudo Inertia from a 4x4 matrix.")
377  .staticmethod("FromMatrix")
378 
379  .def(
380  "FromInertia", &PseudoInertia::FromInertia, bp::args("inertia"),
381  "Returns the Pseudo Inertia from an Inertia object.")
382  .staticmethod("FromInertia")
383 
384  .def("__array__", &PseudoInertia::toMatrix)
385  .def(
386  "__array__", &__array__,
387  (bp::arg("self"), bp::arg("dtype") = bp::object(), bp::arg("copy") = bp::object()))
388 #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION
389  .def_pickle(Pickle())
390 #endif
391  ;
392  }
393 
394  static Scalar getMass(const PseudoInertia & self)
395  {
396  return self.mass;
397  }
398  static void setMass(PseudoInertia & self, Scalar mass)
399  {
400  self.mass = mass;
401  }
402 
403  static Vector3 getH(const PseudoInertia & self)
404  {
405  return self.h;
406  }
407  static void setH(PseudoInertia & self, const Vector3 & h)
408  {
409  self.h = h;
410  }
411 
412  static Matrix3 getSigma(const PseudoInertia & self)
413  {
414  return self.sigma;
415  }
416  static void setSigma(PseudoInertia & self, const Matrix3 & sigma)
417  {
418  self.sigma = sigma;
419  }
420 
422  {
423  return self.toDynamicParameters();
424  }
425 
427  {
428  if (params.rows() != 10 || params.cols() != 1)
429  {
430  std::ostringstream shape;
431  shape << "(" << params.rows() << ", " << params.cols() << ")";
432  throw std::invalid_argument(
433  "Wrong size: params" + shape.str() + " but should have the following shape (10, 1)");
434  }
436  }
437 
438  static void expose()
439  {
440 #if PY_MAJOR_VERSION == 3 && PY_MINOR_VERSION == 6 && EIGENPY_VERSION_AT_LEAST(2, 9, 0)
442 #else
443  typedef ::boost::python::detail::not_specified HolderType;
444 #endif
445  bp::class_<PseudoInertia, HolderType>(
446  "PseudoInertia",
447  "This class represents a pseudo inertia matrix and it is defined by its mass, vector "
448  "part, and 3x3 matrix part.\n\n"
449  "Supported operations ...",
450  bp::no_init)
456  }
457 
458  private:
459  static Matrix4 __array__(const PseudoInertia & self, bp::object, bp::object)
460  {
461  return self.toMatrix();
462  }
463 
464  struct Pickle : bp::pickle_suite
465  {
466  static boost::python::tuple getinitargs(const PseudoInertia & pi)
467  {
468  return bp::make_tuple(pi.mass, pi.h, pi.sigma);
469  }
470 
471  static bool getstate_manages_dict()
472  {
473  return true;
474  }
475  };
476 
477  }; // struct PseudoInertiaPythonVisitor
478 
479  template<typename LogCholeskyParameters>
481  : public boost::python::def_visitor<LogCholeskyParametersPythonVisitor<LogCholeskyParameters>>
482  {
483  enum
484  {
486  };
490  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> VectorXs;
491  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options> MatrixXs;
492 
493  public:
494  template<class PyClass>
495  void visit(PyClass & cl) const
496  {
497  cl.def(
498  "__init__",
499  bp::make_constructor(
500  &LogCholeskyParametersPythonVisitor::makeFromParameters, bp::default_call_policies(),
501  bp::args("log_cholesky_parameters")),
502  "Initialize from log cholesky parameters.")
503  .def(bp::init<const LogCholeskyParameters &>(
504  (bp::arg("self"), bp::arg("clone")), "Copy constructor"))
505 
506  .add_property(
508  &LogCholeskyParametersPythonVisitor::setParameters, "Log Cholesky parameters.")
509 
510  .def(
512  bp::arg("self"), "Returns the dynamic parameters representation.")
513  .def(
514  "toPseudoInertia", &LogCholeskyParameters::toPseudoInertia, bp::arg("self"),
515  "Returns the Pseudo Inertia representation.")
516  .def(
517  "toInertia", &LogCholeskyParameters::toInertia, bp::arg("self"),
518  "Returns the Inertia representation.")
519  .def(
521  bp::arg("self"), "Calculates the Jacobian of the log Cholesky parameters.")
522 
524  .def(
525  "__array__", &__array__,
526  (bp::arg("self"), bp::arg("dtype") = bp::object(), bp::arg("copy") = bp::object()))
527 #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION
528  .def_pickle(Pickle())
529 #endif
530  ;
531  }
532 
534  {
535  if (params.rows() != 10 || params.cols() != 1)
536  {
537  std::ostringstream shape;
538  shape << "(" << params.rows() << ", " << params.cols() << ")";
539  throw std::invalid_argument(
540  "Wrong size: params" + shape.str() + " but should have the following shape (10, 1)");
541  }
542  return new LogCholeskyParameters(params);
543  }
544 
546  {
547  return self.parameters;
548  }
549  static void setParameters(LogCholeskyParameters & self, const Vector10 & parameters)
550  {
551  self.parameters = parameters;
552  }
553 
555  {
556  return self.toDynamicParameters();
557  }
558 
560  {
561  return self.calculateJacobian();
562  }
563 
564  static void expose()
565  {
566 #if PY_MAJOR_VERSION == 3 && PY_MINOR_VERSION == 6 && EIGENPY_VERSION_AT_LEAST(2, 9, 0)
568 #else
569  typedef ::boost::python::detail::not_specified HolderType;
570 #endif
571  bp::class_<LogCholeskyParameters, HolderType>(
572  "LogCholeskyParameters",
573  "This class represents log Cholesky parameters.\n\n"
574  "Supported operations ...",
575  bp::no_init)
582  }
583 
584  private:
585  static VectorXs __array__(const LogCholeskyParameters & self, bp::object, bp::object)
586  {
587  return self.parameters;
588  }
589 
590  struct Pickle : bp::pickle_suite
591  {
592  static boost::python::tuple getinitargs(const LogCholeskyParameters & lcp)
593  {
594  return bp::make_tuple(lcp.parameters);
595  }
596 
597  static bool getstate_manages_dict()
598  {
599  return true;
600  }
601  };
602 
603  }; // struct LogCholeskyParametersPythonVisitor
604 
605  } // namespace python
606 } // namespace pinocchio
607 
608 #endif // ifndef __pinocchio_python_spatial_inertia_hpp__
pinocchio::python::InertiaPythonVisitor::Scalar
Inertia::Scalar Scalar
Definition: bindings/python/spatial/inertia.hpp:39
pinocchio::InertiaTpl< context::Scalar, context::Options >
pinocchio::PseudoInertiaTpl
A structure representing a pseudo inertia matrix.
Definition: spatial/fwd.hpp:62
pinocchio::python::InertiaPythonVisitor::fromDynamicParameters_proxy
static Inertia fromDynamicParameters_proxy(const VectorXs &params)
Definition: bindings/python/spatial/inertia.hpp:253
pinocchio::python::PseudoInertiaPythonVisitor::Pickle
Definition: bindings/python/spatial/inertia.hpp:464
pinocchio::python::InertiaPythonVisitor::makeFromMCI
static Inertia * makeFromMCI(const Scalar &mass, const Vector3 &lever, const Matrix3 &inertia)
Definition: bindings/python/spatial/inertia.hpp:266
pinocchio::python::InertiaPythonVisitor::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Definition: bindings/python/spatial/inertia.hpp:45
pinocchio::python::InertiaPythonVisitor::setInertia
static void setInertia(Inertia &self, const Matrix3 &symmetric_inertia)
Definition: bindings/python/spatial/inertia.hpp:238
boost::python
pinocchio::InertiaTpl< context::Scalar, context::Options >::FromEllipsoid
static InertiaTpl FromEllipsoid(const Scalar mass, const Scalar x, const Scalar y, const Scalar z)
Computes the Inertia of an ellipsoid defined by its mass and main semi-axis dimensions (x,...
Definition: spatial/inertia.hpp:389
pinocchio::PseudoInertiaTpl::h
Vector3 h
Vector part of the pseudo inertia.
Definition: spatial/inertia.hpp:957
pinocchio::python::PseudoInertiaPythonVisitor::Options
@ Options
Definition: bindings/python/spatial/inertia.hpp:328
PINOCCHIO_SHARED_PTR_HOLDER_TYPE
#define PINOCCHIO_SHARED_PTR_HOLDER_TYPE(T)
Definition: bindings/python/fwd.hpp:17
pinocchio::InertiaTpl< context::Scalar, context::Options >::setZero
void setZero()
Definition: spatial/inertia.hpp:342
pinocchio::InertiaTpl< context::Scalar, context::Options >::lever
const Vector3 & lever() const
Definition: spatial/inertia.hpp:848
pinocchio::python::InertiaPythonVisitor::Force
ForceTpl< Scalar, Options > Force
Definition: bindings/python/spatial/inertia.hpp:47
pinocchio::python::PseudoInertiaPythonVisitor::fromDynamicParameters_proxy
static PseudoInertia fromDynamicParameters_proxy(const VectorXs &params)
Definition: bindings/python/spatial/inertia.hpp:426
pinocchio::python::InertiaPythonVisitor::visit
void visit(PyClass &cl) const
Definition: bindings/python/spatial/inertia.hpp:51
pinocchio::PseudoInertiaTpl::Vector10
Eigen::Matrix< Scalar, 10, 1, Options > Vector10
Definition: spatial/inertia.hpp:953
pinocchio::python::InertiaPythonVisitor::getInertia
static Matrix3 getInertia(const Inertia &self)
Definition: bindings/python/spatial/inertia.hpp:232
pinocchio::LogCholeskyParametersTpl::Vector10
Eigen::Matrix< Scalar, 10, 1, Options > Vector10
Definition: spatial/inertia.hpp:1109
eigenpy.hpp
pinocchio::python::LogCholeskyParametersPythonVisitor::Pickle::getstate_manages_dict
static bool getstate_manages_dict()
Definition: bindings/python/spatial/inertia.hpp:597
pinocchio::python::PseudoInertiaPythonVisitor::expose
static void expose()
Definition: bindings/python/spatial/inertia.hpp:438
pinocchio::python::PseudoInertiaPythonVisitor::getH
static Vector3 getH(const PseudoInertia &self)
Definition: bindings/python/spatial/inertia.hpp:403
pinocchio::isZero
bool isZero(const Eigen::MatrixBase< MatrixLike > &m, const typename MatrixLike::RealScalar &prec=Eigen::NumTraits< typename MatrixLike::Scalar >::dummy_precision())
Definition: math/matrix.hpp:59
pinocchio::python::PseudoInertiaPythonVisitor::Matrix4
PseudoInertia::Matrix4 Matrix4
Definition: bindings/python/spatial/inertia.hpp:334
pinocchio::python::InertiaPythonVisitor::expose
static void expose()
Definition: bindings/python/spatial/inertia.hpp:280
pinocchio::InertiaTpl< context::Scalar, context::Options >::FromPseudoInertia
static InertiaTpl FromPseudoInertia(const PseudoInertia &pseudo_inertia)
Create an InertiaTpl object from a PseudoInertia object.
Definition: spatial/inertia.hpp:581
pinocchio::python::PseudoInertiaPythonVisitor::Scalar
PseudoInertia::Scalar Scalar
Definition: bindings/python/spatial/inertia.hpp:330
pinocchio::python::PseudoInertiaPythonVisitor::Vector3
PseudoInertia::Vector3 Vector3
Definition: bindings/python/spatial/inertia.hpp:331
pinocchio::python::LogCholeskyParametersPythonVisitor::__array__
static VectorXs __array__(const LogCholeskyParameters &self, bp::object, bp::object)
Definition: bindings/python/spatial/inertia.hpp:585
pinocchio::Inertia
InertiaTpl< context::Scalar, context::Options > Inertia
Definition: spatial/fwd.hpp:69
pinocchio::python::LogCholeskyParametersPythonVisitor::calculateJacobian_proxy
static MatrixXs calculateJacobian_proxy(const LogCholeskyParameters &self)
Definition: bindings/python/spatial/inertia.hpp:559
pinocchio::python::LogCholeskyParametersPythonVisitor::visit
void visit(PyClass &cl) const
Definition: bindings/python/spatial/inertia.hpp:495
pinocchio::PseudoInertiaTpl::toInertia
InertiaTpl< Scalar, Options > toInertia() const
Converts the PseudoInertiaTpl object to an InertiaTpl object.
Definition: spatial/inertia.hpp:1053
inertia.hpp
pinocchio::LogCholeskyParametersTpl::toPseudoInertia
PseudoInertia toPseudoInertia() const
Converts the LogCholeskyParametersTpl object to a PseudoInertiaTpl object.
Definition: spatial/inertia.hpp:1171
pinocchio::python::ExposeConstructorByCastVisitor
Definition: bindings/python/utils/cast.hpp:33
pinocchio::LogCholeskyParametersTpl::parameters
Vector10 parameters
10-dimensional vector of log Cholesky parameters
Definition: spatial/inertia.hpp:1113
pinocchio::MotionDense
Definition: context/casadi.hpp:36
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
exception.hpp
pinocchio::python::PseudoInertiaPythonVisitor::__array__
static Matrix4 __array__(const PseudoInertia &self, bp::object, bp::object)
Definition: bindings/python/spatial/inertia.hpp:459
pinocchio::python::LogCholeskyParametersPythonVisitor::getParameters
static VectorXs getParameters(const LogCholeskyParameters &self)
Definition: bindings/python/spatial/inertia.hpp:545
pinocchio::python::InertiaPythonVisitor::Pickle::getinitargs
static boost::python::tuple getinitargs(const Inertia &I)
Definition: bindings/python/spatial/inertia.hpp:309
pinocchio::python::LogCholeskyParametersPythonVisitor::expose
static void expose()
Definition: bindings/python/spatial/inertia.hpp:564
pinocchio::LogCholeskyParameters
LogCholeskyParametersTpl< context::Scalar, context::Options > LogCholeskyParameters
Definition: spatial/fwd.hpp:73
pinocchio::python::PseudoInertiaPythonVisitor::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Definition: bindings/python/spatial/inertia.hpp:335
pinocchio::PseudoInertiaTpl::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: spatial/inertia.hpp:951
pinocchio::python::PseudoInertiaPythonVisitor
Definition: bindings/python/spatial/inertia.hpp:323
pinocchio::PseudoInertiaTpl::Matrix3
Eigen::Matrix< Scalar, 3, 3, Options > Matrix3
Definition: spatial/inertia.hpp:952
pinocchio::InertiaTpl< context::Scalar, context::Options >::toPseudoInertia
PseudoInertia toPseudoInertia() const
Convert the InertiaTpl object to a 4x4 pseudo inertia matrix.
Definition: spatial/inertia.hpp:591
pinocchio::python::PseudoInertiaPythonVisitor::setMass
static void setMass(PseudoInertia &self, Scalar mass)
Definition: bindings/python/spatial/inertia.hpp:398
pinocchio::python::LogCholeskyParametersPythonVisitor::MatrixXs
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
Definition: bindings/python/spatial/inertia.hpp:491
pinocchio::InertiaTpl< context::Scalar, context::Options >::Zero
static InertiaTpl Zero()
Definition: spatial/inertia.hpp:337
pinocchio::LogCholeskyParametersTpl::Scalar
_Scalar Scalar
Definition: spatial/inertia.hpp:1104
pinocchio::python::InertiaPythonVisitor::Vector6
Inertia::Vector6 Vector6
Definition: bindings/python/spatial/inertia.hpp:42
pinocchio::python::LogCholeskyParametersPythonVisitor::Scalar
LogCholeskyParameters::Scalar Scalar
Definition: bindings/python/spatial/inertia.hpp:487
pinocchio::python::LogCholeskyParametersPythonVisitor::toDynamicParameters_proxy
static VectorXs toDynamicParameters_proxy(const LogCholeskyParameters &self)
Definition: bindings/python/spatial/inertia.hpp:554
pinocchio::PseudoInertiaTpl::sigma
Matrix3 sigma
3x3 matrix part of the pseudo inertia
Definition: spatial/inertia.hpp:958
cast.hpp
pinocchio::PseudoInertiaTpl::mass
Scalar mass
Mass of the pseudo inertia.
Definition: spatial/inertia.hpp:956
pinocchio::InertiaTpl::inertia
const Symmetric3 & inertia() const
Definition: spatial/inertia.hpp:852
pinocchio::InertiaTpl< context::Scalar, context::Options >::Options
@ Options
Definition: spatial/inertia.hpp:271
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION
#define EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(...)
pinocchio::python::PrintableVisitor
Set the Python method str and repr to use the overloading operator<<.
Definition: printable.hpp:21
pinocchio::InertiaTpl::mass
Scalar mass() const
Definition: spatial/inertia.hpp:844
pinocchio::InertiaTpl< context::Scalar, context::Options >::FromLogCholeskyParameters
static InertiaTpl FromLogCholeskyParameters(const LogCholeskyParameters &log_cholesky)
Create an InertiaTpl object from log Cholesky parameters.
Definition: spatial/inertia.hpp:604
pinocchio::python::InertiaPythonVisitor::Motion
MotionTpl< Scalar, Options > Motion
Definition: bindings/python/spatial/inertia.hpp:46
pinocchio::python::PseudoInertiaPythonVisitor::Pickle::getinitargs
static boost::python::tuple getinitargs(const PseudoInertia &pi)
Definition: bindings/python/spatial/inertia.hpp:466
pinocchio::InertiaTpl< context::Scalar, context::Options >::setRandom
void setRandom()
Definition: spatial/inertia.hpp:472
pinocchio::python::PseudoInertiaPythonVisitor::Matrix3
PseudoInertia::Matrix3 Matrix3
Definition: bindings/python/spatial/inertia.hpp:332
pinocchio::LogCholeskyParametersTpl
A structure representing log Cholesky parameters.
Definition: spatial/fwd.hpp:64
pinocchio::python::InertiaPythonVisitor::setMass
static void setMass(Inertia &self, Scalar mass)
Definition: bindings/python/spatial/inertia.hpp:222
pinocchio::LogCholeskyParametersTpl::toInertia
InertiaTpl< Scalar, Options > toInertia() const
Converts the LogCholeskyParametersTpl object to an InertiaTpl object.
Definition: spatial/inertia.hpp:1181
pinocchio::PseudoInertiaTpl::Matrix4
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
Definition: spatial/inertia.hpp:950
python
pinocchio::python::LogCholeskyParametersPythonVisitor::Pickle::getinitargs
static boost::python::tuple getinitargs(const LogCholeskyParameters &lcp)
Definition: bindings/python/spatial/inertia.hpp:592
pinocchio::python::PseudoInertiaPythonVisitor::getMass
static Scalar getMass(const PseudoInertia &self)
Definition: bindings/python/spatial/inertia.hpp:394
pinocchio::ForceTpl< Scalar, Options >
pinocchio::python::CopyableVisitor
Add the Python method copy to allow a copy of this by calling the copy constructor.
Definition: copyable.hpp:21
pinocchio::InertiaTpl< context::Scalar, context::Options >::FromCapsule
static InertiaTpl FromCapsule(const Scalar mass, const Scalar radius, const Scalar height)
Computes the Inertia of a capsule defined by its mass, radius and length along the Z axis....
Definition: spatial/inertia.hpp:439
pinocchio::python::InertiaPythonVisitor::toDynamicParameters_proxy
static VectorXs toDynamicParameters_proxy(const Inertia &self)
Definition: bindings/python/spatial/inertia.hpp:248
pinocchio::inverse
void inverse(const Eigen::MatrixBase< MatrixIn > &m_in, const Eigen::MatrixBase< MatrixOut > &dest)
Definition: math/matrix.hpp:273
pinocchio::InertiaTpl< context::Scalar, context::Options >::Random
static InertiaTpl Random()
Definition: spatial/inertia.hpp:361
eigenpy::Exception
pinocchio::context::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: context/generic.hpp:53
pinocchio::PseudoInertiaTpl::FromInertia
static PseudoInertiaTpl FromInertia(const InertiaTpl< Scalar, Options > &inertia)
Constructs a PseudoInertiaTpl object from an InertiaTpl object.
Definition: spatial/inertia.hpp:1043
pinocchio::python::PseudoInertiaPythonVisitor::toDynamicParameters_proxy
static VectorXs toDynamicParameters_proxy(const PseudoInertia &self)
Definition: bindings/python/spatial/inertia.hpp:421
pinocchio::python::InertiaPythonVisitor::setLever
static void setLever(Inertia &self, const Vector3 &lever)
Definition: bindings/python/spatial/inertia.hpp:227
pinocchio::python::CastVisitor
Add the Python method cast.
Definition: bindings/python/utils/cast.hpp:23
copyable.hpp
pinocchio::PseudoInertiaTpl::FromMatrix
static PseudoInertiaTpl FromMatrix(const Matrix4 &pseudo_inertia)
Constructs a PseudoInertiaTpl object from a 4x4 pseudo inertia matrix.
Definition: spatial/inertia.hpp:986
anymal-simulation.mass
mass
Definition: anymal-simulation.py:62
ur5x4.h
h
Definition: ur5x4.py:50
pinocchio::Symmetric3Tpl::matrix
Matrix3 matrix() const
Definition: spatial/symmetric3.hpp:304
pinocchio::PseudoInertiaTpl::Scalar
_Scalar Scalar
Definition: spatial/inertia.hpp:945
pinocchio::PseudoInertiaTpl::FromDynamicParameters
static PseudoInertiaTpl FromDynamicParameters(const Eigen::MatrixBase< Vector10Like > &dynamic_params)
Constructs a PseudoInertiaTpl object from dynamic parameters.
Definition: spatial/inertia.hpp:1001
pinocchio::python::InertiaPythonVisitor::getMass
static Scalar getMass(const Inertia &self)
Definition: bindings/python/spatial/inertia.hpp:218
pinocchio::python::LogCholeskyParametersPythonVisitor::Matrix10
LogCholeskyParameters::Matrix10 Matrix10
Definition: bindings/python/spatial/inertia.hpp:489
pinocchio::python::PseudoInertiaPythonVisitor::getSigma
static Matrix3 getSigma(const PseudoInertia &self)
Definition: bindings/python/spatial/inertia.hpp:412
pinocchio::python::InertiaPythonVisitor::Vector3
Inertia::Vector3 Vector3
Definition: bindings/python/spatial/inertia.hpp:40
pinocchio::InertiaTpl< context::Scalar, context::Options >::FromDynamicParameters
static InertiaTpl FromDynamicParameters(const Eigen::MatrixBase< Vector10Like > &params)
Definition: spatial/inertia.hpp:561
pinocchio::InertiaTpl< context::Scalar, context::Options >::Identity
static InertiaTpl Identity()
Definition: spatial/inertia.hpp:349
pinocchio::python::InertiaPythonVisitor::Options
@ Options
Definition: bindings/python/spatial/inertia.hpp:37
pinocchio::python::PseudoInertiaPythonVisitor::Pickle::getstate_manages_dict
static bool getstate_manages_dict()
Definition: bindings/python/spatial/inertia.hpp:471
pinocchio::python::LogCholeskyParametersPythonVisitor::setParameters
static void setParameters(LogCholeskyParameters &self, const Vector10 &parameters)
Definition: bindings/python/spatial/inertia.hpp:549
cl
cl
pinocchio::LogCholeskyParametersTpl::Options
@ Options
Definition: spatial/inertia.hpp:1107
memory.hpp
pinocchio::PseudoInertiaTpl::toMatrix
Matrix4 toMatrix() const
Converts the PseudoInertiaTpl object to a 4x4 matrix.
Definition: spatial/inertia.hpp:971
pinocchio::python::InertiaPythonVisitor::Pickle::getstate_manages_dict
static bool getstate_manages_dict()
Definition: bindings/python/spatial/inertia.hpp:314
printable.hpp
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::InertiaTpl< context::Scalar, context::Options >::FromSphere
static InertiaTpl FromSphere(const Scalar mass, const Scalar radius)
Computes the Inertia of a sphere defined by its mass and its radius.
Definition: spatial/inertia.hpp:374
pinocchio::python::PseudoInertiaPythonVisitor::setSigma
static void setSigma(PseudoInertia &self, const Matrix3 &sigma)
Definition: bindings/python/spatial/inertia.hpp:416
pinocchio::MotionTpl< Scalar, Options >
pinocchio::python::PseudoInertiaPythonVisitor::Vector10
PseudoInertia::Vector10 Vector10
Definition: bindings/python/spatial/inertia.hpp:333
pinocchio::python::PseudoInertiaPythonVisitor::visit
void visit(PyClass &cl) const
Definition: bindings/python/spatial/inertia.hpp:339
pinocchio::python::LogCholeskyParametersPythonVisitor
Definition: bindings/python/spatial/inertia.hpp:480
pinocchio::python::InertiaPythonVisitor::Pickle
Definition: bindings/python/spatial/inertia.hpp:307
pinocchio::python::LogCholeskyParametersPythonVisitor::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Definition: bindings/python/spatial/inertia.hpp:490
pinocchio::InertiaTpl< context::Scalar, context::Options >::FromCylinder
static InertiaTpl FromCylinder(const Scalar mass, const Scalar radius, const Scalar length)
Computes the Inertia of a cylinder defined by its mass, radius and length along the Z axis.
Definition: spatial/inertia.hpp:406
pinocchio::LogCholeskyParametersTpl::Matrix10
Eigen::Matrix< Scalar, 10, 10, Options > Matrix10
Definition: spatial/inertia.hpp:1110
pinocchio::InertiaTpl< context::Scalar, context::Options >::setIdentity
void setIdentity()
Definition: spatial/inertia.hpp:354
pinocchio::python::LogCholeskyParametersPythonVisitor::makeFromParameters
static LogCholeskyParameters * makeFromParameters(const VectorXs &params)
Definition: bindings/python/spatial/inertia.hpp:533
pinocchio::python::InertiaPythonVisitor
Definition: bindings/python/spatial/inertia.hpp:33
pinocchio::python::LogCholeskyParametersPythonVisitor::Options
@ Options
Definition: bindings/python/spatial/inertia.hpp:485
pinocchio::python::PseudoInertiaPythonVisitor::setH
static void setH(PseudoInertia &self, const Vector3 &h)
Definition: bindings/python/spatial/inertia.hpp:407
pinocchio::python::LogCholeskyParametersPythonVisitor::Vector10
LogCholeskyParameters::Vector10 Vector10
Definition: bindings/python/spatial/inertia.hpp:488
pinocchio::python::InertiaPythonVisitor::__array__
static Matrix6 __array__(const Inertia &self, bp::object, bp::object)
Definition: bindings/python/spatial/inertia.hpp:302
pinocchio::python::InertiaPythonVisitor::Matrix6
Inertia::Matrix6 Matrix6
Definition: bindings/python/spatial/inertia.hpp:43
pinocchio::python::InertiaPythonVisitor::Matrix3
Inertia::Matrix3 Matrix3
Definition: bindings/python/spatial/inertia.hpp:41
pinocchio::PseudoInertiaTpl::Options
@ Options
Definition: spatial/inertia.hpp:948
pinocchio::python::LogCholeskyParametersPythonVisitor::Pickle
Definition: bindings/python/spatial/inertia.hpp:590
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:29