6 #ifndef __pinocchio_python_spatial_inertia_hpp__ 7 #define __pinocchio_python_spatial_inertia_hpp__ 12 #include <boost/python/tuple.hpp> 14 #include "pinocchio/spatial/inertia.hpp" 27 template<
typename T>
struct call;
29 template<
typename Scalar,
int Options>
34 static bool isApprox(
const Inertia &
self,
const Inertia & other,
35 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
37 return self.isApprox(other,prec);
40 static bool isZero(
const Inertia &
self,
41 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
43 return self.isZero(prec);
50 template<
typename Inertia>
52 :
public boost::python::def_visitor< InertiaPythonVisitor<Inertia> >
56 typedef typename Inertia::Vector3
Vector3;
57 typedef typename Inertia::Matrix3
Matrix3;
58 typedef typename Inertia::Vector6
Vector6;
59 typedef typename Inertia::Matrix6
Matrix6;
63 template<
class PyClass>
69 bp::default_call_policies(),
70 bp::args(
"mass",
"lever",
"inertia")),
71 "Initialize from mass, lever and 3d inertia.")
72 .def(bp::init<Inertia>(bp::args(
"self",
"other"),
"Copy constructor."))
77 "Mass of the Spatial Inertia.")
78 .add_property(
"lever",
79 bp::make_function((
typename Inertia::Vector3 & (Inertia::*)())&
Inertia::lever,
80 bp::return_internal_reference<>()),
82 "Center of mass location of the Spatial Inertia. It corresponds to the location of the center of mass regarding to the frame where the Spatial Inertia is expressed.")
83 .add_property(
"inertia",
86 "Rotational part of the Spatial Inertia, i.e. a symmetric matrix representing the rotational inertia around the center of mass.")
90 bp::args(
"self",
"M"),
"Returns the result of the action of M on *this.")
92 bp::args(
"self",
"M"),
"Returns the result of the action of the inverse of M on *this.")
95 "Set *this to be the Identity inertia.")
97 "Set all the components of *this to zero.")
99 "Set all the components of *this to random values.")
101 .def(bp::self + bp::self)
102 .def(bp::self * bp::other<Motion>() )
104 .def(
"vxiv",&
Inertia::vxiv,bp::args(
"self",
"v"),
"Returns the result of v x Iv.")
105 .def(
"vtiv",&
Inertia::vtiv,bp::args(
"self",
"v"),
"Returns the result of v.T * Iv.")
107 bp::args(
"self",
"v"),
108 "Returns the result of v x* I, a 6x6 matrix.")
110 bp::args(
"self",
"v"),
111 "Returns the result of I vx, a 6x6 matrix.")
113 bp::args(
"self",
"v"),
114 "Returns the time derivative of the inertia.")
116 .def(bp::self == bp::self)
117 .def(bp::self != bp::self)
121 isApproxInertia_overload(bp::args(
"self",
"other",
"prec"),
122 "Returns true if *this is approximately equal to other, within the precision given by prec."))
126 isZero_overload(bp::args(
"self",
"prec"),
127 "Returns true if *this is approximately equal to the zero Inertia, within the precision given by prec."))
130 .staticmethod(
"Identity")
132 .staticmethod(
"Zero")
134 .staticmethod(
"Random")
137 "Returns the representation of the matrix as a vector of dynamic parameters." 138 "\nThe parameters are given as v = [m, mc_x, mc_y, mc_z, I_{xx}, I_{xy}, I_{yy}, I_{xz}, I_{yz}, I_{zz}]^T " 139 "where I = I_C + mS^T(c)S(c) and I_C has its origin at the barycenter" 141 .def(
"FromDynamicParameters",&Inertia::template FromDynamicParameters<Eigen::VectorXd>,
142 bp::args(
"dynamic_parameters"),
143 "Builds and inertia matrix from a vector of dynamic parameters." 144 "\nThe parameters are given as dynamic_parameters = [m, mc_x, mc_y, mc_z, I_{xx}, I_{xy}, I_{yy}, I_{xz}, I_{yz}, I_{zz}]^T " 145 "where I = I_C + mS^T(c)S(c) and I_C has its origin at the barycenter." 147 .staticmethod(
"FromDynamicParameters")
150 bp::args(
"mass",
"radius"),
151 "Returns the Inertia of a sphere defined by a given mass and radius.")
152 .staticmethod(
"FromSphere")
154 bp::args(
"mass",
"length_x",
"length_y",
"length_z"),
155 "Returns the Inertia of an ellipsoid shape defined by a mass and given dimensions the semi-axis of values length_{x,y,z}.")
156 .staticmethod(
"FromEllipsoid")
158 bp::args(
"mass",
"radius",
"length"),
159 "Returns the Inertia of a cylinder defined by its mass, radius and length along the Z axis.")
160 .staticmethod(
"FromCylinder")
162 bp::args(
"mass",
"length_x",
"length_y",
"length_z"),
163 "Returns the Inertia of a box shape with a mass and of dimension the semi axis of length_{x,y,z}.")
164 .staticmethod(
"FromBox")
172 static Scalar
getMass(
const Inertia &
self ) {
return self.mass(); }
173 static void setMass( Inertia &
self, Scalar mass ) {
self.mass() = mass; }
175 static void setLever( Inertia &
self,
const Vector3 & lever ) {
self.lever() = lever; }
177 static Matrix3
getInertia(
const Inertia &
self ) {
return self.inertia().matrix(); }
179 static void setInertia(Inertia &
self,
const Matrix3 & symmetric_inertia)
181 assert(symmetric_inertia.isApprox(symmetric_inertia.transpose()));
182 self.inertia().data() <<
183 symmetric_inertia(0,0),
184 symmetric_inertia(1,0),
185 symmetric_inertia(1,1),
186 symmetric_inertia(0,2),
187 symmetric_inertia(1,2),
188 symmetric_inertia(2,2);
193 return self.toDynamicParameters();
197 const Vector3 & lever,
198 const Matrix3 & inertia)
200 if(! inertia.isApprox(inertia.transpose()) )
202 if( (Eigen::Vector3d::UnitX().transpose()*inertia*Eigen::Vector3d::UnitX()<0)
203 || (Eigen::Vector3d::UnitY().transpose()*inertia*Eigen::Vector3d::UnitY()<0)
204 || (Eigen::Vector3d::UnitZ().transpose()*inertia*Eigen::Vector3d::UnitZ()<0) )
206 return new Inertia(mass,lever,inertia);
211 #if PY_MAJOR_VERSION == 3 && PY_MINOR_VERSION == 6 && EIGENPY_VERSION_AT_LEAST(2,9,0) 214 typedef ::boost::python::detail::not_specified HolderType;
216 bp::class_<Inertia,HolderType>(
"Inertia",
217 "This class represenses a sparse version of a Spatial Inertia and its is defined by its mass, its center of mass location and the rotational inertia expressed around this center of mass.\n\n" 218 "Supported operations ...",
219 bp::init<>(bp::arg(
"self"),
"Default constructor."))
245 #endif // ifndef __pinocchio_python_spatial_inertia_hpp__ Force vxiv(const Motion &v) const
InertiaTpl< double, 0 > Inertia
const Symmetric3 & inertia() const
static void setInertia(Inertia &self, const Matrix3 &symmetric_inertia)
static void setLever(Inertia &self, const Vector3 &lever)
static InertiaTpl Random()
const Vector3 & lever() const
static Eigen::VectorXd toDynamicParameters_proxy(const Inertia &self)
static bool isApprox(const Inertia &self, const Inertia &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision())
static InertiaTpl FromSphere(const Scalar mass, const Scalar radius)
Computes the Inertia of a sphere defined by its mass and its radius.
Set the Python method str and repr to use the overloading operator<<.
BOOST_PYTHON_FUNCTION_OVERLOADS(computeKKTContactDynamicMatrixInverse_overload, computeKKTContactDynamicMatrixInverse_proxy, 4, 5) static const Eigen
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...
Derived_t se3ActionInverse(const SE3 &M) const
bI = aXb.actInv(aI)
static Matrix3 getInertia(const Inertia &self)
Derived_t se3Action(const SE3 &M) const
aI = aXb.act(bI)
#define PINOCCHIO_SHARED_PTR_HOLDER_TYPE(T)
static InertiaTpl Identity()
Matrix6 variation(const Motion &v) const
static boost::python::tuple getinitargs(const Inertia &I)
Add the Python method copy to allow a copy of this by calling the copy constructor.
static void setMass(Inertia &self, Scalar mass)
InertiaTpl< Scalar, Options > Inertia
Main pinocchio namespace.
auto call(R(*f)(Args...), typename convert_type< Args >::type... args)
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).
static void ivx(const Motion &v, const InertiaTpl< _Scalar, _Options > &I, const Eigen::MatrixBase< M6 > &Iout)
Time variation operator. It computes the time derivative of an inertia I corresponding to the formula...
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...
static Inertia * makeFromMCI(const double &mass, const Vector3 &lever, const Matrix3 &inertia)
#define EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(...)
static bool getstate_manages_dict()
Scalar vtiv(const Motion &v) const
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
void visit(PyClass &cl) const
static void vxi(const Motion &v, const InertiaTpl< _Scalar, _Options > &I, const Eigen::MatrixBase< M6 > &Iout)
Time variation operator. It computes the time derivative of an inertia I corresponding to the formula...
static bool isZero(const Inertia &self, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision())
static Scalar getMass(const Inertia &self)