Template Struct CartesianProductOperation

Inheritance Relationships

Base Type

Struct Documentation

template<typename LieGroup1, typename LieGroup2>
struct CartesianProductOperation : public pinocchio::LieGroupBase<CartesianProductOperation<LieGroup1, LieGroup2>>

Public Functions

PINOCCHIO_LIE_GROUP_TPL_PUBLIC_INTERFACE(CartesianProductOperation)
inline CartesianProductOperation()
inline Index nq() const
inline Index nv() const
inline ConfigVector_t neutral() const
inline std::string name() const
template<class ConfigL_t, class ConfigR_t, class Tangent_t>
inline void difference_impl(const Eigen::MatrixBase<ConfigL_t> &q0, const Eigen::MatrixBase<ConfigR_t> &q1, const Eigen::MatrixBase<Tangent_t> &d) const
template<ArgumentPosition arg, class ConfigL_t, class ConfigR_t, class JacobianOut_t>
inline void dDifference_impl(const Eigen::MatrixBase<ConfigL_t> &q0, const Eigen::MatrixBase<ConfigR_t> &q1, const Eigen::MatrixBase<JacobianOut_t> &J) const
template<class ConfigIn_t, class Velocity_t, class ConfigOut_t>
inline void integrate_impl(const Eigen::MatrixBase<ConfigIn_t> &q, const Eigen::MatrixBase<Velocity_t> &v, const Eigen::MatrixBase<ConfigOut_t> &qout) const
template<class Config_t, class Jacobian_t>
inline void integrateCoeffWiseJacobian_impl(const Eigen::MatrixBase<Config_t> &q, const Eigen::MatrixBase<Jacobian_t> &J) const
template<class Config_t, class Tangent_t, class JacobianOut_t>
inline void dIntegrate_dq_impl(const Eigen::MatrixBase<Config_t> &q, const Eigen::MatrixBase<Tangent_t> &v, const Eigen::MatrixBase<JacobianOut_t> &J, const AssignmentOperatorType op = SETTO) const
template<class Config_t, class Tangent_t, class JacobianOut_t>
inline void dIntegrate_dv_impl(const Eigen::MatrixBase<Config_t> &q, const Eigen::MatrixBase<Tangent_t> &v, const Eigen::MatrixBase<JacobianOut_t> &J, const AssignmentOperatorType op = SETTO) const
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
inline void dIntegrateTransport_dq_impl(const Eigen::MatrixBase<Config_t> &q, const Eigen::MatrixBase<Tangent_t> &v, const Eigen::MatrixBase<JacobianIn_t> &J_in, const Eigen::MatrixBase<JacobianOut_t> &J_out) const
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
inline void dIntegrateTransport_dv_impl(const Eigen::MatrixBase<Config_t> &q, const Eigen::MatrixBase<Tangent_t> &v, const Eigen::MatrixBase<JacobianIn_t> &J_in, const Eigen::MatrixBase<JacobianOut_t> &J_out) const
template<class Config_t, class Tangent_t, class Jacobian_t>
inline void dIntegrateTransport_dq_impl(const Eigen::MatrixBase<Config_t> &q, const Eigen::MatrixBase<Tangent_t> &v, const Eigen::MatrixBase<Jacobian_t> &Jin) const
template<class Config_t, class Tangent_t, class Jacobian_t>
inline void dIntegrateTransport_dv_impl(const Eigen::MatrixBase<Config_t> &q, const Eigen::MatrixBase<Tangent_t> &v, const Eigen::MatrixBase<Jacobian_t> &Jin) const
template<class ConfigL_t, class ConfigR_t>
inline Scalar squaredDistance_impl(const Eigen::MatrixBase<ConfigL_t> &q0, const Eigen::MatrixBase<ConfigR_t> &q1) const
template<class Config_t>
inline void normalize_impl(const Eigen::MatrixBase<Config_t> &qout) const
template<class Config_t>
inline bool isNormalized_impl(const Eigen::MatrixBase<Config_t> &qin, const Scalar &prec) const
template<class Config_t>
inline void random_impl(const Eigen::MatrixBase<Config_t> &qout) const
template<class ConfigL_t, class ConfigR_t, class ConfigOut_t>
inline void randomConfiguration_impl(const Eigen::MatrixBase<ConfigL_t> &lower, const Eigen::MatrixBase<ConfigR_t> &upper, const Eigen::MatrixBase<ConfigOut_t> &qout) const
template<class ConfigL_t, class ConfigR_t>
inline bool isSameConfiguration_impl(const Eigen::MatrixBase<ConfigL_t> &q0, const Eigen::MatrixBase<ConfigR_t> &q1, const Scalar &prec) const
inline bool isEqual_impl(const CartesianProductOperation &other) const

Public Members

LieGroup1 lg1
LieGroup2 lg2