#include <fwd.hpp>
Public Types | |
enum | { Options = _Options } |
typedef Symmetric3::AlphaSkewSquare | AlphaSkewSquare |
typedef LogCholeskyParametersTpl< Scalar, Options > | LogCholeskyParameters |
typedef Eigen::Matrix< Scalar, 10, 10, Options > | Matrix10 |
typedef PseudoInertiaTpl< Scalar, Options > | PseudoInertia |
typedef Eigen::Matrix< Scalar, 10, 1, Options > | Vector10 |
Public Member Functions | |
InertiaTpl & | __equl__ (const InertiaTpl &clone) |
InertiaTpl & | __mequ__ (const InertiaTpl &Yb) |
InertiaTpl | __minus__ (const InertiaTpl &Yb) const |
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 |
Symmetric3 & | inertia () |
const Symmetric3 & | inertia () const |
InertiaTpl () | |
InertiaTpl (const InertiaTpl &clone) | |
template<typename S2 , int O2> | |
InertiaTpl (const InertiaTpl< S2, O2 > &clone) | |
InertiaTpl (const Matrix6 &I6) | |
InertiaTpl (const Scalar &mass, const Vector3 &com, const Matrix3 &rotational_inertia) | |
InertiaTpl (const Scalar &mass, const Vector3 &com, const Symmetric3 &rotational_inertia) | |
Matrix6 | inverse_impl () const |
template<typename Matrix6Like > | |
void | inverse_impl (const Eigen::MatrixBase< Matrix6Like > &M_) const |
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 |
Vector3 & | lever () |
const Vector3 & | lever () const |
Scalar & | mass () |
Scalar | mass () const |
Matrix6 | matrix_impl () const |
template<typename Matrix6Like > | |
void | matrix_impl (const Eigen::MatrixBase< Matrix6Like > &M_) const |
InertiaTpl & | operator= (const InertiaTpl &clone) |
template<typename S2 , int O2> | |
InertiaTpl | se3Action_impl (const SE3Tpl< S2, O2 > &M) const |
aI = aXb.act(bI) More... | |
template<typename S2 , int O2> | |
InertiaTpl | se3ActionInverse_impl (const SE3Tpl< S2, O2 > &M) const |
bI = aXb.actInv(aI) More... | |
void | setIdentity () |
void | setRandom () |
void | setZero () |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | SPATIAL_TYPEDEF_TEMPLATE (InertiaTpl) |
Vector10 | toDynamicParameters () const |
PseudoInertia | toPseudoInertia () const |
Convert the InertiaTpl object to a 4x4 pseudo inertia matrix. More... | |
template<typename MotionDerived > | |
Matrix6 | variation (const MotionDense< MotionDerived > &v) const |
template<typename MotionDerived > | |
Scalar | vtiv_impl (const MotionDense< MotionDerived > &v) const |
template<typename MotionDerived > | |
Force | vxiv (const MotionDense< MotionDerived > &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 | 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. Assumes a uniform density. 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 | FromLogCholeskyParameters (const LogCholeskyParameters &log_cholesky) |
Create an InertiaTpl object from log Cholesky parameters. More... | |
static InertiaTpl | FromPseudoInertia (const PseudoInertia &pseudo_inertia) |
Create an InertiaTpl object from a PseudoInertia object. 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 MotionDerived , typename M6 > | |
static void | ivx_impl (const MotionDense< MotionDerived > &v, const InertiaTpl &I, const Eigen::MatrixBase< M6 > &Iout) |
static InertiaTpl | Random () |
template<typename MotionDerived , typename M6 > | |
static void | vxi_impl (const MotionDense< MotionDerived > &v, const InertiaTpl &I, const Eigen::MatrixBase< M6 > &Iout) |
static InertiaTpl | Zero () |
Protected Attributes | |
Vector3 | m_com |
Symmetric3 | m_inertia |
Scalar | m_mass |
Definition at line 58 of file spatial/fwd.hpp.
typedef Symmetric3::AlphaSkewSquare pinocchio::InertiaTpl< _Scalar, _Options >::AlphaSkewSquare |
Definition at line 274 of file spatial/inertia.hpp.
typedef LogCholeskyParametersTpl<Scalar, Options> pinocchio::InertiaTpl< _Scalar, _Options >::LogCholeskyParameters |
Definition at line 278 of file spatial/inertia.hpp.
typedef Eigen::Matrix<Scalar, 10, 10, Options> pinocchio::InertiaTpl< _Scalar, _Options >::Matrix10 |
Definition at line 276 of file spatial/inertia.hpp.
typedef PseudoInertiaTpl<Scalar, Options> pinocchio::InertiaTpl< _Scalar, _Options >::PseudoInertia |
Definition at line 277 of file spatial/inertia.hpp.
typedef Eigen::Matrix<Scalar, 10, 1, Options> pinocchio::InertiaTpl< _Scalar, _Options >::Vector10 |
Definition at line 275 of file spatial/inertia.hpp.
anonymous enum |
Enumerator | |
---|---|
Options |
Definition at line 269 of file spatial/inertia.hpp.
|
inline |
Definition at line 281 of file spatial/inertia.hpp.
|
inline |
Definition at line 285 of file spatial/inertia.hpp.
|
inlineexplicit |
Definition at line 292 of file spatial/inertia.hpp.
|
inline |
Definition at line 308 of file spatial/inertia.hpp.
|
inline |
Definition at line 315 of file spatial/inertia.hpp.
|
inlineexplicit |
Definition at line 331 of file spatial/inertia.hpp.
|
inline |
Definition at line 611 of file spatial/inertia.hpp.
|
inline |
Definition at line 696 of file spatial/inertia.hpp.
|
inline |
Definition at line 674 of file spatial/inertia.hpp.
|
inline |
Definition at line 718 of file spatial/inertia.hpp.
|
inline |
Definition at line 728 of file spatial/inertia.hpp.
|
inline |
Definition at line 658 of file spatial/inertia.hpp.
|
inline |
Definition at line 640 of file spatial/inertia.hpp.
|
inline |
Definition at line 911 of file spatial/inertia.hpp.
|
inline |
Definition at line 901 of file 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 423 of file spatial/inertia.hpp.
|
inlinestatic |
Computes the Inertia of a capsule defined by its mass, radius and length along the Z axis. Assumes a uniform density.
[in] | mass | of the capsule. |
[in] | radius | of the capsule. |
[in] | height | of the capsule. |
Definition at line 439 of file 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 406 of file 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 561 of file 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 389 of file spatial/inertia.hpp.
|
inlinestatic |
Create an InertiaTpl object from log Cholesky parameters.
log_cholesky | A log cholesky parameters object |
Definition at line 604 of file spatial/inertia.hpp.
|
inlinestatic |
Create an InertiaTpl object from a PseudoInertia object.
pseudo_inertia | A PseudoInertia object. |
Definition at line 581 of file 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 374 of file spatial/inertia.hpp.
|
inlinestatic |
Definition at line 349 of file spatial/inertia.hpp.
|
inline |
Definition at line 865 of file spatial/inertia.hpp.
|
inline |
Definition at line 852 of file spatial/inertia.hpp.
|
inline |
Definition at line 527 of file spatial/inertia.hpp.
|
inline |
Definition at line 500 of file spatial/inertia.hpp.
|
inline |
Definition at line 625 of file spatial/inertia.hpp.
|
inline |
Definition at line 620 of file spatial/inertia.hpp.
|
inline |
Definition at line 634 of file spatial/inertia.hpp.
|
inlinestatic |
Definition at line 812 of file spatial/inertia.hpp.
|
inline |
Definition at line 861 of file spatial/inertia.hpp.
|
inline |
Definition at line 848 of file spatial/inertia.hpp.
|
inline |
Definition at line 857 of file spatial/inertia.hpp.
|
inline |
Definition at line 844 of file spatial/inertia.hpp.
|
inline |
Definition at line 492 of file spatial/inertia.hpp.
|
inline |
Definition at line 480 of file spatial/inertia.hpp.
|
inline |
Definition at line 322 of file spatial/inertia.hpp.
|
inlinestatic |
Definition at line 361 of file spatial/inertia.hpp.
|
inline |
aI = aXb.act(bI)
Definition at line 872 of file spatial/inertia.hpp.
|
inline |
bI = aXb.actInv(aI)
Definition at line 883 of file spatial/inertia.hpp.
|
inline |
Definition at line 354 of file spatial/inertia.hpp.
|
inline |
Definition at line 472 of file spatial/inertia.hpp.
|
inline |
Definition at line 342 of file spatial/inertia.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW 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 541 of file spatial/inertia.hpp.
|
inline |
Convert the InertiaTpl object to a 4x4 pseudo inertia matrix.
Definition at line 591 of file spatial/inertia.hpp.
|
inline |
Definition at line 749 of file spatial/inertia.hpp.
|
inline |
Definition at line 737 of file spatial/inertia.hpp.
|
inlinestatic |
Definition at line 778 of file spatial/inertia.hpp.
|
inline |
Definition at line 891 of file spatial/inertia.hpp.
|
inlinestatic |
Definition at line 337 of file spatial/inertia.hpp.
|
protected |
Definition at line 929 of file spatial/inertia.hpp.
|
protected |
Definition at line 930 of file spatial/inertia.hpp.
|
protected |
Definition at line 928 of file spatial/inertia.hpp.