#include <fwd.hpp>
Public Types | |
enum | { Options = _Options } |
typedef Eigen::Matrix< _Scalar, 10, 1, _Options > | Vector10 |
Public Member Functions | |
InertiaTpl & | __equl__ (const InertiaTpl &clone) |
template<typename MotionDerived > | |
ForceTpl< typename traits< MotionDerived >::Scalar, traits< MotionDerived >::Options > | __mult__ (const MotionDense< MotionDerived > &v) const |
template<typename MotionDerived , typename ForceDerived > | |
void | __mult__ (const MotionDense< MotionDerived > &v, ForceDense< ForceDerived > &f) const |
InertiaTpl & | __pequ__ (const InertiaTpl &Yb) |
InertiaTpl | __plus__ (const InertiaTpl &Yb) const |
template<typename NewScalar > | |
InertiaTpl< NewScalar, Options > | cast () const |
void | disp_impl (std::ostream &os) const |
const Symmetric3 & | inertia () const |
Symmetric3 & | inertia () |
InertiaTpl () | |
InertiaTpl (const Scalar mass, const Vector3 &com, const Matrix3 &rotational_inertia) | |
InertiaTpl (const Matrix6 &I6) | |
InertiaTpl (Scalar mass, const Vector3 &com, const Symmetric3 &rotational_inertia) | |
InertiaTpl (const InertiaTpl &clone) | |
template<int O2> | |
InertiaTpl (const InertiaTpl< Scalar, O2 > &clone) | |
bool | isApprox_impl (const InertiaTpl &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const |
bool | isEqual (const InertiaTpl &Y2) const |
bool | isZero_impl (const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const |
const Vector3 & | lever () const |
Vector3 & | lever () |
Scalar | mass () const |
Scalar & | mass () |
Matrix6 | matrix_impl () const |
InertiaTpl & | operator= (const InertiaTpl &clone) |
InertiaTpl | se3Action_impl (const SE3 &M) const |
aI = aXb.act(bI) More... | |
InertiaTpl | se3ActionInverse_impl (const SE3 &M) const |
bI = aXb.actInv(aI) More... | |
void | setIdentity () |
void | setRandom () |
void | setZero () |
SPATIAL_TYPEDEF_TEMPLATE (InertiaTpl) | |
Vector10 | toDynamicParameters () const |
Matrix6 | variation (const Motion &v) const |
Scalar | vtiv_impl (const Motion &v) const |
Force | vxiv (const Motion &v) const |
Public Member Functions inherited from pinocchio::InertiaBase< InertiaTpl< _Scalar, _Options > > | |
Derived_t & | derived () |
const Derived_t & | derived () const |
void | disp (std::ostream &os) const |
const Symmetric3 & | inertia () const |
Symmetric3 & | inertia () |
bool | isApprox (const InertiaTpl< _Scalar, _Options > &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const |
bool | isZero (const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const |
Matrix6 | ivx (const Motion &v) const |
const Vector3 & | lever () const |
Vector3 & | lever () |
Scalar | mass () const |
Scalar & | mass () |
Matrix6 | matrix () const |
operator Matrix6 () const | |
bool | operator!= (const Derived_t &other) const |
ForceTpl< typename traits< MotionDerived >::Scalar, traits< MotionDerived >::Options > | operator* (const MotionDense< MotionDerived > &v) const |
Derived_t | operator+ (const Derived_t &Yb) const |
Derived_t & | operator+= (const Derived_t &Yb) |
Derived_t & | operator= (const Derived_t &clone) |
bool | operator== (const Derived_t &other) const |
Derived_t | se3Action (const SE3 &M) const |
aI = aXb.act(bI) More... | |
Derived_t | se3ActionInverse (const SE3 &M) const |
bI = aXb.actInv(aI) More... | |
void | setIdentity () |
void | setRandom () |
void | setZero () |
Matrix6 | variation (const Motion &v) const |
Scalar | vtiv (const Motion &v) const |
Matrix6 | vxi (const Motion &v) const |
Static Public Member Functions | |
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). More... | |
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. More... | |
template<typename Vector10Like > | |
static InertiaTpl | FromDynamicParameters (const Eigen::MatrixBase< Vector10Like > ¶ms) |
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,y,z). More... | |
static InertiaTpl | FromSphere (const Scalar mass, const Scalar radius) |
Computes the Inertia of a sphere defined by its mass and its radius. More... | |
static InertiaTpl | Identity () |
template<typename M6 > | |
static void | ivx_impl (const Motion &v, const InertiaTpl &I, const Eigen::MatrixBase< M6 > &Iout) |
static InertiaTpl | Random () |
template<typename M6 > | |
static void | vxi_impl (const Motion &v, const InertiaTpl &I, const Eigen::MatrixBase< M6 > &Iout) |
static InertiaTpl | Zero () |
Static Public Member Functions inherited from pinocchio::InertiaBase< InertiaTpl< _Scalar, _Options > > | |
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 . More... | |
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 . More... | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Symmetric3::AlphaSkewSquare | AlphaSkewSquare |
Protected Attributes | |
Vector3 | m_com |
Symmetric3 | m_inertia |
Scalar | m_mass |
Friends | |
class | InertiaBase< InertiaTpl< _Scalar, _Options > > |
Additional Inherited Members | |
Protected Types inherited from pinocchio::InertiaBase< InertiaTpl< _Scalar, _Options > > | |
typedef InertiaTpl< _Scalar, _Options > | Derived_t |
Protected Member Functions inherited from pinocchio::InertiaBase< InertiaTpl< _Scalar, _Options > > | |
SPATIAL_TYPEDEF_TEMPLATE (Derived_t) | |
Definition at line 52 of file src/spatial/fwd.hpp.
typedef Eigen::Matrix<_Scalar, 10, 1, _Options> pinocchio::InertiaTpl< _Scalar, _Options >::Vector10 |
Definition at line 162 of file src/spatial/inertia.hpp.
anonymous enum |
Enumerator | |
---|---|
Options |
Definition at line 157 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 166 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 169 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 173 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 188 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 192 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 205 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 367 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 429 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 438 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 413 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 396 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 588 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 578 of file src/spatial/inertia.hpp.
|
inlinestatic |
Computes the Inertia of a box defined by its mass and main dimensions (x,y,z).
[in] | mass | of the box. |
[in] | x | dimension along the local X axis. |
[in] | y | dimension along the local Y axis. |
[in] | z | dimension along the local Z axis. |
Definition at line 298 of file src/spatial/inertia.hpp.
|
inlinestatic |
Computes the Inertia of a cylinder defined by its mass, radius and length along the Z axis.
[in] | mass | of the cylinder. |
[in] | radius | of the cylinder. |
[in] | length | of the cylinder. |
Definition at line 279 of file src/spatial/inertia.hpp.
|
inlinestatic |
Builds and inertia matrix from a vector of dynamic parameters.
[in] | params | The dynamic parameters. |
The parameters are given as where and has its origin at the barycenter.
Definition at line 355 of file src/spatial/inertia.hpp.
|
inlinestatic |
Computes the Inertia of an ellipsoid defined by its mass and main semi-axis dimensions (x,y,z).
[in] | mass | of the ellipsoid. |
[in] | x | semi-axis dimension along the local X axis. |
[in] | y | semi-axis dimension along the local Y axis. |
[in] | z | semi-axis dimension along the local Z axis. |
Definition at line 260 of file src/spatial/inertia.hpp.
|
inlinestatic |
Computes the Inertia of a sphere defined by its mass and its radius.
[in] | mass | of the sphere. |
[in] | radius | of the sphere. |
Definition at line 247 of file src/spatial/inertia.hpp.
|
inlinestatic |
Definition at line 221 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 545 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 549 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 379 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 374 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 388 of file src/spatial/inertia.hpp.
|
inlinestatic |
Definition at line 514 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 544 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 548 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 543 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 547 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 316 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 196 of file src/spatial/inertia.hpp.
|
inlinestatic |
Definition at line 233 of file src/spatial/inertia.hpp.
|
inline |
aI = aXb.act(bI)
Definition at line 552 of file src/spatial/inertia.hpp.
|
inline |
bI = aXb.actInv(aI)
Definition at line 563 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 228 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 310 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 219 of file src/spatial/inertia.hpp.
pinocchio::InertiaTpl< _Scalar, _Options >::SPATIAL_TYPEDEF_TEMPLATE | ( | InertiaTpl< _Scalar, _Options > | ) |
|
inline |
Returns the representation of the matrix as a vector of dynamic parameters. The parameters are given as where is the center of mass, and has its origin at the barycenter and is the the skew matrix representation of the cross product operator.
Definition at line 335 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 457 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 446 of file src/spatial/inertia.hpp.
|
inlinestatic |
Definition at line 479 of file src/spatial/inertia.hpp.
|
inline |
Definition at line 570 of file src/spatial/inertia.hpp.
|
inlinestatic |
Definition at line 212 of file src/spatial/inertia.hpp.
|
friend |
Definition at line 155 of file src/spatial/inertia.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Symmetric3::AlphaSkewSquare pinocchio::InertiaTpl< _Scalar, _Options >::AlphaSkewSquare |
Definition at line 160 of file src/spatial/inertia.hpp.
|
protected |
Definition at line 606 of file src/spatial/inertia.hpp.
|
protected |
Definition at line 607 of file src/spatial/inertia.hpp.
|
protected |
Definition at line 605 of file src/spatial/inertia.hpp.