A structure representing a pseudo inertia matrix. More...
#include <fwd.hpp>
Public Types | |
enum | { Options = _Options } |
typedef LogCholeskyParametersTpl< Scalar, Options > | LogCholeskyParameters |
typedef Eigen::Matrix< Scalar, 3, 3, Options > | Matrix3 |
typedef Eigen::Matrix< Scalar, 4, 4, Options > | Matrix4 |
typedef _Scalar | Scalar |
typedef Eigen::Matrix< Scalar, 10, 1, Options > | Vector10 |
typedef Eigen::Matrix< Scalar, 3, 1, Options > | Vector3 |
Public Member Functions | |
template<typename NewScalar > | |
PseudoInertiaTpl< NewScalar, Options > | cast () const |
void | disp_impl (std::ostream &os) const |
PseudoInertiaTpl (Scalar mass, const Vector3 &h, const Matrix3 &sigma) | |
Vector10 | toDynamicParameters () const |
Converts the PseudoInertiaTpl object to dynamic parameters. More... | |
InertiaTpl< Scalar, Options > | toInertia () const |
Converts the PseudoInertiaTpl object to an InertiaTpl object. More... | |
Matrix4 | toMatrix () const |
Converts the PseudoInertiaTpl object to a 4x4 matrix. More... | |
Static Public Member Functions | |
template<typename Vector10Like > | |
static PseudoInertiaTpl | FromDynamicParameters (const Eigen::MatrixBase< Vector10Like > &dynamic_params) |
Constructs a PseudoInertiaTpl object from dynamic parameters. More... | |
static PseudoInertiaTpl | FromInertia (const InertiaTpl< Scalar, Options > &inertia) |
Constructs a PseudoInertiaTpl object from an InertiaTpl object. More... | |
static PseudoInertiaTpl | FromLogCholeskyParameters (const LogCholeskyParameters &log_cholesky) |
Constructs a PseudoInertiaTpl object from log Cholesky parameters. More... | |
static PseudoInertiaTpl | FromMatrix (const Matrix4 &pseudo_inertia) |
Constructs a PseudoInertiaTpl object from a 4x4 pseudo inertia matrix. More... | |
Public Attributes | |
Vector3 | h |
Vector part of the pseudo inertia. More... | |
Scalar | mass |
Mass of the pseudo inertia. More... | |
Matrix3 | sigma |
3x3 matrix part of the pseudo inertia More... | |
Friends | |
std::ostream & | operator<< (std::ostream &os, const PseudoInertiaTpl &pi) |
A structure representing a pseudo inertia matrix.
References:
Definition at line 62 of file spatial/fwd.hpp.
typedef LogCholeskyParametersTpl<Scalar, Options> pinocchio::PseudoInertiaTpl< _Scalar, _Options >::LogCholeskyParameters |
Definition at line 954 of file spatial/inertia.hpp.
typedef Eigen::Matrix<Scalar, 3, 3, Options> pinocchio::PseudoInertiaTpl< _Scalar, _Options >::Matrix3 |
Definition at line 952 of file spatial/inertia.hpp.
typedef Eigen::Matrix<Scalar, 4, 4, Options> pinocchio::PseudoInertiaTpl< _Scalar, _Options >::Matrix4 |
Definition at line 950 of file spatial/inertia.hpp.
typedef _Scalar pinocchio::PseudoInertiaTpl< _Scalar, _Options >::Scalar |
Definition at line 945 of file spatial/inertia.hpp.
typedef Eigen::Matrix<Scalar, 10, 1, Options> pinocchio::PseudoInertiaTpl< _Scalar, _Options >::Vector10 |
Definition at line 953 of file spatial/inertia.hpp.
typedef Eigen::Matrix<Scalar, 3, 1, Options> pinocchio::PseudoInertiaTpl< _Scalar, _Options >::Vector3 |
Definition at line 951 of file spatial/inertia.hpp.
anonymous enum |
Enumerator | |
---|---|
Options |
Definition at line 946 of file spatial/inertia.hpp.
|
inline |
Definition at line 960 of file spatial/inertia.hpp.
|
inline |
Definition at line 1072 of file spatial/inertia.hpp.
|
inline |
Definition at line 1079 of file spatial/inertia.hpp.
|
inlinestatic |
Constructs a PseudoInertiaTpl object from dynamic parameters.
dynamic_params | A 10-dimensional vector of dynamic parameters. |
Definition at line 1001 of file spatial/inertia.hpp.
|
inlinestatic |
Constructs a PseudoInertiaTpl object from an InertiaTpl object.
inertia | An InertiaTpl object. |
Definition at line 1043 of file spatial/inertia.hpp.
|
inlinestatic |
Constructs a PseudoInertiaTpl object from log Cholesky parameters.
log_cholesky | A 10-dimensional vector of log Cholesky parameters. |
Definition at line 1064 of file spatial/inertia.hpp.
|
inlinestatic |
Constructs a PseudoInertiaTpl object from a 4x4 pseudo inertia matrix.
pseudo_inertia | A 4x4 pseudo inertia matrix. |
Definition at line 986 of file spatial/inertia.hpp.
|
inline |
Converts the PseudoInertiaTpl object to dynamic parameters.
Definition at line 1021 of file spatial/inertia.hpp.
|
inline |
Converts the PseudoInertiaTpl object to an InertiaTpl object.
Definition at line 1053 of file spatial/inertia.hpp.
|
inline |
Converts the PseudoInertiaTpl object to a 4x4 matrix.
Definition at line 971 of file spatial/inertia.hpp.
|
friend |
Definition at line 1087 of file spatial/inertia.hpp.
Vector3 pinocchio::PseudoInertiaTpl< _Scalar, _Options >::h |
Vector part of the pseudo inertia.
Definition at line 957 of file spatial/inertia.hpp.
Scalar pinocchio::PseudoInertiaTpl< _Scalar, _Options >::mass |
Mass of the pseudo inertia.
Definition at line 956 of file spatial/inertia.hpp.
Matrix3 pinocchio::PseudoInertiaTpl< _Scalar, _Options >::sigma |
3x3 matrix part of the pseudo inertia
Definition at line 958 of file spatial/inertia.hpp.