|
template<ArgumentPosition arg, class ConfigL_t , class ConfigR_t , class JacobianOut_t > |
void | dDifference_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianOut_t > &J) const |
|
template<class ConfigL_t , class ConfigR_t , class Tangent_t > |
void | difference_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< Tangent_t > &d) const |
|
template<class Config_t , class Tangent_t , class JacobianOut_t > |
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 > |
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 Jacobian_t > |
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 JacobianIn_t , class JacobianOut_t > |
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 Jacobian_t > |
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 Config_t , class Tangent_t , class JacobianIn_t , class JacobianOut_t > |
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 ConfigIn_t , class Velocity_t , class ConfigOut_t > |
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 > |
void | integrateCoeffWiseJacobian_impl (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Jacobian_t > &J) const |
|
bool | isEqual_impl (const CartesianProductOperation &other) const |
|
template<class Config_t > |
bool | isNormalized_impl (const Eigen::MatrixBase< Config_t > &qin, const Scalar &prec) const |
|
template<class ConfigL_t , class ConfigR_t > |
bool | isSameConfiguration_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &prec) const |
|
std::string | name () const |
|
ConfigVector_t | neutral () const |
|
template<class Config_t > |
void | normalize_impl (const Eigen::MatrixBase< Config_t > &qout) const |
|
Index | nq () const |
|
Index | nv () const |
|
| PINOCCHIO_LIE_GROUP_TPL_PUBLIC_INTERFACE (CartesianProductOperation) |
|
template<class Config_t > |
void | random_impl (const Eigen::MatrixBase< Config_t > &qout) const |
|
template<class ConfigL_t , class ConfigR_t , class ConfigOut_t > |
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 > |
Scalar | squaredDistance_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const |
|
template<typename LieGroup1, typename LieGroup2>
struct pinocchio::CartesianProductOperation< LieGroup1, LieGroup2 >
Definition at line 31 of file cartesian-product.hpp.