Template Struct VectorSpaceOperationTpl

Inheritance Relationships

Base Type

Struct Documentation

template<int Dim, typename _Scalar, int _Options>
struct VectorSpaceOperationTpl : public pinocchio::LieGroupBase<VectorSpaceOperationTpl<Dim, _Scalar, _Options>>

Public Functions

PINOCCHIO_LIE_GROUP_TPL_PUBLIC_INTERFACE(VectorSpaceOperationTpl)
inline VectorSpaceOperationTpl(int size = boost::static_signed_max<0, Dim>::value)

Constructor

Parameters:

size – size of the vector space: should be the equal to template argument for static sized vector-spaces.

inline VectorSpaceOperationTpl(const VectorSpaceOperationTpl &other)

Constructor

Parameters:

other – other VectorSpaceOperationTpl from which to retrieve size

inline VectorSpaceOperationTpl &operator=(const VectorSpaceOperationTpl &other)
inline Index nq() const
inline Index nv() const
inline ConfigVector_t neutral() const
inline std::string name() const
template<ArgumentPosition arg, class ConfigL_t, class ConfigR_t, class JacobianOut_t>
inline void dDifference_impl(const Eigen::MatrixBase<ConfigL_t>&, const Eigen::MatrixBase<ConfigR_t>&, const Eigen::MatrixBase<JacobianOut_t> &J) const
template<class ConfigL_t, class ConfigR_t, class ConfigOut_t>
inline void randomConfiguration_impl(const Eigen::MatrixBase<ConfigL_t> &lower_pos_limit, const Eigen::MatrixBase<ConfigR_t> &upper_pos_limit, const Eigen::MatrixBase<ConfigOut_t> &qout) const
inline bool isEqual_impl(const VectorSpaceOperationTpl &other) const

Public Static Functions

template<class ConfigL_t, class ConfigR_t, class Tangent_t>
static inline void difference_impl(const Eigen::MatrixBase<ConfigL_t> &q0, const Eigen::MatrixBase<ConfigR_t> &q1, const Eigen::MatrixBase<Tangent_t> &d)
template<ArgumentPosition arg, class ConfigL_t, class ConfigR_t, class JacobianIn_t, class JacobianOut_t>
static inline void dDifference_product_impl(const ConfigL_t&, const ConfigR_t&, const JacobianIn_t &Jin, JacobianOut_t &Jout, bool, const AssignmentOperatorType op)
template<class ConfigIn_t, class Velocity_t, class ConfigOut_t>
static inline void integrate_impl(const Eigen::MatrixBase<ConfigIn_t> &q, const Eigen::MatrixBase<Velocity_t> &v, const Eigen::MatrixBase<ConfigOut_t> &qout)
template<class Config_t, class Jacobian_t>
static inline void integrateCoeffWiseJacobian_impl(const Eigen::MatrixBase<Config_t>&, const Eigen::MatrixBase<Jacobian_t> &J)
template<class Config_t, class Tangent_t, class JacobianOut_t>
static inline void dIntegrate_dq_impl(const Eigen::MatrixBase<Config_t>&, const Eigen::MatrixBase<Tangent_t>&, const Eigen::MatrixBase<JacobianOut_t> &J, const AssignmentOperatorType op = SETTO)
template<class Config_t, class Tangent_t, class JacobianOut_t>
static inline void dIntegrate_dv_impl(const Eigen::MatrixBase<Config_t>&, const Eigen::MatrixBase<Tangent_t>&, const Eigen::MatrixBase<JacobianOut_t> &J, const AssignmentOperatorType op = SETTO)
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
static inline void dIntegrate_product_impl(const Config_t&, const Tangent_t&, const JacobianIn_t &Jin, JacobianOut_t &Jout, bool, const ArgumentPosition, const AssignmentOperatorType op)
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
static inline void dIntegrateTransport_dq_impl(const Eigen::MatrixBase<Config_t>&, const Eigen::MatrixBase<Tangent_t>&, const Eigen::MatrixBase<JacobianIn_t> &Jin, const Eigen::MatrixBase<JacobianOut_t> &Jout)
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
static inline void dIntegrateTransport_dv_impl(const Eigen::MatrixBase<Config_t>&, const Eigen::MatrixBase<Tangent_t>&, const Eigen::MatrixBase<JacobianIn_t> &Jin, const Eigen::MatrixBase<JacobianOut_t> &Jout)
template<class Config_t, class Tangent_t, class Jacobian_t>
static inline void dIntegrateTransport_dq_impl(const Eigen::MatrixBase<Config_t>&, const Eigen::MatrixBase<Tangent_t>&, const Eigen::MatrixBase<Jacobian_t>&)
template<class Config_t, class Tangent_t, class Jacobian_t>
static inline void dIntegrateTransport_dv_impl(const Eigen::MatrixBase<Config_t>&, const Eigen::MatrixBase<Tangent_t>&, const Eigen::MatrixBase<Jacobian_t>&)
template<class Config_t>
static inline void normalize_impl(const Eigen::MatrixBase<Config_t>&)
template<class Config_t>
static inline bool isNormalized_impl(const Eigen::MatrixBase<Config_t>&, const Scalar&)
template<class Config_t>
static inline void random_impl(const Eigen::MatrixBase<Config_t> &qout)